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


art_msgs
Author(s): Jack O'Quin
autogenerated on Tue Sep 24 2013 10:40:45