GetPath

This is a ROS action definition.

Source

# Get a path from start_pose or current position to the target pose

# Use start_pose or current position as the beginning of the path
bool use_start_pose

# The start pose for the path; optional, used if use_start_pose is true
geometry_msgs/PoseStamped start_pose

# The pose to achieve with the path
geometry_msgs/PoseStamped target_pose

# If the goal is obstructed, how many meters the planner can relax the constraint in x and y before failing
float64 tolerance

# Planner to use; defaults to the first one specified on "planners" parameter
string planner

# use different slots for concurrency
uint8 concurrency_slot

---

# Predefined success codes:
uint8 SUCCESS           = 0
# 1..9 are reserved as plugin specific non-error results

# Possible error codes:
uint8 FAILURE           = 50  # Unspecified failure, only used for old, non-mfb_core based plugins
uint8 CANCELED          = 51  # The action has been canceled by a action client
uint8 INVALID_START     = 52  # The start pose is inconsistent (e.g. frame is not valid)
uint8 INVALID_GOAL      = 53  # The goal pose is inconsistent (e.g. frame is not valid)
uint8 BLOCKED_START     = 54  # The start pose is in collision
uint8 BLOCKED_GOAL      = 55  # The goal pose is in collision
uint8 NO_PATH_FOUND     = 56
uint8 PAT_EXCEEDED      = 57
uint8 EMPTY_PATH        = 58
uint8 TF_ERROR          = 59
uint8 NOT_INITIALIZED   = 60
uint8 INVALID_PLUGIN    = 61
uint8 INTERNAL_ERROR    = 62
uint8 OUT_OF_MAP        = 63  # The start and / or the goal are outside the map
uint8 MAP_ERROR         = 64  # The map is not available or not running properly
uint8 STOPPED           = 65  # The planner execution has been stopped rigorously

uint8 ERROR_RANGE_START = 50
uint8 ERROR_RANGE_END   = 99

# 71..99 are reserved as plugin specific errors:
uint8 PLUGIN_ERROR_RANGE_START = 71
uint8 PLUGIN_ERROR_RANGE_END   = 99

uint32 outcome
string message

nav_msgs/Path path

float64 cost

---