00001 """autogenerated by genmsg_py from PilotState.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 PilotState(roslib.message.Message):
00009 _md5sum = "c177b89612055fab019341d1fcc8bc65"
00010 _type = "art_msgs/PilotState"
00011 _has_header = True
00012 _full_text = """# ART pilot state message
00013
00014 # $Id: PilotState.msg 1541 2011-05-09 19:07:23Z jack.oquin $
00015
00016 Header header
00017
00018 DriverState pilot # pilot state
00019
00020 # current states of individual devices
00021 # (considered CLOSED if device not publishing)
00022 DriverState brake
00023 DriverState imu
00024 DriverState odom
00025 DriverState shifter
00026 DriverState steering
00027 DriverState throttle
00028
00029 # true if pilot preempted for learning speed control
00030 bool preempted
00031
00032 # latest commanded goal and current status
00033 CarDrive target # current command
00034 CarDrive plan # intermediate goal
00035 CarDrive current # current status
00036
00037 ================================================================================
00038 MSG: std_msgs/Header
00039 # Standard metadata for higher-level stamped data types.
00040 # This is generally used to communicate timestamped data
00041 # in a particular coordinate frame.
00042 #
00043 # sequence ID: consecutively increasing ID
00044 uint32 seq
00045 #Two-integer timestamp that is expressed as:
00046 # * stamp.secs: seconds (stamp_secs) since epoch
00047 # * stamp.nsecs: nanoseconds since stamp_secs
00048 # time-handling sugar is provided by the client library
00049 time stamp
00050 #Frame this data is associated with
00051 # 0: no frame
00052 # 1: global frame
00053 string frame_id
00054
00055 ================================================================================
00056 MSG: art_msgs/DriverState
00057 # ART driver states -- similar to those in driver_base.
00058
00059 # $Id: DriverState.msg 1161 2011-03-26 02:10:49Z jack.oquin $
00060
00061 # constants
00062 uint32 CLOSED = 0 # Not connected to the hardware
00063 uint32 OPENED = 1 # Passively connected to the hardware
00064 uint32 RUNNING = 2 # Sending hardware commands
00065
00066 uint32 state
00067
00068 ================================================================================
00069 MSG: art_msgs/CarDrive
00070 # Driving command for a car-like vehicle using Ackermann steering.
00071 # $Id: CarDrive.msg 1539 2011-05-09 04:09:20Z jack.oquin $
00072
00073 # Drive at requested speed, acceleration and jerk (the 1st, 2nd and
00074 # 3rd derivatives of position). All are non-negative scalars.
00075 #
00076 # Speed is defined as the scalar magnitude of the velocity
00077 # vector. Direction (forwards or backwards) is determined by the gear.
00078 #
00079 # Zero acceleration means change speed as quickly as
00080 # possible. Positive acceleration may include deceleration as needed
00081 # to match the desired speed. It represents a desired rate and also a
00082 # limit not to exceed.
00083 #
00084 # Zero jerk means change acceleration as quickly as possible. Positive
00085 # jerk describes the desired rate of acceleration change in both
00086 # directions (positive and negative).
00087 #
00088 float32 speed # magnitude of velocity vector (m/s)
00089 float32 acceleration # desired acceleration (m/s^2)
00090 float32 jerk # desired jerk (m/s^3)
00091
00092 # Assumes Ackermann (front-wheel) steering. This angle is the average
00093 # yaw of the two front wheels in the vehicle frame of reference
00094 # (positive left), ignoring their slightly differing angles as if it
00095 # were a tricycle. This is *not* the angle of the steering wheel
00096 # inside the passenger compartment.
00097 #
00098 float32 steering_angle # steering angle (radians)
00099
00100 Gear gear # requested gear (no change if Naught)
00101 PilotBehavior behavior # requested pilot behavior
00102
00103 ================================================================================
00104 MSG: art_msgs/Gear
00105 # ART vehicle transmission gear numbers
00106 #
00107 # Used by several different messages.
00108
00109 # $Id: Gear.msg 1539 2011-05-09 04:09:20Z jack.oquin $
00110
00111 # Gear numbers.
00112 #
00113 # Naught means: reset all Shifter relays; no change of CarDrive gear.
00114 uint8 Naught = 0
00115 uint8 Park = 1
00116 uint8 Reverse = 2
00117 uint8 Neutral = 3
00118 uint8 Drive = 4
00119 uint8 N_gears = 5
00120
00121 uint8 value # requested or reported gear number
00122
00123 ================================================================================
00124 MSG: art_msgs/PilotBehavior
00125 # ART autonomous vehicle pilot node behaviors.
00126 #
00127 # Normally, the pilot node does Run, continually sending commands to
00128 # the servo device actuators and monitoring their state. With Pause,
00129 # the pilot becomes passive, allowing a learning algorithm or human
00130 # controller direct access to those devices. In the Off state,
00131 # various devices are shut down: the transmission in Park, the brake
00132 # released, the throttle at idle. The engine is not turned off, but
00133 # it could be.
00134
00135 # $Id: PilotBehavior.msg 1539 2011-05-09 04:09:20Z jack.oquin $
00136
00137 # Behavior value
00138 uint8 value
00139
00140 # Behavior numbers:
00141 uint8 Run = 0 # normal driving
00142 uint8 Pause = 1 # stop issuing servo commands
00143 uint8 Off = 2 # turn off devices
00144 uint8 N_behaviors = 3
00145
00146 """
00147 __slots__ = ['header','pilot','brake','imu','odom','shifter','steering','throttle','preempted','target','plan','current']
00148 _slot_types = ['Header','art_msgs/DriverState','art_msgs/DriverState','art_msgs/DriverState','art_msgs/DriverState','art_msgs/DriverState','art_msgs/DriverState','art_msgs/DriverState','bool','art_msgs/CarDrive','art_msgs/CarDrive','art_msgs/CarDrive']
00149
00150 def __init__(self, *args, **kwds):
00151 """
00152 Constructor. Any message fields that are implicitly/explicitly
00153 set to None will be assigned a default value. The recommend
00154 use is keyword arguments as this is more robust to future message
00155 changes. You cannot mix in-order arguments and keyword arguments.
00156
00157 The available fields are:
00158 header,pilot,brake,imu,odom,shifter,steering,throttle,preempted,target,plan,current
00159
00160 @param args: complete set of field values, in .msg order
00161 @param kwds: use keyword arguments corresponding to message field names
00162 to set specific fields.
00163 """
00164 if args or kwds:
00165 super(PilotState, self).__init__(*args, **kwds)
00166
00167 if self.header is None:
00168 self.header = std_msgs.msg._Header.Header()
00169 if self.pilot is None:
00170 self.pilot = art_msgs.msg.DriverState()
00171 if self.brake is None:
00172 self.brake = art_msgs.msg.DriverState()
00173 if self.imu is None:
00174 self.imu = art_msgs.msg.DriverState()
00175 if self.odom is None:
00176 self.odom = art_msgs.msg.DriverState()
00177 if self.shifter is None:
00178 self.shifter = art_msgs.msg.DriverState()
00179 if self.steering is None:
00180 self.steering = art_msgs.msg.DriverState()
00181 if self.throttle is None:
00182 self.throttle = art_msgs.msg.DriverState()
00183 if self.preempted is None:
00184 self.preempted = False
00185 if self.target is None:
00186 self.target = art_msgs.msg.CarDrive()
00187 if self.plan is None:
00188 self.plan = art_msgs.msg.CarDrive()
00189 if self.current is None:
00190 self.current = art_msgs.msg.CarDrive()
00191 else:
00192 self.header = std_msgs.msg._Header.Header()
00193 self.pilot = art_msgs.msg.DriverState()
00194 self.brake = art_msgs.msg.DriverState()
00195 self.imu = art_msgs.msg.DriverState()
00196 self.odom = art_msgs.msg.DriverState()
00197 self.shifter = art_msgs.msg.DriverState()
00198 self.steering = art_msgs.msg.DriverState()
00199 self.throttle = art_msgs.msg.DriverState()
00200 self.preempted = False
00201 self.target = art_msgs.msg.CarDrive()
00202 self.plan = art_msgs.msg.CarDrive()
00203 self.current = art_msgs.msg.CarDrive()
00204
00205 def _get_types(self):
00206 """
00207 internal API method
00208 """
00209 return self._slot_types
00210
00211 def serialize(self, buff):
00212 """
00213 serialize message into buffer
00214 @param buff: buffer
00215 @type buff: StringIO
00216 """
00217 try:
00218 _x = self
00219 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00220 _x = self.header.frame_id
00221 length = len(_x)
00222 buff.write(struct.pack('<I%ss'%length, length, _x))
00223 _x = self
00224 buff.write(_struct_7IB4f2B4f2B4f2B.pack(_x.pilot.state, _x.brake.state, _x.imu.state, _x.odom.state, _x.shifter.state, _x.steering.state, _x.throttle.state, _x.preempted, _x.target.speed, _x.target.acceleration, _x.target.jerk, _x.target.steering_angle, _x.target.gear.value, _x.target.behavior.value, _x.plan.speed, _x.plan.acceleration, _x.plan.jerk, _x.plan.steering_angle, _x.plan.gear.value, _x.plan.behavior.value, _x.current.speed, _x.current.acceleration, _x.current.jerk, _x.current.steering_angle, _x.current.gear.value, _x.current.behavior.value))
00225 except struct.error, se: self._check_types(se)
00226 except TypeError, te: self._check_types(te)
00227
00228 def deserialize(self, str):
00229 """
00230 unpack serialized message in str into this message instance
00231 @param str: byte array of serialized message
00232 @type str: str
00233 """
00234 try:
00235 if self.header is None:
00236 self.header = std_msgs.msg._Header.Header()
00237 if self.pilot is None:
00238 self.pilot = art_msgs.msg.DriverState()
00239 if self.brake is None:
00240 self.brake = art_msgs.msg.DriverState()
00241 if self.imu is None:
00242 self.imu = art_msgs.msg.DriverState()
00243 if self.odom is None:
00244 self.odom = art_msgs.msg.DriverState()
00245 if self.shifter is None:
00246 self.shifter = art_msgs.msg.DriverState()
00247 if self.steering is None:
00248 self.steering = art_msgs.msg.DriverState()
00249 if self.throttle is None:
00250 self.throttle = art_msgs.msg.DriverState()
00251 if self.target is None:
00252 self.target = art_msgs.msg.CarDrive()
00253 if self.plan is None:
00254 self.plan = art_msgs.msg.CarDrive()
00255 if self.current is None:
00256 self.current = art_msgs.msg.CarDrive()
00257 end = 0
00258 _x = self
00259 start = end
00260 end += 12
00261 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00262 start = end
00263 end += 4
00264 (length,) = _struct_I.unpack(str[start:end])
00265 start = end
00266 end += length
00267 self.header.frame_id = str[start:end]
00268 _x = self
00269 start = end
00270 end += 83
00271 (_x.pilot.state, _x.brake.state, _x.imu.state, _x.odom.state, _x.shifter.state, _x.steering.state, _x.throttle.state, _x.preempted, _x.target.speed, _x.target.acceleration, _x.target.jerk, _x.target.steering_angle, _x.target.gear.value, _x.target.behavior.value, _x.plan.speed, _x.plan.acceleration, _x.plan.jerk, _x.plan.steering_angle, _x.plan.gear.value, _x.plan.behavior.value, _x.current.speed, _x.current.acceleration, _x.current.jerk, _x.current.steering_angle, _x.current.gear.value, _x.current.behavior.value,) = _struct_7IB4f2B4f2B4f2B.unpack(str[start:end])
00272 self.preempted = bool(self.preempted)
00273 return self
00274 except struct.error, e:
00275 raise roslib.message.DeserializationError(e)
00276
00277
00278 def serialize_numpy(self, buff, numpy):
00279 """
00280 serialize message with numpy array types into buffer
00281 @param buff: buffer
00282 @type buff: StringIO
00283 @param numpy: numpy python module
00284 @type numpy module
00285 """
00286 try:
00287 _x = self
00288 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00289 _x = self.header.frame_id
00290 length = len(_x)
00291 buff.write(struct.pack('<I%ss'%length, length, _x))
00292 _x = self
00293 buff.write(_struct_7IB4f2B4f2B4f2B.pack(_x.pilot.state, _x.brake.state, _x.imu.state, _x.odom.state, _x.shifter.state, _x.steering.state, _x.throttle.state, _x.preempted, _x.target.speed, _x.target.acceleration, _x.target.jerk, _x.target.steering_angle, _x.target.gear.value, _x.target.behavior.value, _x.plan.speed, _x.plan.acceleration, _x.plan.jerk, _x.plan.steering_angle, _x.plan.gear.value, _x.plan.behavior.value, _x.current.speed, _x.current.acceleration, _x.current.jerk, _x.current.steering_angle, _x.current.gear.value, _x.current.behavior.value))
00294 except struct.error, se: self._check_types(se)
00295 except TypeError, te: self._check_types(te)
00296
00297 def deserialize_numpy(self, str, numpy):
00298 """
00299 unpack serialized message in str into this message instance using numpy for array types
00300 @param str: byte array of serialized message
00301 @type str: str
00302 @param numpy: numpy python module
00303 @type numpy: module
00304 """
00305 try:
00306 if self.header is None:
00307 self.header = std_msgs.msg._Header.Header()
00308 if self.pilot is None:
00309 self.pilot = art_msgs.msg.DriverState()
00310 if self.brake is None:
00311 self.brake = art_msgs.msg.DriverState()
00312 if self.imu is None:
00313 self.imu = art_msgs.msg.DriverState()
00314 if self.odom is None:
00315 self.odom = art_msgs.msg.DriverState()
00316 if self.shifter is None:
00317 self.shifter = art_msgs.msg.DriverState()
00318 if self.steering is None:
00319 self.steering = art_msgs.msg.DriverState()
00320 if self.throttle is None:
00321 self.throttle = art_msgs.msg.DriverState()
00322 if self.target is None:
00323 self.target = art_msgs.msg.CarDrive()
00324 if self.plan is None:
00325 self.plan = art_msgs.msg.CarDrive()
00326 if self.current is None:
00327 self.current = art_msgs.msg.CarDrive()
00328 end = 0
00329 _x = self
00330 start = end
00331 end += 12
00332 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00333 start = end
00334 end += 4
00335 (length,) = _struct_I.unpack(str[start:end])
00336 start = end
00337 end += length
00338 self.header.frame_id = str[start:end]
00339 _x = self
00340 start = end
00341 end += 83
00342 (_x.pilot.state, _x.brake.state, _x.imu.state, _x.odom.state, _x.shifter.state, _x.steering.state, _x.throttle.state, _x.preempted, _x.target.speed, _x.target.acceleration, _x.target.jerk, _x.target.steering_angle, _x.target.gear.value, _x.target.behavior.value, _x.plan.speed, _x.plan.acceleration, _x.plan.jerk, _x.plan.steering_angle, _x.plan.gear.value, _x.plan.behavior.value, _x.current.speed, _x.current.acceleration, _x.current.jerk, _x.current.steering_angle, _x.current.gear.value, _x.current.behavior.value,) = _struct_7IB4f2B4f2B4f2B.unpack(str[start:end])
00343 self.preempted = bool(self.preempted)
00344 return self
00345 except struct.error, e:
00346 raise roslib.message.DeserializationError(e)
00347
00348 _struct_I = roslib.message.struct_I
00349 _struct_3I = struct.Struct("<3I")
00350 _struct_7IB4f2B4f2B4f2B = struct.Struct("<7IB4f2B4f2B4f2B")