diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index 949b3cd73b..acf518100b 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -356,7 +356,10 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan( expansions = std::make_unique>>(); } // Note: All exceptions thrown are handled by the planner server and returned to the action - if (!_a_star->createPath(path, num_iterations, 0, expansions.get())) { + if (!_a_star->createPath( + path, num_iterations, + _tolerance / static_cast(costmap->getResolution()), expansions.get())) + { if (num_iterations < _a_star->getMaxIterations()) { throw nav2_core::NoValidPathCouldBeFound("no valid path found"); } else { diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 66ddd95d74..8b46fc3ae7 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -284,7 +284,9 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( std::string error; // Note: All exceptions thrown are handled by the planner server and returned to the action - if (!_a_star->createPath(path, num_iterations, 0 /*no tolerance*/)) { + if (!_a_star->createPath( + path, num_iterations, _tolerance / static_cast(_costmap->getResolution()))) + { if (num_iterations < _a_star->getMaxIterations()) { throw nav2_core::NoValidPathCouldBeFound("no valid path found"); } else {