From dcc1d4dafba6f6c7588cb5f7f6ca918b2a6c48ef Mon Sep 17 00:00:00 2001 From: justinIRBT <69175069+justinIRBT@users.noreply.github.com> Date: Tue, 6 Oct 2020 11:13:30 -0700 Subject: [PATCH] Fix max path cycles for case where map has larger Y dimension than X dimension (#2017) * Fix max path cycles for case where map has larger Y dimension than X dimension * Improve readability * fix ament_cpplint and ament_uncrustify issues --- nav2_navfn_planner/src/navfn_planner.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/nav2_navfn_planner/src/navfn_planner.cpp b/nav2_navfn_planner/src/navfn_planner.cpp index 2258b5e1..1b2e2d5e 100644 --- a/nav2_navfn_planner/src/navfn_planner.cpp +++ b/nav2_navfn_planner/src/navfn_planner.cpp @@ -320,7 +320,10 @@ NavfnPlanner::getPlanFromPotential( planner_->setStart(map_goal); - int path_len = planner_->calcPath(costmap_->getSizeInCellsX() * 4); + const int & max_cycles = (costmap_->getSizeInCellsX() >= costmap_->getSizeInCellsY()) ? + (costmap_->getSizeInCellsX() * 4) : (costmap_->getSizeInCellsY() * 4); + + int path_len = planner_->calcPath(max_cycles); if (path_len == 0) { return false; } -- GitLab