61 lines
1.6 KiB
Plaintext
Executable File
61 lines
1.6 KiB
Plaintext
Executable File
# Follow the given path until completion or failure
|
|
|
|
nav_msgs/Path path
|
|
|
|
# Controller to use; defaults to the first one specified on "controllers" parameter
|
|
string controller
|
|
|
|
# use different slots for concurrency
|
|
uint8 concurrency_slot
|
|
|
|
# Optionally overrule goal tolerances
|
|
bool tolerance_from_action
|
|
float32 dist_tolerance
|
|
float32 angle_tolerance
|
|
|
|
---
|
|
|
|
# Predefined success codes:
|
|
uint8 SUCCESS = 0
|
|
# 1..9 are reserved as plugin specific non-error results
|
|
|
|
# Predefined error codes:
|
|
uint8 FAILURE = 100 # Unspecified failure, only used for old, non-mfb_core based plugins
|
|
uint8 CANCELED = 101
|
|
uint8 NO_VALID_CMD = 102
|
|
uint8 PAT_EXCEEDED = 103
|
|
uint8 COLLISION = 104
|
|
uint8 OSCILLATION = 105
|
|
uint8 ROBOT_STUCK = 106
|
|
uint8 MISSED_GOAL = 107
|
|
uint8 MISSED_PATH = 108
|
|
uint8 BLOCKED_PATH = 109
|
|
uint8 INVALID_PATH = 110
|
|
uint8 TF_ERROR = 111
|
|
uint8 NOT_INITIALIZED = 112
|
|
uint8 INVALID_PLUGIN = 113
|
|
uint8 INTERNAL_ERROR = 114
|
|
uint8 OUT_OF_MAP = 115 # The start and / or the goal are outside the map
|
|
uint8 MAP_ERROR = 116 # The map is not running properly
|
|
uint8 STOPPED = 117 # The controller execution has been stopped rigorously.
|
|
|
|
# 121..149 are reserved as plugin specific errors
|
|
|
|
uint32 outcome
|
|
string message
|
|
|
|
geometry_msgs/PoseStamped final_pose
|
|
float32 dist_to_goal
|
|
float32 angle_to_goal
|
|
|
|
---
|
|
|
|
# Outcome of most recent controller cycle. Same values as in result
|
|
uint32 outcome
|
|
string message
|
|
|
|
float32 dist_to_goal
|
|
float32 angle_to_goal
|
|
geometry_msgs/PoseStamped current_pose
|
|
geometry_msgs/TwistStamped last_cmd_vel # last command calculated by the controller
|