00001 """autogenerated by genpy from art_msgs/Order.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 Order(genpy.Message):
00011 _md5sum = "f43d538cba2d46c585cc23d97b9223b2"
00012 _type = "art_msgs/Order"
00013 _has_header = False
00014 _full_text = """# commander order for the navigator
00015 # $Id: Order.msg 615 2010-09-24 16:07:50Z jack.oquin $
00016
00017 uint32 N_WAYPTS = 5 # number of way-points in order
00018 uint32 N_CHKPTS = 2 # number of checkpoints in order
00019
00020 Behavior behavior # requested behavior
00021 art_msgs/WayPoint[5] waypt # way-point array
00022 art_msgs/WayPoint[2] chkpt # next two goal checkpoints
00023 float32 min_speed # in meters/sec
00024 float32 max_speed
00025 int32 replan_num
00026 int32 next_uturn # Uturn between [1] and [2]
00027
00028 ================================================================================
00029 MSG: art_msgs/Behavior
00030 # ART Navigator behaviors (lower numbers have higher priority)
00031 # $Id: Behavior.msg 996 2011-02-27 16:07:34Z jack.oquin $
00032
00033 # enumerated behavior values
00034 int16 Abort = 0
00035 int16 Quit = 1
00036 int16 Pause = 2
00037 int16 Run = 3
00038 int16 Suspend = 4
00039 int16 Initialize = 5
00040 int16 Go = 6
00041 int16 NONE = 7
00042 int16 N_behaviors = 8
00043
00044 int16 value
00045
00046 ================================================================================
00047 MSG: art_msgs/WayPoint
00048 # Way-point attributes
00049 # $Id: WayPoint.msg 614 2010-09-24 15:08:46Z jack.oquin $
00050
00051 float64 latitude # latitude in degrees
00052 float64 longitude # longitude in degrees
00053 geometry_msgs/Point32 mapxy # MapXY position
00054 MapID id # way-point ID
00055 uint16 index # parser index of waypoint
00056
00057 # way-point flags
00058 bool is_entry # lane or zone exit point
00059 bool is_exit # lane or zone entry point
00060 bool is_goal # this is a goal checkpoint
00061 bool is_lane_change # change lanes after here
00062 bool is_spot # parking spot
00063 bool is_stop # stop line here
00064 bool is_perimeter # zone perimeter point
00065 int32 checkpoint_id # checkpoint ID or zero
00066 float32 lane_width
00067
00068 ================================================================================
00069 MSG: geometry_msgs/Point32
00070 # This contains the position of a point in free space(with 32 bits of precision).
00071 # It is recommeded to use Point wherever possible instead of Point32.
00072 #
00073 # This recommendation is to promote interoperability.
00074 #
00075 # This message is designed to take up less space when sending
00076 # lots of points at once, as in the case of a PointCloud.
00077
00078 float32 x
00079 float32 y
00080 float32 z
00081 ================================================================================
00082 MSG: art_msgs/MapID
00083 # Road map identifier for segments, lanes and way-points.
00084 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $
00085
00086 uint16 NULL_ID = 65535
00087
00088 uint16 seg # segment ID
00089 uint16 lane # lane ID
00090 uint16 pt # way-point ID
00091
00092 """
00093
00094 N_WAYPTS = 5
00095 N_CHKPTS = 2
00096
00097 __slots__ = ['behavior','waypt','chkpt','min_speed','max_speed','replan_num','next_uturn']
00098 _slot_types = ['art_msgs/Behavior','art_msgs/WayPoint[5]','art_msgs/WayPoint[2]','float32','float32','int32','int32']
00099
00100 def __init__(self, *args, **kwds):
00101 """
00102 Constructor. Any message fields that are implicitly/explicitly
00103 set to None will be assigned a default value. The recommend
00104 use is keyword arguments as this is more robust to future message
00105 changes. You cannot mix in-order arguments and keyword arguments.
00106
00107 The available fields are:
00108 behavior,waypt,chkpt,min_speed,max_speed,replan_num,next_uturn
00109
00110 :param args: complete set of field values, in .msg order
00111 :param kwds: use keyword arguments corresponding to message field names
00112 to set specific fields.
00113 """
00114 if args or kwds:
00115 super(Order, self).__init__(*args, **kwds)
00116
00117 if self.behavior is None:
00118 self.behavior = art_msgs.msg.Behavior()
00119 if self.waypt is None:
00120 self.waypt = [art_msgs.msg.WayPoint(),art_msgs.msg.WayPoint(),art_msgs.msg.WayPoint(),art_msgs.msg.WayPoint(),art_msgs.msg.WayPoint()]
00121 if self.chkpt is None:
00122 self.chkpt = [art_msgs.msg.WayPoint(),art_msgs.msg.WayPoint()]
00123 if self.min_speed is None:
00124 self.min_speed = 0.
00125 if self.max_speed is None:
00126 self.max_speed = 0.
00127 if self.replan_num is None:
00128 self.replan_num = 0
00129 if self.next_uturn is None:
00130 self.next_uturn = 0
00131 else:
00132 self.behavior = art_msgs.msg.Behavior()
00133 self.waypt = [art_msgs.msg.WayPoint(),art_msgs.msg.WayPoint(),art_msgs.msg.WayPoint(),art_msgs.msg.WayPoint(),art_msgs.msg.WayPoint()]
00134 self.chkpt = [art_msgs.msg.WayPoint(),art_msgs.msg.WayPoint()]
00135 self.min_speed = 0.
00136 self.max_speed = 0.
00137 self.replan_num = 0
00138 self.next_uturn = 0
00139
00140 def _get_types(self):
00141 """
00142 internal API method
00143 """
00144 return self._slot_types
00145
00146 def serialize(self, buff):
00147 """
00148 serialize message into buffer
00149 :param buff: buffer, ``StringIO``
00150 """
00151 try:
00152 buff.write(_struct_h.pack(self.behavior.value))
00153 for val1 in self.waypt:
00154 _x = val1
00155 buff.write(_struct_2d.pack(_x.latitude, _x.longitude))
00156 _v1 = val1.mapxy
00157 _x = _v1
00158 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00159 _v2 = val1.id
00160 _x = _v2
00161 buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00162 _x = val1
00163 buff.write(_struct_H7Bif.pack(_x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width))
00164 for val1 in self.chkpt:
00165 _x = val1
00166 buff.write(_struct_2d.pack(_x.latitude, _x.longitude))
00167 _v3 = val1.mapxy
00168 _x = _v3
00169 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00170 _v4 = val1.id
00171 _x = _v4
00172 buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00173 _x = val1
00174 buff.write(_struct_H7Bif.pack(_x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width))
00175 _x = self
00176 buff.write(_struct_2f2i.pack(_x.min_speed, _x.max_speed, _x.replan_num, _x.next_uturn))
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.behavior is None:
00187 self.behavior = art_msgs.msg.Behavior()
00188 if self.waypt is None:
00189 self.waypt = None
00190 if self.chkpt is None:
00191 self.chkpt = None
00192 end = 0
00193 start = end
00194 end += 2
00195 (self.behavior.value,) = _struct_h.unpack(str[start:end])
00196 self.waypt = []
00197 for i in range(0, 5):
00198 val1 = art_msgs.msg.WayPoint()
00199 _x = val1
00200 start = end
00201 end += 16
00202 (_x.latitude, _x.longitude,) = _struct_2d.unpack(str[start:end])
00203 _v5 = val1.mapxy
00204 _x = _v5
00205 start = end
00206 end += 12
00207 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00208 _v6 = val1.id
00209 _x = _v6
00210 start = end
00211 end += 6
00212 (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00213 _x = val1
00214 start = end
00215 end += 17
00216 (_x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width,) = _struct_H7Bif.unpack(str[start:end])
00217 val1.is_entry = bool(val1.is_entry)
00218 val1.is_exit = bool(val1.is_exit)
00219 val1.is_goal = bool(val1.is_goal)
00220 val1.is_lane_change = bool(val1.is_lane_change)
00221 val1.is_spot = bool(val1.is_spot)
00222 val1.is_stop = bool(val1.is_stop)
00223 val1.is_perimeter = bool(val1.is_perimeter)
00224 self.waypt.append(val1)
00225 self.chkpt = []
00226 for i in range(0, 2):
00227 val1 = art_msgs.msg.WayPoint()
00228 _x = val1
00229 start = end
00230 end += 16
00231 (_x.latitude, _x.longitude,) = _struct_2d.unpack(str[start:end])
00232 _v7 = val1.mapxy
00233 _x = _v7
00234 start = end
00235 end += 12
00236 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00237 _v8 = val1.id
00238 _x = _v8
00239 start = end
00240 end += 6
00241 (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00242 _x = val1
00243 start = end
00244 end += 17
00245 (_x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width,) = _struct_H7Bif.unpack(str[start:end])
00246 val1.is_entry = bool(val1.is_entry)
00247 val1.is_exit = bool(val1.is_exit)
00248 val1.is_goal = bool(val1.is_goal)
00249 val1.is_lane_change = bool(val1.is_lane_change)
00250 val1.is_spot = bool(val1.is_spot)
00251 val1.is_stop = bool(val1.is_stop)
00252 val1.is_perimeter = bool(val1.is_perimeter)
00253 self.chkpt.append(val1)
00254 _x = self
00255 start = end
00256 end += 16
00257 (_x.min_speed, _x.max_speed, _x.replan_num, _x.next_uturn,) = _struct_2f2i.unpack(str[start:end])
00258 return self
00259 except struct.error as e:
00260 raise genpy.DeserializationError(e)
00261
00262
00263 def serialize_numpy(self, buff, numpy):
00264 """
00265 serialize message with numpy array types into buffer
00266 :param buff: buffer, ``StringIO``
00267 :param numpy: numpy python module
00268 """
00269 try:
00270 buff.write(_struct_h.pack(self.behavior.value))
00271 for val1 in self.waypt:
00272 _x = val1
00273 buff.write(_struct_2d.pack(_x.latitude, _x.longitude))
00274 _v9 = val1.mapxy
00275 _x = _v9
00276 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00277 _v10 = val1.id
00278 _x = _v10
00279 buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00280 _x = val1
00281 buff.write(_struct_H7Bif.pack(_x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width))
00282 for val1 in self.chkpt:
00283 _x = val1
00284 buff.write(_struct_2d.pack(_x.latitude, _x.longitude))
00285 _v11 = val1.mapxy
00286 _x = _v11
00287 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00288 _v12 = val1.id
00289 _x = _v12
00290 buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00291 _x = val1
00292 buff.write(_struct_H7Bif.pack(_x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width))
00293 _x = self
00294 buff.write(_struct_2f2i.pack(_x.min_speed, _x.max_speed, _x.replan_num, _x.next_uturn))
00295 except struct.error as se: self._check_types(se)
00296 except TypeError as te: self._check_types(te)
00297
00298 def deserialize_numpy(self, str, numpy):
00299 """
00300 unpack serialized message in str into this message instance using numpy for array types
00301 :param str: byte array of serialized message, ``str``
00302 :param numpy: numpy python module
00303 """
00304 try:
00305 if self.behavior is None:
00306 self.behavior = art_msgs.msg.Behavior()
00307 if self.waypt is None:
00308 self.waypt = None
00309 if self.chkpt is None:
00310 self.chkpt = None
00311 end = 0
00312 start = end
00313 end += 2
00314 (self.behavior.value,) = _struct_h.unpack(str[start:end])
00315 self.waypt = []
00316 for i in range(0, 5):
00317 val1 = art_msgs.msg.WayPoint()
00318 _x = val1
00319 start = end
00320 end += 16
00321 (_x.latitude, _x.longitude,) = _struct_2d.unpack(str[start:end])
00322 _v13 = val1.mapxy
00323 _x = _v13
00324 start = end
00325 end += 12
00326 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00327 _v14 = val1.id
00328 _x = _v14
00329 start = end
00330 end += 6
00331 (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00332 _x = val1
00333 start = end
00334 end += 17
00335 (_x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width,) = _struct_H7Bif.unpack(str[start:end])
00336 val1.is_entry = bool(val1.is_entry)
00337 val1.is_exit = bool(val1.is_exit)
00338 val1.is_goal = bool(val1.is_goal)
00339 val1.is_lane_change = bool(val1.is_lane_change)
00340 val1.is_spot = bool(val1.is_spot)
00341 val1.is_stop = bool(val1.is_stop)
00342 val1.is_perimeter = bool(val1.is_perimeter)
00343 self.waypt.append(val1)
00344 self.chkpt = []
00345 for i in range(0, 2):
00346 val1 = art_msgs.msg.WayPoint()
00347 _x = val1
00348 start = end
00349 end += 16
00350 (_x.latitude, _x.longitude,) = _struct_2d.unpack(str[start:end])
00351 _v15 = val1.mapxy
00352 _x = _v15
00353 start = end
00354 end += 12
00355 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00356 _v16 = val1.id
00357 _x = _v16
00358 start = end
00359 end += 6
00360 (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00361 _x = val1
00362 start = end
00363 end += 17
00364 (_x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width,) = _struct_H7Bif.unpack(str[start:end])
00365 val1.is_entry = bool(val1.is_entry)
00366 val1.is_exit = bool(val1.is_exit)
00367 val1.is_goal = bool(val1.is_goal)
00368 val1.is_lane_change = bool(val1.is_lane_change)
00369 val1.is_spot = bool(val1.is_spot)
00370 val1.is_stop = bool(val1.is_stop)
00371 val1.is_perimeter = bool(val1.is_perimeter)
00372 self.chkpt.append(val1)
00373 _x = self
00374 start = end
00375 end += 16
00376 (_x.min_speed, _x.max_speed, _x.replan_num, _x.next_uturn,) = _struct_2f2i.unpack(str[start:end])
00377 return self
00378 except struct.error as e:
00379 raise genpy.DeserializationError(e)
00380
00381 _struct_I = genpy.struct_I
00382 _struct_h = struct.Struct("<h")
00383 _struct_2f2i = struct.Struct("<2f2i")
00384 _struct_H7Bif = struct.Struct("<H7Bif")
00385 _struct_2d = struct.Struct("<2d")
00386 _struct_3H = struct.Struct("<3H")
00387 _struct_3f = struct.Struct("<3f")