00001 """autogenerated by genpy from art_msgs/ArtLanes.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 import std_msgs.msg
00010
00011 class ArtLanes(genpy.Message):
00012 _md5sum = "384de56fb723b4265b396fcf86b17531"
00013 _type = "art_msgs/ArtLanes"
00014 _has_header = True
00015 _full_text = """# ART lanes message
00016 # $Id: ArtLanes.msg 614 2010-09-24 15:08:46Z jack.oquin $
00017
00018 Header header
00019 ArtQuadrilateral[] polygons
00020
00021 ================================================================================
00022 MSG: std_msgs/Header
00023 # Standard metadata for higher-level stamped data types.
00024 # This is generally used to communicate timestamped data
00025 # in a particular coordinate frame.
00026 #
00027 # sequence ID: consecutively increasing ID
00028 uint32 seq
00029 #Two-integer timestamp that is expressed as:
00030 # * stamp.secs: seconds (stamp_secs) since epoch
00031 # * stamp.nsecs: nanoseconds since stamp_secs
00032 # time-handling sugar is provided by the client library
00033 time stamp
00034 #Frame this data is associated with
00035 # 0: no frame
00036 # 1: global frame
00037 string frame_id
00038
00039 ================================================================================
00040 MSG: art_msgs/ArtQuadrilateral
00041 # ART quadrilateral polygon
00042 # $Id: ArtQuadrilateral.msg 614 2010-09-24 15:08:46Z jack.oquin $
00043
00044 # Each of these polygons is a quadrilateral. The four vertex points
00045 # are ordered relative to the heading of the lane containing it.
00046
00047 geometry_msgs/Polygon poly
00048 int32 bottom_left = 0
00049 int32 top_left = 1
00050 int32 top_right = 2
00051 int32 bottom_right = 3
00052 int32 quad_size = 4
00053
00054 geometry_msgs/Point midpoint # Middle of the polygon
00055
00056 float32 heading # average of right and left boundary headings
00057 float32 length # length of the polygon
00058 int32 poly_id # unique MapLanes ID
00059
00060 bool is_stop # this poly has a stop waypoint
00061 bool is_transition # not a lane polygon, no waypoint
00062 bool contains_way # both start_way and end_way are the contained waypoint
00063
00064 MapID start_way
00065 MapID end_way
00066
00067 LaneMarking left_boundary
00068 LaneMarking right_boundary
00069
00070 ================================================================================
00071 MSG: geometry_msgs/Polygon
00072 #A specification of a polygon where the first and last points are assumed to be connected
00073 Point32[] points
00074
00075 ================================================================================
00076 MSG: geometry_msgs/Point32
00077 # This contains the position of a point in free space(with 32 bits of precision).
00078 # It is recommeded to use Point wherever possible instead of Point32.
00079 #
00080 # This recommendation is to promote interoperability.
00081 #
00082 # This message is designed to take up less space when sending
00083 # lots of points at once, as in the case of a PointCloud.
00084
00085 float32 x
00086 float32 y
00087 float32 z
00088 ================================================================================
00089 MSG: geometry_msgs/Point
00090 # This contains the position of a point in free space
00091 float64 x
00092 float64 y
00093 float64 z
00094
00095 ================================================================================
00096 MSG: art_msgs/MapID
00097 # Road map identifier for segments, lanes and way-points.
00098 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $
00099
00100 uint16 NULL_ID = 65535
00101
00102 uint16 seg # segment ID
00103 uint16 lane # lane ID
00104 uint16 pt # way-point ID
00105
00106 ================================================================================
00107 MSG: art_msgs/LaneMarking
00108 # Route Network Definition File lane marking
00109 # $Id: LaneMarking.msg 614 2010-09-24 15:08:46Z jack.oquin $
00110
00111 int16 DOUBLE_YELLOW = 0
00112 int16 SOLID_YELLOW = 1
00113 int16 SOLID_WHITE = 2
00114 int16 BROKEN_WHITE = 3
00115 int16 UNDEFINED = 4
00116
00117 int16 lane_marking
00118
00119 """
00120 __slots__ = ['header','polygons']
00121 _slot_types = ['std_msgs/Header','art_msgs/ArtQuadrilateral[]']
00122
00123 def __init__(self, *args, **kwds):
00124 """
00125 Constructor. Any message fields that are implicitly/explicitly
00126 set to None will be assigned a default value. The recommend
00127 use is keyword arguments as this is more robust to future message
00128 changes. You cannot mix in-order arguments and keyword arguments.
00129
00130 The available fields are:
00131 header,polygons
00132
00133 :param args: complete set of field values, in .msg order
00134 :param kwds: use keyword arguments corresponding to message field names
00135 to set specific fields.
00136 """
00137 if args or kwds:
00138 super(ArtLanes, self).__init__(*args, **kwds)
00139
00140 if self.header is None:
00141 self.header = std_msgs.msg.Header()
00142 if self.polygons is None:
00143 self.polygons = []
00144 else:
00145 self.header = std_msgs.msg.Header()
00146 self.polygons = []
00147
00148 def _get_types(self):
00149 """
00150 internal API method
00151 """
00152 return self._slot_types
00153
00154 def serialize(self, buff):
00155 """
00156 serialize message into buffer
00157 :param buff: buffer, ``StringIO``
00158 """
00159 try:
00160 _x = self
00161 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00162 _x = self.header.frame_id
00163 length = len(_x)
00164 if python3 or type(_x) == unicode:
00165 _x = _x.encode('utf-8')
00166 length = len(_x)
00167 buff.write(struct.pack('<I%ss'%length, length, _x))
00168 length = len(self.polygons)
00169 buff.write(_struct_I.pack(length))
00170 for val1 in self.polygons:
00171 _v1 = val1.poly
00172 length = len(_v1.points)
00173 buff.write(_struct_I.pack(length))
00174 for val3 in _v1.points:
00175 _x = val3
00176 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00177 _v2 = val1.midpoint
00178 _x = _v2
00179 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00180 _x = val1
00181 buff.write(_struct_2fi3B.pack(_x.heading, _x.length, _x.poly_id, _x.is_stop, _x.is_transition, _x.contains_way))
00182 _v3 = val1.start_way
00183 _x = _v3
00184 buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00185 _v4 = val1.end_way
00186 _x = _v4
00187 buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00188 _v5 = val1.left_boundary
00189 buff.write(_struct_h.pack(_v5.lane_marking))
00190 _v6 = val1.right_boundary
00191 buff.write(_struct_h.pack(_v6.lane_marking))
00192 except struct.error as se: self._check_types(se)
00193 except TypeError as te: self._check_types(te)
00194
00195 def deserialize(self, str):
00196 """
00197 unpack serialized message in str into this message instance
00198 :param str: byte array of serialized message, ``str``
00199 """
00200 try:
00201 if self.header is None:
00202 self.header = std_msgs.msg.Header()
00203 if self.polygons is None:
00204 self.polygons = None
00205 end = 0
00206 _x = self
00207 start = end
00208 end += 12
00209 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00210 start = end
00211 end += 4
00212 (length,) = _struct_I.unpack(str[start:end])
00213 start = end
00214 end += length
00215 if python3:
00216 self.header.frame_id = str[start:end].decode('utf-8')
00217 else:
00218 self.header.frame_id = str[start:end]
00219 start = end
00220 end += 4
00221 (length,) = _struct_I.unpack(str[start:end])
00222 self.polygons = []
00223 for i in range(0, length):
00224 val1 = art_msgs.msg.ArtQuadrilateral()
00225 _v7 = val1.poly
00226 start = end
00227 end += 4
00228 (length,) = _struct_I.unpack(str[start:end])
00229 _v7.points = []
00230 for i in range(0, length):
00231 val3 = geometry_msgs.msg.Point32()
00232 _x = val3
00233 start = end
00234 end += 12
00235 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00236 _v7.points.append(val3)
00237 _v8 = val1.midpoint
00238 _x = _v8
00239 start = end
00240 end += 24
00241 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00242 _x = val1
00243 start = end
00244 end += 15
00245 (_x.heading, _x.length, _x.poly_id, _x.is_stop, _x.is_transition, _x.contains_way,) = _struct_2fi3B.unpack(str[start:end])
00246 val1.is_stop = bool(val1.is_stop)
00247 val1.is_transition = bool(val1.is_transition)
00248 val1.contains_way = bool(val1.contains_way)
00249 _v9 = val1.start_way
00250 _x = _v9
00251 start = end
00252 end += 6
00253 (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00254 _v10 = val1.end_way
00255 _x = _v10
00256 start = end
00257 end += 6
00258 (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00259 _v11 = val1.left_boundary
00260 start = end
00261 end += 2
00262 (_v11.lane_marking,) = _struct_h.unpack(str[start:end])
00263 _v12 = val1.right_boundary
00264 start = end
00265 end += 2
00266 (_v12.lane_marking,) = _struct_h.unpack(str[start:end])
00267 self.polygons.append(val1)
00268 return self
00269 except struct.error as e:
00270 raise genpy.DeserializationError(e)
00271
00272
00273 def serialize_numpy(self, buff, numpy):
00274 """
00275 serialize message with numpy array types into buffer
00276 :param buff: buffer, ``StringIO``
00277 :param numpy: numpy python module
00278 """
00279 try:
00280 _x = self
00281 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00282 _x = self.header.frame_id
00283 length = len(_x)
00284 if python3 or type(_x) == unicode:
00285 _x = _x.encode('utf-8')
00286 length = len(_x)
00287 buff.write(struct.pack('<I%ss'%length, length, _x))
00288 length = len(self.polygons)
00289 buff.write(_struct_I.pack(length))
00290 for val1 in self.polygons:
00291 _v13 = val1.poly
00292 length = len(_v13.points)
00293 buff.write(_struct_I.pack(length))
00294 for val3 in _v13.points:
00295 _x = val3
00296 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00297 _v14 = val1.midpoint
00298 _x = _v14
00299 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00300 _x = val1
00301 buff.write(_struct_2fi3B.pack(_x.heading, _x.length, _x.poly_id, _x.is_stop, _x.is_transition, _x.contains_way))
00302 _v15 = val1.start_way
00303 _x = _v15
00304 buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00305 _v16 = val1.end_way
00306 _x = _v16
00307 buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00308 _v17 = val1.left_boundary
00309 buff.write(_struct_h.pack(_v17.lane_marking))
00310 _v18 = val1.right_boundary
00311 buff.write(_struct_h.pack(_v18.lane_marking))
00312 except struct.error as se: self._check_types(se)
00313 except TypeError as te: self._check_types(te)
00314
00315 def deserialize_numpy(self, str, numpy):
00316 """
00317 unpack serialized message in str into this message instance using numpy for array types
00318 :param str: byte array of serialized message, ``str``
00319 :param numpy: numpy python module
00320 """
00321 try:
00322 if self.header is None:
00323 self.header = std_msgs.msg.Header()
00324 if self.polygons is None:
00325 self.polygons = None
00326 end = 0
00327 _x = self
00328 start = end
00329 end += 12
00330 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00331 start = end
00332 end += 4
00333 (length,) = _struct_I.unpack(str[start:end])
00334 start = end
00335 end += length
00336 if python3:
00337 self.header.frame_id = str[start:end].decode('utf-8')
00338 else:
00339 self.header.frame_id = str[start:end]
00340 start = end
00341 end += 4
00342 (length,) = _struct_I.unpack(str[start:end])
00343 self.polygons = []
00344 for i in range(0, length):
00345 val1 = art_msgs.msg.ArtQuadrilateral()
00346 _v19 = val1.poly
00347 start = end
00348 end += 4
00349 (length,) = _struct_I.unpack(str[start:end])
00350 _v19.points = []
00351 for i in range(0, length):
00352 val3 = geometry_msgs.msg.Point32()
00353 _x = val3
00354 start = end
00355 end += 12
00356 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00357 _v19.points.append(val3)
00358 _v20 = val1.midpoint
00359 _x = _v20
00360 start = end
00361 end += 24
00362 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00363 _x = val1
00364 start = end
00365 end += 15
00366 (_x.heading, _x.length, _x.poly_id, _x.is_stop, _x.is_transition, _x.contains_way,) = _struct_2fi3B.unpack(str[start:end])
00367 val1.is_stop = bool(val1.is_stop)
00368 val1.is_transition = bool(val1.is_transition)
00369 val1.contains_way = bool(val1.contains_way)
00370 _v21 = val1.start_way
00371 _x = _v21
00372 start = end
00373 end += 6
00374 (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00375 _v22 = val1.end_way
00376 _x = _v22
00377 start = end
00378 end += 6
00379 (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00380 _v23 = val1.left_boundary
00381 start = end
00382 end += 2
00383 (_v23.lane_marking,) = _struct_h.unpack(str[start:end])
00384 _v24 = val1.right_boundary
00385 start = end
00386 end += 2
00387 (_v24.lane_marking,) = _struct_h.unpack(str[start:end])
00388 self.polygons.append(val1)
00389 return self
00390 except struct.error as e:
00391 raise genpy.DeserializationError(e)
00392
00393 _struct_I = genpy.struct_I
00394 _struct_h = struct.Struct("<h")
00395 _struct_2fi3B = struct.Struct("<2fi3B")
00396 _struct_3I = struct.Struct("<3I")
00397 _struct_3H = struct.Struct("<3H")
00398 _struct_3f = struct.Struct("<3f")
00399 _struct_3d = struct.Struct("<3d")