File: art_msgs/ArtQuadrilateral.msg
# ART quadrilateral polygon
# $Id: ArtQuadrilateral.msg 614 2010-09-24 15:08:46Z jack.oquin $
# Each of these polygons is a quadrilateral. The four vertex points
# are ordered relative to the heading of the lane containing it.
geometry_msgs/Polygon poly
int32 bottom_left = 0
int32 top_left = 1
int32 top_right = 2
int32 bottom_right = 3
int32 quad_size = 4
geometry_msgs/Point midpoint # Middle of the polygon
float32 heading # average of right and left boundary headings
float32 length # length of the polygon
int32 poly_id # unique MapLanes ID
bool is_stop # this poly has a stop waypoint
bool is_transition # not a lane polygon, no waypoint
bool contains_way # both start_way and end_way are the contained waypoint
MapID start_way
MapID end_way
LaneMarking left_boundary
LaneMarking right_boundary
Expanded Definition
int32 bottom_left=0
int32 top_left=1
int32 top_right=2
int32 bottom_right=3
int32 quad_size=4
geometry_msgs/Polygon poly
geometry_msgs/Point32[] points
float32 x
float32 y
float32 z
geometry_msgs/Point midpoint
float64 x
float64 y
float64 z
float32 heading
float32 length
int32 poly_id
bool is_stop
bool is_transition
bool contains_way
MapID start_way
uint16 NULL_ID=65535
uint16 seg
uint16 lane
uint16 pt
MapID end_way
uint16 NULL_ID=65535
uint16 seg
uint16 lane
uint16 pt
LaneMarking left_boundary
int16 DOUBLE_YELLOW=0
int16 SOLID_YELLOW=1
int16 SOLID_WHITE=2
int16 BROKEN_WHITE=3
int16 UNDEFINED=4
int16 lane_marking
LaneMarking right_boundary
int16 DOUBLE_YELLOW=0
int16 SOLID_YELLOW=1
int16 SOLID_WHITE=2
int16 BROKEN_WHITE=3
int16 UNDEFINED=4
int16 lane_marking