File tree Expand file tree Collapse file tree 5 files changed +11
-2
lines changed
include/nav2_smac_planner Expand file tree Collapse file tree 5 files changed +11
-2
lines changed Original file line number Diff line number Diff line change @@ -73,7 +73,7 @@ class AnalyticExpansion
7373 * @brief Sets the collision checker and costmap to use in expansion validation
7474 * @param collision_checker Collision checker to use
7575 */
76- void setCollisionChecker (GridCollisionChecker * & collision_checker);
76+ void setCollisionChecker (GridCollisionChecker * collision_checker);
7777
7878 /* *
7979 * @brief Attempt an analytic path completion
Original file line number Diff line number Diff line change @@ -41,7 +41,7 @@ AnalyticExpansion<NodeT>::AnalyticExpansion(
4141
4242template <typename NodeT>
4343void AnalyticExpansion<NodeT>::setCollisionChecker(
44- GridCollisionChecker * & collision_checker)
44+ GridCollisionChecker * collision_checker)
4545{
4646 _collision_checker = collision_checker;
4747}
Original file line number Diff line number Diff line change @@ -66,6 +66,7 @@ void GridCollisionChecker::setFootprint(
6666 return ;
6767 }
6868
69+ oriented_footprints_.clear ();
6970 oriented_footprints_.reserve (angles_.size ());
7071 double sin_th, cos_th;
7172 geometry_msgs::msg::Point new_pt;
Original file line number Diff line number Diff line change @@ -338,6 +338,10 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
338338 }
339339
340340 // Set collision checker and costmap information
341+ _collision_checker.setFootprint (
342+ _costmap_ros->getRobotFootprint (),
343+ _costmap_ros->getUseRadius (),
344+ findCircumscribedCost (_costmap_ros));
341345 _a_star->setCollisionChecker (&_collision_checker);
342346
343347 // Set starting point, in A* bin search coordinates
Original file line number Diff line number Diff line change @@ -274,6 +274,10 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan(
274274 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t > lock (*(_costmap->getMutex ()));
275275
276276 // Set collision checker and costmap information
277+ _collision_checker.setFootprint (
278+ _costmap_ros->getRobotFootprint (),
279+ _costmap_ros->getUseRadius (),
280+ findCircumscribedCost (_costmap_ros));
277281 _a_star->setCollisionChecker (&_collision_checker);
278282
279283 // Set starting point, in A* bin search coordinates
You can’t perform that action at this time.
0 commit comments