Skip to content

Commit 5584fc0

Browse files
committed
Call reset on new plan, not new goal
The documentation on `reset()` says: > called at the beginning of every new navigation, i.e. when we get a > new global plan The `reset()` functions were called in `setGoalPose()`, i.e. when the user gives a new goal. However, when the local planner fails and the global planner replans, `setGoalPose()` is not called, but `setPlan()` is. This commit makes sure that `reset()` is also called in this case.
1 parent c24cfa9 commit 5584fc0

File tree

1 file changed

+6
-6
lines changed

1 file changed

+6
-6
lines changed

dwb_local_planner/src/dwb_local_planner.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -161,18 +161,18 @@ void DWBLocalPlanner::setGoalPose(const nav_2d_msgs::Pose2DStamped& goal_pose)
161161
{
162162
ROS_INFO_NAMED("DWBLocalPlanner", "New Goal Received.");
163163
goal_pose_ = goal_pose;
164-
traj_generator_->reset();
165-
goal_checker_->reset();
166-
for (TrajectoryCritic::Ptr critic : critics_)
167-
{
168-
critic->reset();
169-
}
170164
}
171165

172166
void DWBLocalPlanner::setPlan(const nav_2d_msgs::Path2D& path)
173167
{
174168
pub_.publishGlobalPlan(path);
175169
global_plan_ = path;
170+
traj_generator_->reset();
171+
goal_checker_->reset();
172+
for (TrajectoryCritic::Ptr critic : critics_)
173+
{
174+
critic->reset();
175+
}
176176
}
177177

178178
nav_2d_msgs::Twist2DStamped DWBLocalPlanner::computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose,

0 commit comments

Comments
 (0)