00001 """autogenerated by genmsg_py from ArtQuadrilateral.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004 
00005 import geometry_msgs.msg
00006 import art_msgs.msg
00007 
00008 class ArtQuadrilateral(roslib.message.Message):
00009   _md5sum = "d704c9f78f17e5d333efb87e5729a41e"
00010   _type = "art_msgs/ArtQuadrilateral"
00011   _has_header = False 
00012   _full_text = """# ART quadrilateral polygon
00013 # $Id: ArtQuadrilateral.msg 614 2010-09-24 15:08:46Z jack.oquin $
00014 
00015 # Each of these polygons is a quadrilateral.  The four vertex points
00016 # are ordered relative to the heading of the lane containing it.
00017 
00018 geometry_msgs/Polygon poly
00019 int32 bottom_left  = 0
00020 int32 top_left     = 1
00021 int32 top_right    = 2
00022 int32 bottom_right = 3
00023 int32 quad_size = 4
00024 
00025 geometry_msgs/Point midpoint # Middle of the polygon
00026 
00027 float32 heading         # average of right and left boundary headings
00028 float32 length          # length of the polygon
00029 int32 poly_id           # unique MapLanes ID
00030 
00031 bool is_stop            # this poly has a stop waypoint
00032 bool is_transition      # not a lane polygon, no waypoint
00033 bool contains_way       # both start_way and end_way are the contained waypoint
00034 
00035 MapID start_way
00036 MapID end_way
00037 
00038 LaneMarking left_boundary
00039 LaneMarking right_boundary
00040 
00041 ================================================================================
00042 MSG: geometry_msgs/Polygon
00043 #A specification of a polygon where the first and last points are assumed to be connected
00044 geometry_msgs/Point32[] points
00045 
00046 ================================================================================
00047 MSG: geometry_msgs/Point32
00048 # This contains the position of a point in free space(with 32 bits of precision).
00049 # It is recommeded to use Point wherever possible instead of Point32.  
00050 # 
00051 # This recommendation is to promote interoperability.  
00052 #
00053 # This message is designed to take up less space when sending
00054 # lots of points at once, as in the case of a PointCloud.  
00055 
00056 float32 x
00057 float32 y
00058 float32 z
00059 ================================================================================
00060 MSG: geometry_msgs/Point
00061 # This contains the position of a point in free space
00062 float64 x
00063 float64 y
00064 float64 z
00065 
00066 ================================================================================
00067 MSG: art_msgs/MapID
00068 # Road map identifier for segments, lanes and way-points.
00069 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $
00070 
00071 uint16 NULL_ID = 65535
00072 
00073 uint16 seg      # segment ID
00074 uint16 lane     # lane ID
00075 uint16 pt       # way-point ID
00076 
00077 ================================================================================
00078 MSG: art_msgs/LaneMarking
00079 # Route Network Definition File lane marking
00080 # $Id: LaneMarking.msg 614 2010-09-24 15:08:46Z jack.oquin $
00081 
00082 int16 DOUBLE_YELLOW = 0
00083 int16 SOLID_YELLOW = 1
00084 int16 SOLID_WHITE = 2
00085 int16 BROKEN_WHITE = 3
00086 int16 UNDEFINED = 4
00087 
00088 int16 lane_marking
00089 
00090 """
00091   
00092   bottom_left = 0
00093   top_left = 1
00094   top_right = 2
00095   bottom_right = 3
00096   quad_size = 4
00097 
00098   __slots__ = ['poly','midpoint','heading','length','poly_id','is_stop','is_transition','contains_way','start_way','end_way','left_boundary','right_boundary']
00099   _slot_types = ['geometry_msgs/Polygon','geometry_msgs/Point','float32','float32','int32','bool','bool','bool','art_msgs/MapID','art_msgs/MapID','art_msgs/LaneMarking','art_msgs/LaneMarking']
00100 
00101   def __init__(self, *args, **kwds):
00102     """
00103     Constructor. Any message fields that are implicitly/explicitly
00104     set to None will be assigned a default value. The recommend
00105     use is keyword arguments as this is more robust to future message
00106     changes.  You cannot mix in-order arguments and keyword arguments.
00107     
00108     The available fields are:
00109        poly,midpoint,heading,length,poly_id,is_stop,is_transition,contains_way,start_way,end_way,left_boundary,right_boundary
00110     
00111     @param args: complete set of field values, in .msg order
00112     @param kwds: use keyword arguments corresponding to message field names
00113     to set specific fields. 
00114     """
00115     if args or kwds:
00116       super(ArtQuadrilateral, self).__init__(*args, **kwds)
00117       
00118       if self.poly is None:
00119         self.poly = geometry_msgs.msg.Polygon()
00120       if self.midpoint is None:
00121         self.midpoint = geometry_msgs.msg.Point()
00122       if self.heading is None:
00123         self.heading = 0.
00124       if self.length is None:
00125         self.length = 0.
00126       if self.poly_id is None:
00127         self.poly_id = 0
00128       if self.is_stop is None:
00129         self.is_stop = False
00130       if self.is_transition is None:
00131         self.is_transition = False
00132       if self.contains_way is None:
00133         self.contains_way = False
00134       if self.start_way is None:
00135         self.start_way = art_msgs.msg.MapID()
00136       if self.end_way is None:
00137         self.end_way = art_msgs.msg.MapID()
00138       if self.left_boundary is None:
00139         self.left_boundary = art_msgs.msg.LaneMarking()
00140       if self.right_boundary is None:
00141         self.right_boundary = art_msgs.msg.LaneMarking()
00142     else:
00143       self.poly = geometry_msgs.msg.Polygon()
00144       self.midpoint = geometry_msgs.msg.Point()
00145       self.heading = 0.
00146       self.length = 0.
00147       self.poly_id = 0
00148       self.is_stop = False
00149       self.is_transition = False
00150       self.contains_way = False
00151       self.start_way = art_msgs.msg.MapID()
00152       self.end_way = art_msgs.msg.MapID()
00153       self.left_boundary = art_msgs.msg.LaneMarking()
00154       self.right_boundary = art_msgs.msg.LaneMarking()
00155 
00156   def _get_types(self):
00157     """
00158     internal API method
00159     """
00160     return self._slot_types
00161 
00162   def serialize(self, buff):
00163     """
00164     serialize message into buffer
00165     @param buff: buffer
00166     @type  buff: StringIO
00167     """
00168     try:
00169       length = len(self.poly.points)
00170       buff.write(_struct_I.pack(length))
00171       for val1 in self.poly.points:
00172         _x = val1
00173         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00174       _x = self
00175       buff.write(_struct_3d2fi3B6H2h.pack(_x.midpoint.x, _x.midpoint.y, _x.midpoint.z, _x.heading, _x.length, _x.poly_id, _x.is_stop, _x.is_transition, _x.contains_way, _x.start_way.seg, _x.start_way.lane, _x.start_way.pt, _x.end_way.seg, _x.end_way.lane, _x.end_way.pt, _x.left_boundary.lane_marking, _x.right_boundary.lane_marking))
00176     except struct.error, se: self._check_types(se)
00177     except TypeError, te: self._check_types(te)
00178 
00179   def deserialize(self, str):
00180     """
00181     unpack serialized message in str into this message instance
00182     @param str: byte array of serialized message
00183     @type  str: str
00184     """
00185     try:
00186       if self.poly is None:
00187         self.poly = geometry_msgs.msg.Polygon()
00188       if self.midpoint is None:
00189         self.midpoint = geometry_msgs.msg.Point()
00190       if self.start_way is None:
00191         self.start_way = art_msgs.msg.MapID()
00192       if self.end_way is None:
00193         self.end_way = art_msgs.msg.MapID()
00194       if self.left_boundary is None:
00195         self.left_boundary = art_msgs.msg.LaneMarking()
00196       if self.right_boundary is None:
00197         self.right_boundary = art_msgs.msg.LaneMarking()
00198       end = 0
00199       start = end
00200       end += 4
00201       (length,) = _struct_I.unpack(str[start:end])
00202       self.poly.points = []
00203       for i in xrange(0, length):
00204         val1 = geometry_msgs.msg.Point32()
00205         _x = val1
00206         start = end
00207         end += 12
00208         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00209         self.poly.points.append(val1)
00210       _x = self
00211       start = end
00212       end += 55
00213       (_x.midpoint.x, _x.midpoint.y, _x.midpoint.z, _x.heading, _x.length, _x.poly_id, _x.is_stop, _x.is_transition, _x.contains_way, _x.start_way.seg, _x.start_way.lane, _x.start_way.pt, _x.end_way.seg, _x.end_way.lane, _x.end_way.pt, _x.left_boundary.lane_marking, _x.right_boundary.lane_marking,) = _struct_3d2fi3B6H2h.unpack(str[start:end])
00214       self.is_stop = bool(self.is_stop)
00215       self.is_transition = bool(self.is_transition)
00216       self.contains_way = bool(self.contains_way)
00217       return self
00218     except struct.error, e:
00219       raise roslib.message.DeserializationError(e) 
00220 
00221 
00222   def serialize_numpy(self, buff, numpy):
00223     """
00224     serialize message with numpy array types into buffer
00225     @param buff: buffer
00226     @type  buff: StringIO
00227     @param numpy: numpy python module
00228     @type  numpy module
00229     """
00230     try:
00231       length = len(self.poly.points)
00232       buff.write(_struct_I.pack(length))
00233       for val1 in self.poly.points:
00234         _x = val1
00235         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00236       _x = self
00237       buff.write(_struct_3d2fi3B6H2h.pack(_x.midpoint.x, _x.midpoint.y, _x.midpoint.z, _x.heading, _x.length, _x.poly_id, _x.is_stop, _x.is_transition, _x.contains_way, _x.start_way.seg, _x.start_way.lane, _x.start_way.pt, _x.end_way.seg, _x.end_way.lane, _x.end_way.pt, _x.left_boundary.lane_marking, _x.right_boundary.lane_marking))
00238     except struct.error, se: self._check_types(se)
00239     except TypeError, te: self._check_types(te)
00240 
00241   def deserialize_numpy(self, str, numpy):
00242     """
00243     unpack serialized message in str into this message instance using numpy for array types
00244     @param str: byte array of serialized message
00245     @type  str: str
00246     @param numpy: numpy python module
00247     @type  numpy: module
00248     """
00249     try:
00250       if self.poly is None:
00251         self.poly = geometry_msgs.msg.Polygon()
00252       if self.midpoint is None:
00253         self.midpoint = geometry_msgs.msg.Point()
00254       if self.start_way is None:
00255         self.start_way = art_msgs.msg.MapID()
00256       if self.end_way is None:
00257         self.end_way = art_msgs.msg.MapID()
00258       if self.left_boundary is None:
00259         self.left_boundary = art_msgs.msg.LaneMarking()
00260       if self.right_boundary is None:
00261         self.right_boundary = art_msgs.msg.LaneMarking()
00262       end = 0
00263       start = end
00264       end += 4
00265       (length,) = _struct_I.unpack(str[start:end])
00266       self.poly.points = []
00267       for i in xrange(0, length):
00268         val1 = geometry_msgs.msg.Point32()
00269         _x = val1
00270         start = end
00271         end += 12
00272         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00273         self.poly.points.append(val1)
00274       _x = self
00275       start = end
00276       end += 55
00277       (_x.midpoint.x, _x.midpoint.y, _x.midpoint.z, _x.heading, _x.length, _x.poly_id, _x.is_stop, _x.is_transition, _x.contains_way, _x.start_way.seg, _x.start_way.lane, _x.start_way.pt, _x.end_way.seg, _x.end_way.lane, _x.end_way.pt, _x.left_boundary.lane_marking, _x.right_boundary.lane_marking,) = _struct_3d2fi3B6H2h.unpack(str[start:end])
00278       self.is_stop = bool(self.is_stop)
00279       self.is_transition = bool(self.is_transition)
00280       self.contains_way = bool(self.contains_way)
00281       return self
00282     except struct.error, e:
00283       raise roslib.message.DeserializationError(e) 
00284 
00285 _struct_I = roslib.message.struct_I
00286 _struct_3d2fi3B6H2h = struct.Struct("<3d2fi3B6H2h")
00287 _struct_3f = struct.Struct("<3f")