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