From e07ec7777578b77cc5fd4d48b4574124d0f21533 Mon Sep 17 00:00:00 2001 From: Nicolas Limpert Date: Fri, 30 Mar 2018 11:06:22 +0200 Subject: [PATCH] global_planner: use tolerance instead of default_tolerance_ Instead of the tolerance parameter of makePlan the default_tolerance_ parameter was used - leading to no usage of the tolerance parameter. --- global_planner/src/planner_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/global_planner/src/planner_core.cpp b/global_planner/src/planner_core.cpp index 1915680e9..d22575f23 100644 --- a/global_planner/src/planner_core.cpp +++ b/global_planner/src/planner_core.cpp @@ -280,7 +280,7 @@ bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geom int width = (int) costmap_->getSizeInCellsX(); int height = (int) costmap_->getSizeInCellsY(); - int max_num_cells = default_tolerance_ / costmap_->getResolution(); + int max_num_cells = tolerance / costmap_->getResolution(); unsigned int offset_x = 0; unsigned int offset_y = 0;