Skip to content

Commit 318e04f

Browse files
committed
Make WaypointFollower use WaypointStatus message type in action result
Signed-off-by: zz990099 <771647586@qq.com>
1 parent 86ab643 commit 318e04f

File tree

4 files changed

+5
-5
lines changed

4 files changed

+5
-5
lines changed

nav2_msgs/action/FollowGPSWaypoints.action

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ uint16 TASK_EXECUTOR_FAILED=601
1313
uint16 NO_WAYPOINTS_GIVEN=602
1414
uint16 STOP_ON_MISSED_WAYPOINT=603
1515

16-
MissedWaypoint[] missed_waypoints
16+
WaypointStatus[] missed_waypoints
1717
int16 error_code
1818
string error_msg
1919
---

nav2_msgs/action/FollowWaypoints.action

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ uint16 TASK_EXECUTOR_FAILED=601
1313
uint16 NO_VALID_WAYPOINTS=602
1414
uint16 STOP_ON_MISSED_WAYPOINT=603
1515

16-
MissedWaypoint[] missed_waypoints
16+
WaypointStatus[] missed_waypoints
1717
uint16 error_code
1818
string error_msg
1919
---

nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
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"

nav2_waypoint_follower/src/waypoint_follower.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff 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 =

0 commit comments

Comments
 (0)