ComputePathThroughPoses
This is a ROS action definition.
Source
# Error codes
# Note: The expected priority order of the errors should match the message order
uint16 NONE=0
uint16 UNKNOWN=300
uint16 INVALID_PLANNER=301
uint16 TF_ERROR=302
uint16 START_OUTSIDE_MAP=303
uint16 GOAL_OUTSIDE_MAP=304
uint16 START_OCCUPIED=305
uint16 GOAL_OCCUPIED=306
uint16 TIMEOUT=307
uint16 NO_VALID_PATH=308
uint16 NO_VIAPOINTS_GIVEN=309
#goal definition
geometry_msgs/PoseStamped[] goals
geometry_msgs/PoseStamped start
string planner_id
bool use_start # If false, use current robot pose as path start, if true, use start above instead
---
#result definition
nav_msgs/Path path
builtin_interfaces/Duration planning_time
uint16 error_code
---
#feedback definition