art_msgs/Order Message

File: art_msgs/Order.msg

# commander order for the navigator
# $Id: Order.msg 615 2010-09-24 16:07:50Z jack.oquin $

uint32 N_WAYPTS = 5      # number of way-points in order
uint32 N_CHKPTS = 2              # number of checkpoints in order

Behavior behavior # requested behavior
art_msgs/WayPoint[5] waypt        # way-point array
art_msgs/WayPoint[2] chkpt        # next two goal checkpoints
float32 min_speed # in meters/sec
float32 max_speed
int32 replan_num
int32 next_uturn          # Uturn between [1] and [2]

Expanded Definition

uint32 N_WAYPTS=5
uint32 N_CHKPTS=2
Behavior behavior
    int16 Abort=0
    int16 Quit=1
    int16 Pause=2
    int16 Run=3
    int16 Suspend=4
    int16 Initialize=5
    int16 Go=6
    int16 NONE=7
    int16 N_behaviors=8
    int16 value
art_msgs/WayPoint[5] waypt
    float64 latitude
    float64 longitude
    geometry_msgs/Point32 mapxy
        float32 x
        float32 y
        float32 z
    art_msgs/MapID id
        uint16 NULL_ID=65535
        uint16 seg
        uint16 lane
        uint16 pt
    uint16 index
    bool is_entry
    bool is_exit
    bool is_goal
    bool is_lane_change
    bool is_spot
    bool is_stop
    bool is_perimeter
    int32 checkpoint_id
    float32 lane_width
art_msgs/WayPoint[2] chkpt
    float64 latitude
    float64 longitude
    geometry_msgs/Point32 mapxy
        float32 x
        float32 y
        float32 z
    art_msgs/MapID id
        uint16 NULL_ID=65535
        uint16 seg
        uint16 lane
        uint16 pt
    uint16 index
    bool is_entry
    bool is_exit
    bool is_goal
    bool is_lane_change
    bool is_spot
    bool is_stop
    bool is_perimeter
    int32 checkpoint_id
    float32 lane_width
float32 min_speed
float32 max_speed
int32 replan_num
int32 next_uturn