_CarDriveStamped.py
Go to the documentation of this file.
00001 """autogenerated by genpy from art_msgs/CarDriveStamped.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 art_msgs.msg
00008 import std_msgs.msg
00009 
00010 class CarDriveStamped(genpy.Message):
00011   _md5sum = "d243ac5e38754a52c8788d4d37db7a05"
00012   _type = "art_msgs/CarDriveStamped"
00013   _has_header = True #flag to mark the presence of a Header object
00014   _full_text = """# CarDrive message with timestamp.
00015 # $Id: CarDriveStamped.msg 1539 2011-05-09 04:09:20Z jack.oquin $
00016 
00017 Header    header
00018 CarDrive  control
00019 
00020 ================================================================================
00021 MSG: std_msgs/Header
00022 # Standard metadata for higher-level stamped data types.
00023 # This is generally used to communicate timestamped data 
00024 # in a particular coordinate frame.
00025 # 
00026 # sequence ID: consecutively increasing ID 
00027 uint32 seq
00028 #Two-integer timestamp that is expressed as:
00029 # * stamp.secs: seconds (stamp_secs) since epoch
00030 # * stamp.nsecs: nanoseconds since stamp_secs
00031 # time-handling sugar is provided by the client library
00032 time stamp
00033 #Frame this data is associated with
00034 # 0: no frame
00035 # 1: global frame
00036 string frame_id
00037 
00038 ================================================================================
00039 MSG: art_msgs/CarDrive
00040 # Driving command for a car-like vehicle using Ackermann steering.
00041 # $Id: CarDrive.msg 1539 2011-05-09 04:09:20Z jack.oquin $
00042 
00043 # Drive at requested speed, acceleration and jerk (the 1st, 2nd and
00044 # 3rd derivatives of position). All are non-negative scalars. 
00045 #
00046 # Speed is defined as the scalar magnitude of the velocity
00047 # vector. Direction (forwards or backwards) is determined by the gear.
00048 #
00049 # Zero acceleration means change speed as quickly as
00050 # possible. Positive acceleration may include deceleration as needed
00051 # to match the desired speed. It represents a desired rate and also a
00052 # limit not to exceed.
00053 #
00054 # Zero jerk means change acceleration as quickly as possible. Positive
00055 # jerk describes the desired rate of acceleration change in both
00056 # directions (positive and negative).
00057 #
00058 float32 speed                   # magnitude of velocity vector (m/s)
00059 float32 acceleration            # desired acceleration (m/s^2)
00060 float32 jerk                    # desired jerk (m/s^3)
00061 
00062 # Assumes Ackermann (front-wheel) steering. This angle is the average
00063 # yaw of the two front wheels in the vehicle frame of reference
00064 # (positive left), ignoring their slightly differing angles as if it
00065 # were a tricycle. This is *not* the angle of the steering wheel
00066 # inside the passenger compartment.
00067 #
00068 float32 steering_angle          # steering angle (radians)
00069 
00070 Gear gear                       # requested gear (no change if Naught)
00071 PilotBehavior behavior          # requested pilot behavior
00072 
00073 ================================================================================
00074 MSG: art_msgs/Gear
00075 # ART vehicle transmission gear numbers
00076 #
00077 # Used by several different messages.
00078 
00079 # $Id: Gear.msg 1539 2011-05-09 04:09:20Z jack.oquin $
00080 
00081 # Gear numbers. 
00082 #
00083 # Naught means: reset all Shifter relays; no change of CarDrive gear.
00084 uint8 Naught = 0
00085 uint8 Park = 1
00086 uint8 Reverse = 2
00087 uint8 Neutral = 3
00088 uint8 Drive = 4
00089 uint8 N_gears = 5
00090 
00091 uint8 value             # requested or reported gear number
00092 
00093 ================================================================================
00094 MSG: art_msgs/PilotBehavior
00095 # ART autonomous vehicle pilot node behaviors.
00096 #
00097 # Normally, the pilot node does Run, continually sending commands to
00098 # the servo device actuators and monitoring their state.  With Pause,
00099 # the pilot becomes passive, allowing a learning algorithm or human
00100 # controller direct access to those devices.  In the Off state,
00101 # various devices are shut down: the transmission in Park, the brake
00102 # released, the throttle at idle.  The engine is not turned off, but
00103 # it could be.
00104 
00105 # $Id: PilotBehavior.msg 1539 2011-05-09 04:09:20Z jack.oquin $
00106 
00107 # Behavior value
00108 uint8 value
00109 
00110 # Behavior numbers:
00111 uint8 Run = 0                   # normal driving
00112 uint8 Pause = 1                 # stop issuing servo commands
00113 uint8 Off = 2                   # turn off devices
00114 uint8 N_behaviors = 3
00115 
00116 """
00117   __slots__ = ['header','control']
00118   _slot_types = ['std_msgs/Header','art_msgs/CarDrive']
00119 
00120   def __init__(self, *args, **kwds):
00121     """
00122     Constructor. Any message fields that are implicitly/explicitly
00123     set to None will be assigned a default value. The recommend
00124     use is keyword arguments as this is more robust to future message
00125     changes.  You cannot mix in-order arguments and keyword arguments.
00126 
00127     The available fields are:
00128        header,control
00129 
00130     :param args: complete set of field values, in .msg order
00131     :param kwds: use keyword arguments corresponding to message field names
00132     to set specific fields.
00133     """
00134     if args or kwds:
00135       super(CarDriveStamped, self).__init__(*args, **kwds)
00136       #message fields cannot be None, assign default values for those that are
00137       if self.header is None:
00138         self.header = std_msgs.msg.Header()
00139       if self.control is None:
00140         self.control = art_msgs.msg.CarDrive()
00141     else:
00142       self.header = std_msgs.msg.Header()
00143       self.control = art_msgs.msg.CarDrive()
00144 
00145   def _get_types(self):
00146     """
00147     internal API method
00148     """
00149     return self._slot_types
00150 
00151   def serialize(self, buff):
00152     """
00153     serialize message into buffer
00154     :param buff: buffer, ``StringIO``
00155     """
00156     try:
00157       _x = self
00158       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00159       _x = self.header.frame_id
00160       length = len(_x)
00161       if python3 or type(_x) == unicode:
00162         _x = _x.encode('utf-8')
00163         length = len(_x)
00164       buff.write(struct.pack('<I%ss'%length, length, _x))
00165       _x = self
00166       buff.write(_struct_4f2B.pack(_x.control.speed, _x.control.acceleration, _x.control.jerk, _x.control.steering_angle, _x.control.gear.value, _x.control.behavior.value))
00167     except struct.error as se: self._check_types(se)
00168     except TypeError as te: self._check_types(te)
00169 
00170   def deserialize(self, str):
00171     """
00172     unpack serialized message in str into this message instance
00173     :param str: byte array of serialized message, ``str``
00174     """
00175     try:
00176       if self.header is None:
00177         self.header = std_msgs.msg.Header()
00178       if self.control is None:
00179         self.control = art_msgs.msg.CarDrive()
00180       end = 0
00181       _x = self
00182       start = end
00183       end += 12
00184       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00185       start = end
00186       end += 4
00187       (length,) = _struct_I.unpack(str[start:end])
00188       start = end
00189       end += length
00190       if python3:
00191         self.header.frame_id = str[start:end].decode('utf-8')
00192       else:
00193         self.header.frame_id = str[start:end]
00194       _x = self
00195       start = end
00196       end += 18
00197       (_x.control.speed, _x.control.acceleration, _x.control.jerk, _x.control.steering_angle, _x.control.gear.value, _x.control.behavior.value,) = _struct_4f2B.unpack(str[start:end])
00198       return self
00199     except struct.error as e:
00200       raise genpy.DeserializationError(e) #most likely buffer underfill
00201 
00202 
00203   def serialize_numpy(self, buff, numpy):
00204     """
00205     serialize message with numpy array types into buffer
00206     :param buff: buffer, ``StringIO``
00207     :param numpy: numpy python module
00208     """
00209     try:
00210       _x = self
00211       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00212       _x = self.header.frame_id
00213       length = len(_x)
00214       if python3 or type(_x) == unicode:
00215         _x = _x.encode('utf-8')
00216         length = len(_x)
00217       buff.write(struct.pack('<I%ss'%length, length, _x))
00218       _x = self
00219       buff.write(_struct_4f2B.pack(_x.control.speed, _x.control.acceleration, _x.control.jerk, _x.control.steering_angle, _x.control.gear.value, _x.control.behavior.value))
00220     except struct.error as se: self._check_types(se)
00221     except TypeError as te: self._check_types(te)
00222 
00223   def deserialize_numpy(self, str, numpy):
00224     """
00225     unpack serialized message in str into this message instance using numpy for array types
00226     :param str: byte array of serialized message, ``str``
00227     :param numpy: numpy python module
00228     """
00229     try:
00230       if self.header is None:
00231         self.header = std_msgs.msg.Header()
00232       if self.control is None:
00233         self.control = art_msgs.msg.CarDrive()
00234       end = 0
00235       _x = self
00236       start = end
00237       end += 12
00238       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00239       start = end
00240       end += 4
00241       (length,) = _struct_I.unpack(str[start:end])
00242       start = end
00243       end += length
00244       if python3:
00245         self.header.frame_id = str[start:end].decode('utf-8')
00246       else:
00247         self.header.frame_id = str[start:end]
00248       _x = self
00249       start = end
00250       end += 18
00251       (_x.control.speed, _x.control.acceleration, _x.control.jerk, _x.control.steering_angle, _x.control.gear.value, _x.control.behavior.value,) = _struct_4f2B.unpack(str[start:end])
00252       return self
00253     except struct.error as e:
00254       raise genpy.DeserializationError(e) #most likely buffer underfill
00255 
00256 _struct_I = genpy.struct_I
00257 _struct_3I = struct.Struct("<3I")
00258 _struct_4f2B = struct.Struct("<4f2B")
 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