Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add string error_msg to all action result messages (#4341) #4459

Merged
merged 1 commit into from
Jun 24, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions nav2_msgs/action/AssistedTeleop.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
1 change: 1 addition & 0 deletions nav2_msgs/action/BackUp.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
1 change: 1 addition & 0 deletions nav2_msgs/action/ComputePathThroughPoses.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
1 change: 1 addition & 0 deletions nav2_msgs/action/ComputePathToPose.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
2 changes: 1 addition & 1 deletion nav2_msgs/action/DockRobot.action
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
1 change: 1 addition & 0 deletions nav2_msgs/action/DriveOnHeading.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
1 change: 1 addition & 0 deletions nav2_msgs/action/DummyBehavior.action
Original file line number Diff line number Diff line change
Expand Up @@ -4,5 +4,6 @@ std_msgs/String command
#result definition
builtin_interfaces/Duration total_elapsed_time
uint16 error_code
string error_msg
---
#feedback definition
2 changes: 2 additions & 0 deletions nav2_msgs/action/FollowGPSWaypoints.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
1 change: 1 addition & 0 deletions nav2_msgs/action/FollowPath.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions nav2_msgs/action/FollowWaypoints.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
1 change: 1 addition & 0 deletions nav2_msgs/action/NavigateThroughPoses.action
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ string behavior_tree
uint16 NONE=0

uint16 error_code
string error_msg
---
#feedback definition
geometry_msgs/PoseStamped current_pose
Expand Down
1 change: 1 addition & 0 deletions nav2_msgs/action/NavigateToPose.action
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ string behavior_tree
uint16 NONE=0

uint16 error_code
string error_msg
---
#feedback definition
geometry_msgs/PoseStamped current_pose
Expand Down
1 change: 1 addition & 0 deletions nav2_msgs/action/SmoothPath.action
Original file line number Diff line number Diff line change
Expand Up @@ -20,5 +20,6 @@ nav_msgs/Path path
builtin_interfaces/Duration smoothing_duration
bool was_completed
uint16 error_code
string error_msg
---
#feedback definition
1 change: 1 addition & 0 deletions nav2_msgs/action/Spin.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
2 changes: 1 addition & 1 deletion nav2_msgs/action/UndockRobot.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
1 change: 1 addition & 0 deletions nav2_msgs/action/Wait.action
Original file line number Diff line number Diff line change
Expand Up @@ -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
Loading