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