_NavigatorState.py
Go to the documentation of this file.
00001 """autogenerated by genpy from art_msgs/NavigatorState.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 NavigatorState(genpy.Message):
00012   _md5sum = "c40e5f1fdc1b82b80af736960035d5c8"
00013   _type = "art_msgs/NavigatorState"
00014   _has_header = True #flag to mark the presence of a Header object
00015   _full_text = """# navigator state message
00016 # $Id: NavigatorState.msg 615 2010-09-24 16:07:50Z jack.oquin $
00017 
00018 Header header
00019 
00020 EstopState estop
00021 RoadState road
00022 
00023 art_msgs/MapID last_waypt               # last way-point reached
00024 art_msgs/MapID replan_waypt             # next way-point for replan
00025 
00026 int32 cur_poly                          # current polygon, -1 if none
00027 
00028 # status flags
00029 bool alarm
00030 bool flasher
00031 bool lane_blocked
00032 bool road_blocked
00033 bool reverse
00034 bool signal_left
00035 bool signal_right
00036 bool stopped
00037 bool have_zones
00038 
00039 Order last_order                        # last commander order received
00040 
00041 ================================================================================
00042 MSG: std_msgs/Header
00043 # Standard metadata for higher-level stamped data types.
00044 # This is generally used to communicate timestamped data 
00045 # in a particular coordinate frame.
00046 # 
00047 # sequence ID: consecutively increasing ID 
00048 uint32 seq
00049 #Two-integer timestamp that is expressed as:
00050 # * stamp.secs: seconds (stamp_secs) since epoch
00051 # * stamp.nsecs: nanoseconds since stamp_secs
00052 # time-handling sugar is provided by the client library
00053 time stamp
00054 #Frame this data is associated with
00055 # 0: no frame
00056 # 1: global frame
00057 string frame_id
00058 
00059 ================================================================================
00060 MSG: art_msgs/EstopState
00061 # Navigator E-stop state values
00062 # $Id: EstopState.msg 996 2011-02-27 16:07:34Z jack.oquin $
00063 
00064 uint16 Pause    = 0                     # E-stop pause (initial state)
00065 uint16 Run      = 1                     # E-stop run enabled
00066 uint16 Done     = 2                     # mission finished (disabled)
00067 uint16 Suspend  = 3                     # suspend autonomous operation
00068 uint16 N_states = 4
00069 
00070 uint16 state
00071 
00072 ================================================================================
00073 MSG: art_msgs/RoadState
00074 # Navigator Road state values
00075 # $Id: RoadState.msg 615 2010-09-24 16:07:50Z jack.oquin $
00076 
00077 uint16 Init      = 0
00078 uint16 Block     = 1
00079 uint16 Evade     = 2
00080 uint16 Follow    = 3
00081 uint16 Pass      = 4
00082 uint16 Uturn     = 5
00083 uint16 WaitCross = 6
00084 uint16 WaitLane  = 7
00085 uint16 WaitPass  = 8
00086 uint16 WaitStop  = 9
00087 uint16 Zone      = 10
00088 uint16 N_states  = 11
00089 
00090 uint16 state
00091 
00092 ================================================================================
00093 MSG: art_msgs/MapID
00094 # Road map identifier for segments, lanes and way-points.
00095 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $
00096 
00097 uint16 NULL_ID = 65535
00098 
00099 uint16 seg      # segment ID
00100 uint16 lane     # lane ID
00101 uint16 pt       # way-point ID
00102 
00103 ================================================================================
00104 MSG: art_msgs/Order
00105 # commander order for the navigator
00106 # $Id: Order.msg 615 2010-09-24 16:07:50Z jack.oquin $
00107 
00108 uint32 N_WAYPTS = 5                     # number of way-points in order
00109 uint32 N_CHKPTS = 2                     # number of checkpoints in order
00110 
00111 Behavior behavior                       # requested behavior
00112 art_msgs/WayPoint[5] waypt              # way-point array
00113 art_msgs/WayPoint[2] chkpt              # next two goal checkpoints
00114 float32 min_speed                       # in meters/sec
00115 float32 max_speed
00116 int32 replan_num
00117 int32 next_uturn                        # Uturn between [1] and [2]
00118 
00119 ================================================================================
00120 MSG: art_msgs/Behavior
00121 # ART Navigator behaviors (lower numbers have higher priority)
00122 # $Id: Behavior.msg 996 2011-02-27 16:07:34Z jack.oquin $
00123 
00124 # enumerated behavior values
00125 int16 Abort       = 0
00126 int16 Quit        = 1
00127 int16 Pause       = 2
00128 int16 Run         = 3
00129 int16 Suspend     = 4
00130 int16 Initialize  = 5
00131 int16 Go          = 6
00132 int16 NONE        = 7
00133 int16 N_behaviors = 8
00134 
00135 int16 value
00136 
00137 ================================================================================
00138 MSG: art_msgs/WayPoint
00139 # Way-point attributes
00140 # $Id: WayPoint.msg 614 2010-09-24 15:08:46Z jack.oquin $
00141 
00142 float64 latitude                        # latitude in degrees
00143 float64 longitude                       # longitude in degrees
00144 geometry_msgs/Point32 mapxy             # MapXY position
00145 MapID id                                # way-point ID
00146 uint16 index                            # parser index of waypoint
00147 
00148 # way-point flags
00149 bool is_entry                           # lane or zone exit point
00150 bool is_exit                            # lane or zone entry point
00151 bool is_goal                            # this is a goal checkpoint
00152 bool is_lane_change                     # change lanes after here
00153 bool is_spot                            # parking spot
00154 bool is_stop                            # stop line here
00155 bool is_perimeter                       # zone perimeter point
00156 int32 checkpoint_id                     # checkpoint ID or zero
00157 float32 lane_width
00158 
00159 ================================================================================
00160 MSG: geometry_msgs/Point32
00161 # This contains the position of a point in free space(with 32 bits of precision).
00162 # It is recommeded to use Point wherever possible instead of Point32.  
00163 # 
00164 # This recommendation is to promote interoperability.  
00165 #
00166 # This message is designed to take up less space when sending
00167 # lots of points at once, as in the case of a PointCloud.  
00168 
00169 float32 x
00170 float32 y
00171 float32 z
00172 """
00173   __slots__ = ['header','estop','road','last_waypt','replan_waypt','cur_poly','alarm','flasher','lane_blocked','road_blocked','reverse','signal_left','signal_right','stopped','have_zones','last_order']
00174   _slot_types = ['std_msgs/Header','art_msgs/EstopState','art_msgs/RoadState','art_msgs/MapID','art_msgs/MapID','int32','bool','bool','bool','bool','bool','bool','bool','bool','bool','art_msgs/Order']
00175 
00176   def __init__(self, *args, **kwds):
00177     """
00178     Constructor. Any message fields that are implicitly/explicitly
00179     set to None will be assigned a default value. The recommend
00180     use is keyword arguments as this is more robust to future message
00181     changes.  You cannot mix in-order arguments and keyword arguments.
00182 
00183     The available fields are:
00184        header,estop,road,last_waypt,replan_waypt,cur_poly,alarm,flasher,lane_blocked,road_blocked,reverse,signal_left,signal_right,stopped,have_zones,last_order
00185 
00186     :param args: complete set of field values, in .msg order
00187     :param kwds: use keyword arguments corresponding to message field names
00188     to set specific fields.
00189     """
00190     if args or kwds:
00191       super(NavigatorState, self).__init__(*args, **kwds)
00192       #message fields cannot be None, assign default values for those that are
00193       if self.header is None:
00194         self.header = std_msgs.msg.Header()
00195       if self.estop is None:
00196         self.estop = art_msgs.msg.EstopState()
00197       if self.road is None:
00198         self.road = art_msgs.msg.RoadState()
00199       if self.last_waypt is None:
00200         self.last_waypt = art_msgs.msg.MapID()
00201       if self.replan_waypt is None:
00202         self.replan_waypt = art_msgs.msg.MapID()
00203       if self.cur_poly is None:
00204         self.cur_poly = 0
00205       if self.alarm is None:
00206         self.alarm = False
00207       if self.flasher is None:
00208         self.flasher = False
00209       if self.lane_blocked is None:
00210         self.lane_blocked = False
00211       if self.road_blocked is None:
00212         self.road_blocked = False
00213       if self.reverse is None:
00214         self.reverse = False
00215       if self.signal_left is None:
00216         self.signal_left = False
00217       if self.signal_right is None:
00218         self.signal_right = False
00219       if self.stopped is None:
00220         self.stopped = False
00221       if self.have_zones is None:
00222         self.have_zones = False
00223       if self.last_order is None:
00224         self.last_order = art_msgs.msg.Order()
00225     else:
00226       self.header = std_msgs.msg.Header()
00227       self.estop = art_msgs.msg.EstopState()
00228       self.road = art_msgs.msg.RoadState()
00229       self.last_waypt = art_msgs.msg.MapID()
00230       self.replan_waypt = art_msgs.msg.MapID()
00231       self.cur_poly = 0
00232       self.alarm = False
00233       self.flasher = False
00234       self.lane_blocked = False
00235       self.road_blocked = False
00236       self.reverse = False
00237       self.signal_left = False
00238       self.signal_right = False
00239       self.stopped = False
00240       self.have_zones = False
00241       self.last_order = art_msgs.msg.Order()
00242 
00243   def _get_types(self):
00244     """
00245     internal API method
00246     """
00247     return self._slot_types
00248 
00249   def serialize(self, buff):
00250     """
00251     serialize message into buffer
00252     :param buff: buffer, ``StringIO``
00253     """
00254     try:
00255       _x = self
00256       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00257       _x = self.header.frame_id
00258       length = len(_x)
00259       if python3 or type(_x) == unicode:
00260         _x = _x.encode('utf-8')
00261         length = len(_x)
00262       buff.write(struct.pack('<I%ss'%length, length, _x))
00263       _x = self
00264       buff.write(_struct_8Hi9Bh.pack(_x.estop.state, _x.road.state, _x.last_waypt.seg, _x.last_waypt.lane, _x.last_waypt.pt, _x.replan_waypt.seg, _x.replan_waypt.lane, _x.replan_waypt.pt, _x.cur_poly, _x.alarm, _x.flasher, _x.lane_blocked, _x.road_blocked, _x.reverse, _x.signal_left, _x.signal_right, _x.stopped, _x.have_zones, _x.last_order.behavior.value))
00265       for val1 in self.last_order.waypt:
00266         _x = val1
00267         buff.write(_struct_2d.pack(_x.latitude, _x.longitude))
00268         _v1 = val1.mapxy
00269         _x = _v1
00270         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00271         _v2 = val1.id
00272         _x = _v2
00273         buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00274         _x = val1
00275         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))
00276       for val1 in self.last_order.chkpt:
00277         _x = val1
00278         buff.write(_struct_2d.pack(_x.latitude, _x.longitude))
00279         _v3 = val1.mapxy
00280         _x = _v3
00281         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00282         _v4 = val1.id
00283         _x = _v4
00284         buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00285         _x = val1
00286         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))
00287       _x = self
00288       buff.write(_struct_2f2i.pack(_x.last_order.min_speed, _x.last_order.max_speed, _x.last_order.replan_num, _x.last_order.next_uturn))
00289     except struct.error as se: self._check_types(se)
00290     except TypeError as te: self._check_types(te)
00291 
00292   def deserialize(self, str):
00293     """
00294     unpack serialized message in str into this message instance
00295     :param str: byte array of serialized message, ``str``
00296     """
00297     try:
00298       if self.header is None:
00299         self.header = std_msgs.msg.Header()
00300       if self.estop is None:
00301         self.estop = art_msgs.msg.EstopState()
00302       if self.road is None:
00303         self.road = art_msgs.msg.RoadState()
00304       if self.last_waypt is None:
00305         self.last_waypt = art_msgs.msg.MapID()
00306       if self.replan_waypt is None:
00307         self.replan_waypt = art_msgs.msg.MapID()
00308       if self.last_order is None:
00309         self.last_order = art_msgs.msg.Order()
00310       end = 0
00311       _x = self
00312       start = end
00313       end += 12
00314       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00315       start = end
00316       end += 4
00317       (length,) = _struct_I.unpack(str[start:end])
00318       start = end
00319       end += length
00320       if python3:
00321         self.header.frame_id = str[start:end].decode('utf-8')
00322       else:
00323         self.header.frame_id = str[start:end]
00324       _x = self
00325       start = end
00326       end += 31
00327       (_x.estop.state, _x.road.state, _x.last_waypt.seg, _x.last_waypt.lane, _x.last_waypt.pt, _x.replan_waypt.seg, _x.replan_waypt.lane, _x.replan_waypt.pt, _x.cur_poly, _x.alarm, _x.flasher, _x.lane_blocked, _x.road_blocked, _x.reverse, _x.signal_left, _x.signal_right, _x.stopped, _x.have_zones, _x.last_order.behavior.value,) = _struct_8Hi9Bh.unpack(str[start:end])
00328       self.alarm = bool(self.alarm)
00329       self.flasher = bool(self.flasher)
00330       self.lane_blocked = bool(self.lane_blocked)
00331       self.road_blocked = bool(self.road_blocked)
00332       self.reverse = bool(self.reverse)
00333       self.signal_left = bool(self.signal_left)
00334       self.signal_right = bool(self.signal_right)
00335       self.stopped = bool(self.stopped)
00336       self.have_zones = bool(self.have_zones)
00337       self.last_order.waypt = []
00338       for i in range(0, 5):
00339         val1 = art_msgs.msg.WayPoint()
00340         _x = val1
00341         start = end
00342         end += 16
00343         (_x.latitude, _x.longitude,) = _struct_2d.unpack(str[start:end])
00344         _v5 = val1.mapxy
00345         _x = _v5
00346         start = end
00347         end += 12
00348         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00349         _v6 = val1.id
00350         _x = _v6
00351         start = end
00352         end += 6
00353         (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00354         _x = val1
00355         start = end
00356         end += 17
00357         (_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])
00358         val1.is_entry = bool(val1.is_entry)
00359         val1.is_exit = bool(val1.is_exit)
00360         val1.is_goal = bool(val1.is_goal)
00361         val1.is_lane_change = bool(val1.is_lane_change)
00362         val1.is_spot = bool(val1.is_spot)
00363         val1.is_stop = bool(val1.is_stop)
00364         val1.is_perimeter = bool(val1.is_perimeter)
00365         self.last_order.waypt.append(val1)
00366       self.last_order.chkpt = []
00367       for i in range(0, 2):
00368         val1 = art_msgs.msg.WayPoint()
00369         _x = val1
00370         start = end
00371         end += 16
00372         (_x.latitude, _x.longitude,) = _struct_2d.unpack(str[start:end])
00373         _v7 = val1.mapxy
00374         _x = _v7
00375         start = end
00376         end += 12
00377         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00378         _v8 = val1.id
00379         _x = _v8
00380         start = end
00381         end += 6
00382         (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00383         _x = val1
00384         start = end
00385         end += 17
00386         (_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])
00387         val1.is_entry = bool(val1.is_entry)
00388         val1.is_exit = bool(val1.is_exit)
00389         val1.is_goal = bool(val1.is_goal)
00390         val1.is_lane_change = bool(val1.is_lane_change)
00391         val1.is_spot = bool(val1.is_spot)
00392         val1.is_stop = bool(val1.is_stop)
00393         val1.is_perimeter = bool(val1.is_perimeter)
00394         self.last_order.chkpt.append(val1)
00395       _x = self
00396       start = end
00397       end += 16
00398       (_x.last_order.min_speed, _x.last_order.max_speed, _x.last_order.replan_num, _x.last_order.next_uturn,) = _struct_2f2i.unpack(str[start:end])
00399       return self
00400     except struct.error as e:
00401       raise genpy.DeserializationError(e) #most likely buffer underfill
00402 
00403 
00404   def serialize_numpy(self, buff, numpy):
00405     """
00406     serialize message with numpy array types into buffer
00407     :param buff: buffer, ``StringIO``
00408     :param numpy: numpy python module
00409     """
00410     try:
00411       _x = self
00412       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00413       _x = self.header.frame_id
00414       length = len(_x)
00415       if python3 or type(_x) == unicode:
00416         _x = _x.encode('utf-8')
00417         length = len(_x)
00418       buff.write(struct.pack('<I%ss'%length, length, _x))
00419       _x = self
00420       buff.write(_struct_8Hi9Bh.pack(_x.estop.state, _x.road.state, _x.last_waypt.seg, _x.last_waypt.lane, _x.last_waypt.pt, _x.replan_waypt.seg, _x.replan_waypt.lane, _x.replan_waypt.pt, _x.cur_poly, _x.alarm, _x.flasher, _x.lane_blocked, _x.road_blocked, _x.reverse, _x.signal_left, _x.signal_right, _x.stopped, _x.have_zones, _x.last_order.behavior.value))
00421       for val1 in self.last_order.waypt:
00422         _x = val1
00423         buff.write(_struct_2d.pack(_x.latitude, _x.longitude))
00424         _v9 = val1.mapxy
00425         _x = _v9
00426         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00427         _v10 = val1.id
00428         _x = _v10
00429         buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00430         _x = val1
00431         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))
00432       for val1 in self.last_order.chkpt:
00433         _x = val1
00434         buff.write(_struct_2d.pack(_x.latitude, _x.longitude))
00435         _v11 = val1.mapxy
00436         _x = _v11
00437         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00438         _v12 = val1.id
00439         _x = _v12
00440         buff.write(_struct_3H.pack(_x.seg, _x.lane, _x.pt))
00441         _x = val1
00442         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))
00443       _x = self
00444       buff.write(_struct_2f2i.pack(_x.last_order.min_speed, _x.last_order.max_speed, _x.last_order.replan_num, _x.last_order.next_uturn))
00445     except struct.error as se: self._check_types(se)
00446     except TypeError as te: self._check_types(te)
00447 
00448   def deserialize_numpy(self, str, numpy):
00449     """
00450     unpack serialized message in str into this message instance using numpy for array types
00451     :param str: byte array of serialized message, ``str``
00452     :param numpy: numpy python module
00453     """
00454     try:
00455       if self.header is None:
00456         self.header = std_msgs.msg.Header()
00457       if self.estop is None:
00458         self.estop = art_msgs.msg.EstopState()
00459       if self.road is None:
00460         self.road = art_msgs.msg.RoadState()
00461       if self.last_waypt is None:
00462         self.last_waypt = art_msgs.msg.MapID()
00463       if self.replan_waypt is None:
00464         self.replan_waypt = art_msgs.msg.MapID()
00465       if self.last_order is None:
00466         self.last_order = art_msgs.msg.Order()
00467       end = 0
00468       _x = self
00469       start = end
00470       end += 12
00471       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00472       start = end
00473       end += 4
00474       (length,) = _struct_I.unpack(str[start:end])
00475       start = end
00476       end += length
00477       if python3:
00478         self.header.frame_id = str[start:end].decode('utf-8')
00479       else:
00480         self.header.frame_id = str[start:end]
00481       _x = self
00482       start = end
00483       end += 31
00484       (_x.estop.state, _x.road.state, _x.last_waypt.seg, _x.last_waypt.lane, _x.last_waypt.pt, _x.replan_waypt.seg, _x.replan_waypt.lane, _x.replan_waypt.pt, _x.cur_poly, _x.alarm, _x.flasher, _x.lane_blocked, _x.road_blocked, _x.reverse, _x.signal_left, _x.signal_right, _x.stopped, _x.have_zones, _x.last_order.behavior.value,) = _struct_8Hi9Bh.unpack(str[start:end])
00485       self.alarm = bool(self.alarm)
00486       self.flasher = bool(self.flasher)
00487       self.lane_blocked = bool(self.lane_blocked)
00488       self.road_blocked = bool(self.road_blocked)
00489       self.reverse = bool(self.reverse)
00490       self.signal_left = bool(self.signal_left)
00491       self.signal_right = bool(self.signal_right)
00492       self.stopped = bool(self.stopped)
00493       self.have_zones = bool(self.have_zones)
00494       self.last_order.waypt = []
00495       for i in range(0, 5):
00496         val1 = art_msgs.msg.WayPoint()
00497         _x = val1
00498         start = end
00499         end += 16
00500         (_x.latitude, _x.longitude,) = _struct_2d.unpack(str[start:end])
00501         _v13 = val1.mapxy
00502         _x = _v13
00503         start = end
00504         end += 12
00505         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00506         _v14 = val1.id
00507         _x = _v14
00508         start = end
00509         end += 6
00510         (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00511         _x = val1
00512         start = end
00513         end += 17
00514         (_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])
00515         val1.is_entry = bool(val1.is_entry)
00516         val1.is_exit = bool(val1.is_exit)
00517         val1.is_goal = bool(val1.is_goal)
00518         val1.is_lane_change = bool(val1.is_lane_change)
00519         val1.is_spot = bool(val1.is_spot)
00520         val1.is_stop = bool(val1.is_stop)
00521         val1.is_perimeter = bool(val1.is_perimeter)
00522         self.last_order.waypt.append(val1)
00523       self.last_order.chkpt = []
00524       for i in range(0, 2):
00525         val1 = art_msgs.msg.WayPoint()
00526         _x = val1
00527         start = end
00528         end += 16
00529         (_x.latitude, _x.longitude,) = _struct_2d.unpack(str[start:end])
00530         _v15 = val1.mapxy
00531         _x = _v15
00532         start = end
00533         end += 12
00534         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00535         _v16 = val1.id
00536         _x = _v16
00537         start = end
00538         end += 6
00539         (_x.seg, _x.lane, _x.pt,) = _struct_3H.unpack(str[start:end])
00540         _x = val1
00541         start = end
00542         end += 17
00543         (_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])
00544         val1.is_entry = bool(val1.is_entry)
00545         val1.is_exit = bool(val1.is_exit)
00546         val1.is_goal = bool(val1.is_goal)
00547         val1.is_lane_change = bool(val1.is_lane_change)
00548         val1.is_spot = bool(val1.is_spot)
00549         val1.is_stop = bool(val1.is_stop)
00550         val1.is_perimeter = bool(val1.is_perimeter)
00551         self.last_order.chkpt.append(val1)
00552       _x = self
00553       start = end
00554       end += 16
00555       (_x.last_order.min_speed, _x.last_order.max_speed, _x.last_order.replan_num, _x.last_order.next_uturn,) = _struct_2f2i.unpack(str[start:end])
00556       return self
00557     except struct.error as e:
00558       raise genpy.DeserializationError(e) #most likely buffer underfill
00559 
00560 _struct_I = genpy.struct_I
00561 _struct_8Hi9Bh = struct.Struct("<8Hi9Bh")
00562 _struct_2f2i = struct.Struct("<2f2i")
00563 _struct_H7Bif = struct.Struct("<H7Bif")
00564 _struct_2d = struct.Struct("<2d")
00565 _struct_3I = struct.Struct("<3I")
00566 _struct_3H = struct.Struct("<3H")
00567 _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