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