Skip to content

Commit

Permalink
global_planner: use tolerance instead of default_tolerance_
Browse files Browse the repository at this point in the history
Instead of the tolerance parameter of makePlan the default_tolerance_
parameter was used - leading to no usage of the tolerance parameter.
  • Loading branch information
nlimpert committed Jul 5, 2019
1 parent 0f01494 commit e07ec77
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion global_planner/src/planner_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit e07ec77

Please sign in to comment.