File tree Expand file tree Collapse file tree 3 files changed +9
-0
lines changed Expand file tree Collapse file tree 3 files changed +9
-0
lines changed Original file line number Diff line number Diff line change @@ -62,6 +62,7 @@ void GridCollisionChecker::setFootprint(
6262 return ;
6363 }
6464
65+ oriented_footprints_.clear ();
6566 oriented_footprints_.reserve (angles_.size ());
6667 double sin_th, cos_th;
6768 geometry_msgs::msg::Point new_pt;
Original file line number Diff line number Diff line change @@ -304,6 +304,10 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
304304 }
305305
306306 // Set collision checker and costmap information
307+ _collision_checker.setFootprint (
308+ _costmap_ros->getRobotFootprint (),
309+ _costmap_ros->getUseRadius (),
310+ findCircumscribedCost (_costmap_ros));
307311 _a_star->setCollisionChecker (&_collision_checker);
308312
309313 // Set starting point, in A* bin search coordinates
Original file line number Diff line number Diff line change @@ -243,6 +243,10 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan(
243243 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t > lock (*(_costmap->getMutex ()));
244244
245245 // Set collision checker and costmap information
246+ _collision_checker.setFootprint (
247+ _costmap_ros->getRobotFootprint (),
248+ _costmap_ros->getUseRadius (),
249+ findCircumscribedCost (_costmap_ros));
246250 _a_star->setCollisionChecker (&_collision_checker);
247251
248252 // Set starting point, in A* bin search coordinates
You can’t perform that action at this time.
0 commit comments