diff --git a/nav2_msgs/action/AssistedTeleop.action b/nav2_msgs/action/AssistedTeleop.action index 8737bdd0cd..20019f1935 100644 --- a/nav2_msgs/action/AssistedTeleop.action +++ b/nav2_msgs/action/AssistedTeleop.action @@ -12,6 +12,7 @@ uint16 TF_ERROR=732 builtin_interfaces/Duration total_elapsed_time uint16 error_code +string error_msg --- #feedback builtin_interfaces/Duration current_teleop_duration diff --git a/nav2_msgs/action/BackUp.action b/nav2_msgs/action/BackUp.action index 28711bfa5d..9be1d56988 100644 --- a/nav2_msgs/action/BackUp.action +++ b/nav2_msgs/action/BackUp.action @@ -17,6 +17,7 @@ uint16 COLLISION_AHEAD=714 builtin_interfaces/Duration total_elapsed_time uint16 error_code +string error_msg --- #feedback definition float32 distance_traveled diff --git a/nav2_msgs/action/ComputePathThroughPoses.action b/nav2_msgs/action/ComputePathThroughPoses.action index 8a81f6f954..bedd939679 100644 --- a/nav2_msgs/action/ComputePathThroughPoses.action +++ b/nav2_msgs/action/ComputePathThroughPoses.action @@ -23,5 +23,6 @@ uint16 NO_VIAPOINTS_GIVEN=309 nav_msgs/Path path builtin_interfaces/Duration planning_time uint16 error_code +string error_msg --- #feedback definition diff --git a/nav2_msgs/action/ComputePathToPose.action b/nav2_msgs/action/ComputePathToPose.action index ef8b20d307..572a9b5b5a 100644 --- a/nav2_msgs/action/ComputePathToPose.action +++ b/nav2_msgs/action/ComputePathToPose.action @@ -22,5 +22,6 @@ uint16 NO_VALID_PATH=208 nav_msgs/Path path builtin_interfaces/Duration planning_time uint16 error_code +string error_msg --- #feedback definition diff --git a/nav2_msgs/action/DockRobot.action b/nav2_msgs/action/DockRobot.action index fc85e6cca9..e3e2fbf78c 100644 --- a/nav2_msgs/action/DockRobot.action +++ b/nav2_msgs/action/DockRobot.action @@ -26,7 +26,7 @@ uint16 UNKNOWN=999 bool success True # docking success status uint16 error_code 0 # Contextual error code, if any uint16 num_retries 0 # Number of retries attempted - +string error_msg --- #feedback definition diff --git a/nav2_msgs/action/DriveOnHeading.action b/nav2_msgs/action/DriveOnHeading.action index 67d2badeef..a9bc79710d 100644 --- a/nav2_msgs/action/DriveOnHeading.action +++ b/nav2_msgs/action/DriveOnHeading.action @@ -17,6 +17,7 @@ uint16 INVALID_INPUT=724 builtin_interfaces/Duration total_elapsed_time uint16 error_code +string error_msg --- #feedback definition float32 distance_traveled diff --git a/nav2_msgs/action/DummyBehavior.action b/nav2_msgs/action/DummyBehavior.action index 2b90ea781a..b031ef7e1a 100644 --- a/nav2_msgs/action/DummyBehavior.action +++ b/nav2_msgs/action/DummyBehavior.action @@ -4,5 +4,6 @@ std_msgs/String command #result definition builtin_interfaces/Duration total_elapsed_time uint16 error_code +string error_msg --- #feedback definition diff --git a/nav2_msgs/action/FollowGPSWaypoints.action b/nav2_msgs/action/FollowGPSWaypoints.action index 707e9a2b37..f4f3aafba4 100644 --- a/nav2_msgs/action/FollowGPSWaypoints.action +++ b/nav2_msgs/action/FollowGPSWaypoints.action @@ -12,6 +12,8 @@ uint16 UNKNOWN=600 uint16 TASK_EXECUTOR_FAILED=601 MissedWaypoint[] missed_waypoints +int16 error_code +string error_msg --- #feedback uint32 current_waypoint diff --git a/nav2_msgs/action/FollowPath.action b/nav2_msgs/action/FollowPath.action index 654e43192e..49f04e2139 100644 --- a/nav2_msgs/action/FollowPath.action +++ b/nav2_msgs/action/FollowPath.action @@ -19,6 +19,7 @@ uint16 NO_VALID_CONTROL=106 std_msgs/Empty result uint16 error_code +string error_msg --- #feedback definition float32 distance_to_goal diff --git a/nav2_msgs/action/FollowWaypoints.action b/nav2_msgs/action/FollowWaypoints.action index a8706cd59c..9b5d8af05f 100644 --- a/nav2_msgs/action/FollowWaypoints.action +++ b/nav2_msgs/action/FollowWaypoints.action @@ -12,6 +12,8 @@ uint16 UNKNOWN=600 uint16 TASK_EXECUTOR_FAILED=601 MissedWaypoint[] missed_waypoints +uint16 error_code +string error_msg --- #feedback definition uint32 current_waypoint diff --git a/nav2_msgs/action/NavigateThroughPoses.action b/nav2_msgs/action/NavigateThroughPoses.action index efc4767306..898e4540ef 100644 --- a/nav2_msgs/action/NavigateThroughPoses.action +++ b/nav2_msgs/action/NavigateThroughPoses.action @@ -10,6 +10,7 @@ string behavior_tree uint16 NONE=0 uint16 error_code +string error_msg --- #feedback definition geometry_msgs/PoseStamped current_pose diff --git a/nav2_msgs/action/NavigateToPose.action b/nav2_msgs/action/NavigateToPose.action index c3c25c9fee..daec275662 100644 --- a/nav2_msgs/action/NavigateToPose.action +++ b/nav2_msgs/action/NavigateToPose.action @@ -9,6 +9,7 @@ string behavior_tree uint16 NONE=0 uint16 error_code +string error_msg --- #feedback definition geometry_msgs/PoseStamped current_pose diff --git a/nav2_msgs/action/SmoothPath.action b/nav2_msgs/action/SmoothPath.action index 8b04d1d104..9c42be999a 100644 --- a/nav2_msgs/action/SmoothPath.action +++ b/nav2_msgs/action/SmoothPath.action @@ -20,5 +20,6 @@ nav_msgs/Path path builtin_interfaces/Duration smoothing_duration bool was_completed uint16 error_code +string error_msg --- #feedback definition diff --git a/nav2_msgs/action/Spin.action b/nav2_msgs/action/Spin.action index 945a16d3d6..91288cbf20 100644 --- a/nav2_msgs/action/Spin.action +++ b/nav2_msgs/action/Spin.action @@ -14,6 +14,7 @@ uint16 COLLISION_AHEAD=703 builtin_interfaces/Duration total_elapsed_time uint16 error_code +string error_msg --- #feedback definition float32 angular_distance_traveled diff --git a/nav2_msgs/action/UndockRobot.action b/nav2_msgs/action/UndockRobot.action index 4ab21a75dd..6174783060 100644 --- a/nav2_msgs/action/UndockRobot.action +++ b/nav2_msgs/action/UndockRobot.action @@ -20,6 +20,6 @@ uint16 UNKNOWN=999 bool success True # docking success status uint16 error_code 0 # Contextual error code, if any - +string error_msg --- #feedback definition diff --git a/nav2_msgs/action/Wait.action b/nav2_msgs/action/Wait.action index 4657a7daa2..e7a5dc261a 100644 --- a/nav2_msgs/action/Wait.action +++ b/nav2_msgs/action/Wait.action @@ -4,6 +4,7 @@ builtin_interfaces/Duration time #result definition builtin_interfaces/Duration total_elapsed_time uint16 error_code +string error_msg --- #feedback definition builtin_interfaces/Duration time_left