File tree Expand file tree Collapse file tree 4 files changed +5
-5
lines changed
include/nav2_waypoint_follower Expand file tree Collapse file tree 4 files changed +5
-5
lines changed Original file line number Diff line number Diff line change @@ -13,7 +13,7 @@ uint16 TASK_EXECUTOR_FAILED=601
1313uint16 NO_WAYPOINTS_GIVEN =602
1414uint16 STOP_ON_MISSED_WAYPOINT =603
1515
16- MissedWaypoint [] missed_waypoints
16+ WaypointStatus [] missed_waypoints
1717int16 error_code
1818string error_msg
1919---
Original file line number Diff line number Diff line change @@ -13,7 +13,7 @@ uint16 TASK_EXECUTOR_FAILED=601
1313uint16 NO_VALID_WAYPOINTS =602
1414uint16 STOP_ON_MISSED_WAYPOINT =603
1515
16- MissedWaypoint [] missed_waypoints
16+ WaypointStatus [] missed_waypoints
1717uint16 error_code
1818string error_msg
1919---
Original file line number Diff line number Diff line change 2727#include " nav2_util/lifecycle_node.hpp"
2828#include " nav2_msgs/action/navigate_to_pose.hpp"
2929#include " nav2_msgs/action/follow_waypoints.hpp"
30- #include " nav2_msgs/msg/missed_waypoint .hpp"
30+ #include " nav2_msgs/msg/waypoint_status .hpp"
3131#include " nav_msgs/msg/path.hpp"
3232#include " nav2_util/simple_action_server.hpp"
3333#include " nav2_util/node_utils.hpp"
Original file line number Diff line number Diff line change @@ -305,7 +305,7 @@ void WaypointFollower::followWaypointsHandler(
305305 current_goal_status_.status == ActionStatus::FAILED ||
306306 current_goal_status_.status == ActionStatus::UNKNOWN)
307307 {
308- nav2_msgs::msg::MissedWaypoint missedWaypoint;
308+ nav2_msgs::msg::WaypointStatus missedWaypoint;
309309 missedWaypoint.index = goal_index;
310310 missedWaypoint.goal = poses[goal_index];
311311 missedWaypoint.error_code = current_goal_status_.error_code ;
@@ -340,7 +340,7 @@ void WaypointFollower::followWaypointsHandler(
340340 is_task_executed ? " succeeded" : " failed!" );
341341
342342 if (!is_task_executed) {
343- nav2_msgs::msg::MissedWaypoint missedWaypoint;
343+ nav2_msgs::msg::WaypointStatus missedWaypoint;
344344 missedWaypoint.index = goal_index;
345345 missedWaypoint.goal = poses[goal_index];
346346 missedWaypoint.error_code =
You can’t perform that action at this time.
0 commit comments