git commit -m "first commit"

This commit is contained in:
2026-05-28 10:29:58 +07:00
commit 167c52aeb6
2048 changed files with 740251 additions and 0 deletions

View File

@@ -0,0 +1,60 @@
# 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

View File

@@ -0,0 +1,55 @@
# 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
# Planner to use; defaults to the first one specified on "planners" parameter
string planner
# use different slots for concurrency
uint8 concurrency_slot
# Optional: how many meters/radians away from the goal can end the created path. The final pose of the
# path must be within tolerance range (position and orientation) for MBF to return a success outcome.
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
# 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 #
uint8 INVALID_GOAL = 53
uint8 NO_PATH_FOUND = 54
uint8 PAT_EXCEEDED = 55
uint8 EMPTY_PATH = 56
uint8 TF_ERROR = 57
uint8 NOT_INITIALIZED = 58
uint8 INVALID_PLUGIN = 59
uint8 INTERNAL_ERROR = 60
uint8 OUT_OF_MAP = 61
uint8 MAP_ERROR = 62
uint8 STOPPED = 63 # The planner execution has been stopped rigorously.
# 71..99 are reserved as plugin specific errors
uint32 outcome
string message
nav_msgs/Path path
float64 cost
---

View File

@@ -0,0 +1,60 @@
# Extension of move_base_msgs/MoveBase action, with more detailed result
# and feedback and the possibility to specify lists of applicable plugins
geometry_msgs/PoseStamped target_pose
# Controller to use; defaults to the first one specified on "controllers" parameter
string controller
# Planner to use; defaults to the first one specified on "planners" parameter
string planner
# Recovery behaviors to try on case of failure; defaults to the "recovery_behaviors" parameter value
string[] recovery_behaviors
# Optionally overrule controller's goal tolerances
bool tolerance_from_action
float32 dist_tolerance
float32 angle_tolerance
---
# Predefined success codes:
uint8 SUCCESS = 0
# Predefined general error codes:
uint8 FAILURE = 10
uint8 CANCELED = 11
uint8 COLLISION = 12
uint8 OSCILLATION = 13
uint8 START_BLOCKED = 14
uint8 GOAL_BLOCKED = 15
uint8 TF_ERROR = 16
uint8 INTERNAL_ERROR = 17
# 21..49 are reserved for future general error codes
# Planning/controlling failures:
uint8 PLAN_FAILURE = 50
# 51..99 are reserved as planner specific errors
uint8 CTRL_FAILURE = 100
# 101..149 are reserved as controller specific errors
uint32 outcome
string message
# Configuration upon action completion
float32 dist_to_goal
float32 angle_to_goal
geometry_msgs/PoseStamped final_pose
---
# Outcome of most recent controller cycle. Same values as in MoveBase or ExePath 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

View File

@@ -0,0 +1,30 @@
# Run one of the recovery behavior listed on recovery_behaviors parameter
string behavior
# use different slots for concurrency
uint8 concurrency_slot
---
# Predefined success codes:
uint8 SUCCESS = 0
# Possible server codes:
uint8 FAILURE = 150
uint8 CANCELED = 151
uint8 PAT_EXCEEDED = 152
uint8 TF_ERROR = 153
uint8 NOT_INITIALIZED = 154
uint8 INVALID_PLUGIN = 155
uint8 INTERNAL_ERROR = 156
uint8 STOPPED = 157 # The recovery behaviour execution has been stopped rigorously.
uint8 IMPASSABLE = 158 # Further execution would lead to a collision
# 171..199 are reserved as plugin specific errors
uint32 outcome
string message
string used_plugin
---