art_msgs/WayPoint Message

File: art_msgs/WayPoint.msg

# Way-point attributes
# $Id: WayPoint.msg 614 2010-09-24 15:08:46Z jack.oquin $

float64 latitude # latitude in degrees
float64 longitude # longitude in degrees
geometry_msgs/Point32 mapxy # MapXY position
MapID id # way-point ID
uint16 index     # parser index of waypoint

# way-point flags
bool is_entry                           # lane or zone exit point
bool is_exit # lane or zone entry point
bool is_goal # this is a goal checkpoint
bool is_lane_change # change lanes after here
bool is_spot # parking spot
bool is_stop # stop line here
bool is_perimeter # zone perimeter point
int32 checkpoint_id # checkpoint ID or zero
float32 lane_width

Expanded Definition

float64 latitude
float64 longitude
geometry_msgs/Point32 mapxy
    float32 x
    float32 y
    float32 z
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