Skip to content

Commit

Permalink
Fix zero waypoints crash (ros-navigation#1978)
Browse files Browse the repository at this point in the history
* return if the number of waypoints is zero.

* terminate the action.

* Succeed action instead of terminating.
  • Loading branch information
wilcobonestroo authored and ruffsl committed Jul 2, 2021
1 parent 02f4149 commit aef8b36
Showing 1 changed file with 5 additions and 0 deletions.
5 changes: 5 additions & 0 deletions nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,11 @@ WaypointFollower::followWaypoints()
get_logger(), "Received follow waypoint request with %i waypoints.",
static_cast<int>(goal->poses.size()));

if (goal->poses.size() == 0) {
action_server_->succeeded_current(result);
return;
}

rclcpp::Rate r(loop_rate_);
uint32_t goal_index = 0;
bool new_goal = true;
Expand Down

0 comments on commit aef8b36

Please sign in to comment.