art_msgs/NavigatorState Message

File: art_msgs/NavigatorState.msg

# navigator state message
# $Id: NavigatorState.msg 615 2010-09-24 16:07:50Z jack.oquin $

Header header

EstopState estop
RoadState road

art_msgs/MapID last_waypt # last way-point reached
art_msgs/MapID replan_waypt # next way-point for replan

int32 cur_poly                          # current polygon, -1 if none

# status flags
bool alarm
bool flasher
bool lane_blocked
bool road_blocked
bool reverse
bool signal_left
bool signal_right
bool stopped
bool have_zones

Order last_order # last commander order received

Expanded Definition

Header header
    uint32 seq
    time stamp
    string frame_id
EstopState estop
    uint16 Pause=0
    uint16 Run=1
    uint16 Done=2
    uint16 Suspend=3
    uint16 N_states=4
    uint16 state
RoadState road
    uint16 Init=0
    uint16 Block=1
    uint16 Evade=2
    uint16 Follow=3
    uint16 Pass=4
    uint16 Uturn=5
    uint16 WaitCross=6
    uint16 WaitLane=7
    uint16 WaitPass=8
    uint16 WaitStop=9
    uint16 Zone=10
    uint16 N_states=11
    uint16 state
art_msgs/MapID last_waypt
    uint16 NULL_ID=65535
    uint16 seg
    uint16 lane
    uint16 pt
art_msgs/MapID replan_waypt
    uint16 NULL_ID=65535
    uint16 seg
    uint16 lane
    uint16 pt
int32 cur_poly
bool alarm
bool flasher
bool lane_blocked
bool road_blocked
bool reverse
bool signal_left
bool signal_right
bool stopped
bool have_zones
Order last_order
    uint32 N_WAYPTS=5
    uint32 N_CHKPTS=2
    art_msgs/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