$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-art_vehicle/doc_stacks/2013-03-01_14-08-11.497537/art_vehicle/art_msgs/msg/PilotState.msg */ 00002 #ifndef ART_MSGS_MESSAGE_PILOTSTATE_H 00003 #define ART_MSGS_MESSAGE_PILOTSTATE_H 00004 #include <string> 00005 #include <vector> 00006 #include <map> 00007 #include <ostream> 00008 #include "ros/serialization.h" 00009 #include "ros/builtin_message_traits.h" 00010 #include "ros/message_operations.h" 00011 #include "ros/time.h" 00012 00013 #include "ros/macros.h" 00014 00015 #include "ros/assert.h" 00016 00017 #include "std_msgs/Header.h" 00018 #include "art_msgs/DriverState.h" 00019 #include "art_msgs/DriverState.h" 00020 #include "art_msgs/DriverState.h" 00021 #include "art_msgs/DriverState.h" 00022 #include "art_msgs/DriverState.h" 00023 #include "art_msgs/DriverState.h" 00024 #include "art_msgs/DriverState.h" 00025 #include "art_msgs/CarDrive.h" 00026 #include "art_msgs/CarDrive.h" 00027 #include "art_msgs/CarDrive.h" 00028 00029 namespace art_msgs 00030 { 00031 template <class ContainerAllocator> 00032 struct PilotState_ { 00033 typedef PilotState_<ContainerAllocator> Type; 00034 00035 PilotState_() 00036 : header() 00037 , pilot() 00038 , brake() 00039 , imu() 00040 , odom() 00041 , shifter() 00042 , steering() 00043 , throttle() 00044 , preempted(false) 00045 , target() 00046 , plan() 00047 , current() 00048 { 00049 } 00050 00051 PilotState_(const ContainerAllocator& _alloc) 00052 : header(_alloc) 00053 , pilot(_alloc) 00054 , brake(_alloc) 00055 , imu(_alloc) 00056 , odom(_alloc) 00057 , shifter(_alloc) 00058 , steering(_alloc) 00059 , throttle(_alloc) 00060 , preempted(false) 00061 , target(_alloc) 00062 , plan(_alloc) 00063 , current(_alloc) 00064 { 00065 } 00066 00067 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00068 ::std_msgs::Header_<ContainerAllocator> header; 00069 00070 typedef ::art_msgs::DriverState_<ContainerAllocator> _pilot_type; 00071 ::art_msgs::DriverState_<ContainerAllocator> pilot; 00072 00073 typedef ::art_msgs::DriverState_<ContainerAllocator> _brake_type; 00074 ::art_msgs::DriverState_<ContainerAllocator> brake; 00075 00076 typedef ::art_msgs::DriverState_<ContainerAllocator> _imu_type; 00077 ::art_msgs::DriverState_<ContainerAllocator> imu; 00078 00079 typedef ::art_msgs::DriverState_<ContainerAllocator> _odom_type; 00080 ::art_msgs::DriverState_<ContainerAllocator> odom; 00081 00082 typedef ::art_msgs::DriverState_<ContainerAllocator> _shifter_type; 00083 ::art_msgs::DriverState_<ContainerAllocator> shifter; 00084 00085 typedef ::art_msgs::DriverState_<ContainerAllocator> _steering_type; 00086 ::art_msgs::DriverState_<ContainerAllocator> steering; 00087 00088 typedef ::art_msgs::DriverState_<ContainerAllocator> _throttle_type; 00089 ::art_msgs::DriverState_<ContainerAllocator> throttle; 00090 00091 typedef uint8_t _preempted_type; 00092 uint8_t preempted; 00093 00094 typedef ::art_msgs::CarDrive_<ContainerAllocator> _target_type; 00095 ::art_msgs::CarDrive_<ContainerAllocator> target; 00096 00097 typedef ::art_msgs::CarDrive_<ContainerAllocator> _plan_type; 00098 ::art_msgs::CarDrive_<ContainerAllocator> plan; 00099 00100 typedef ::art_msgs::CarDrive_<ContainerAllocator> _current_type; 00101 ::art_msgs::CarDrive_<ContainerAllocator> current; 00102 00103 00104 private: 00105 static const char* __s_getDataType_() { return "art_msgs/PilotState"; } 00106 public: 00107 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00108 00109 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00110 00111 private: 00112 static const char* __s_getMD5Sum_() { return "c177b89612055fab019341d1fcc8bc65"; } 00113 public: 00114 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00115 00116 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00117 00118 private: 00119 static const char* __s_getMessageDefinition_() { return "# ART pilot state message\n\ 00120 \n\ 00121 # $Id: PilotState.msg 1541 2011-05-09 19:07:23Z jack.oquin $\n\ 00122 \n\ 00123 Header header\n\ 00124 \n\ 00125 DriverState pilot # pilot state\n\ 00126 \n\ 00127 # current states of individual devices\n\ 00128 # (considered CLOSED if device not publishing)\n\ 00129 DriverState brake\n\ 00130 DriverState imu\n\ 00131 DriverState odom\n\ 00132 DriverState shifter\n\ 00133 DriverState steering\n\ 00134 DriverState throttle\n\ 00135 \n\ 00136 # true if pilot preempted for learning speed control\n\ 00137 bool preempted\n\ 00138 \n\ 00139 # latest commanded goal and current status\n\ 00140 CarDrive target # current command\n\ 00141 CarDrive plan # intermediate goal\n\ 00142 CarDrive current # current status\n\ 00143 \n\ 00144 ================================================================================\n\ 00145 MSG: std_msgs/Header\n\ 00146 # Standard metadata for higher-level stamped data types.\n\ 00147 # This is generally used to communicate timestamped data \n\ 00148 # in a particular coordinate frame.\n\ 00149 # \n\ 00150 # sequence ID: consecutively increasing ID \n\ 00151 uint32 seq\n\ 00152 #Two-integer timestamp that is expressed as:\n\ 00153 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00154 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00155 # time-handling sugar is provided by the client library\n\ 00156 time stamp\n\ 00157 #Frame this data is associated with\n\ 00158 # 0: no frame\n\ 00159 # 1: global frame\n\ 00160 string frame_id\n\ 00161 \n\ 00162 ================================================================================\n\ 00163 MSG: art_msgs/DriverState\n\ 00164 # ART driver states -- similar to those in driver_base.\n\ 00165 \n\ 00166 # $Id: DriverState.msg 1161 2011-03-26 02:10:49Z jack.oquin $\n\ 00167 \n\ 00168 # constants\n\ 00169 uint32 CLOSED = 0 # Not connected to the hardware\n\ 00170 uint32 OPENED = 1 # Passively connected to the hardware\n\ 00171 uint32 RUNNING = 2 # Sending hardware commands\n\ 00172 \n\ 00173 uint32 state\n\ 00174 \n\ 00175 ================================================================================\n\ 00176 MSG: art_msgs/CarDrive\n\ 00177 # Driving command for a car-like vehicle using Ackermann steering.\n\ 00178 # $Id: CarDrive.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\ 00179 \n\ 00180 # Drive at requested speed, acceleration and jerk (the 1st, 2nd and\n\ 00181 # 3rd derivatives of position). All are non-negative scalars. \n\ 00182 #\n\ 00183 # Speed is defined as the scalar magnitude of the velocity\n\ 00184 # vector. Direction (forwards or backwards) is determined by the gear.\n\ 00185 #\n\ 00186 # Zero acceleration means change speed as quickly as\n\ 00187 # possible. Positive acceleration may include deceleration as needed\n\ 00188 # to match the desired speed. It represents a desired rate and also a\n\ 00189 # limit not to exceed.\n\ 00190 #\n\ 00191 # Zero jerk means change acceleration as quickly as possible. Positive\n\ 00192 # jerk describes the desired rate of acceleration change in both\n\ 00193 # directions (positive and negative).\n\ 00194 #\n\ 00195 float32 speed # magnitude of velocity vector (m/s)\n\ 00196 float32 acceleration # desired acceleration (m/s^2)\n\ 00197 float32 jerk # desired jerk (m/s^3)\n\ 00198 \n\ 00199 # Assumes Ackermann (front-wheel) steering. This angle is the average\n\ 00200 # yaw of the two front wheels in the vehicle frame of reference\n\ 00201 # (positive left), ignoring their slightly differing angles as if it\n\ 00202 # were a tricycle. This is *not* the angle of the steering wheel\n\ 00203 # inside the passenger compartment.\n\ 00204 #\n\ 00205 float32 steering_angle # steering angle (radians)\n\ 00206 \n\ 00207 Gear gear # requested gear (no change if Naught)\n\ 00208 PilotBehavior behavior # requested pilot behavior\n\ 00209 \n\ 00210 ================================================================================\n\ 00211 MSG: art_msgs/Gear\n\ 00212 # ART vehicle transmission gear numbers\n\ 00213 #\n\ 00214 # Used by several different messages.\n\ 00215 \n\ 00216 # $Id: Gear.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\ 00217 \n\ 00218 # Gear numbers. \n\ 00219 #\n\ 00220 # Naught means: reset all Shifter relays; no change of CarDrive gear.\n\ 00221 uint8 Naught = 0\n\ 00222 uint8 Park = 1\n\ 00223 uint8 Reverse = 2\n\ 00224 uint8 Neutral = 3\n\ 00225 uint8 Drive = 4\n\ 00226 uint8 N_gears = 5\n\ 00227 \n\ 00228 uint8 value # requested or reported gear number\n\ 00229 \n\ 00230 ================================================================================\n\ 00231 MSG: art_msgs/PilotBehavior\n\ 00232 # ART autonomous vehicle pilot node behaviors.\n\ 00233 #\n\ 00234 # Normally, the pilot node does Run, continually sending commands to\n\ 00235 # the servo device actuators and monitoring their state. With Pause,\n\ 00236 # the pilot becomes passive, allowing a learning algorithm or human\n\ 00237 # controller direct access to those devices. In the Off state,\n\ 00238 # various devices are shut down: the transmission in Park, the brake\n\ 00239 # released, the throttle at idle. The engine is not turned off, but\n\ 00240 # it could be.\n\ 00241 \n\ 00242 # $Id: PilotBehavior.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\ 00243 \n\ 00244 # Behavior value\n\ 00245 uint8 value\n\ 00246 \n\ 00247 # Behavior numbers:\n\ 00248 uint8 Run = 0 # normal driving\n\ 00249 uint8 Pause = 1 # stop issuing servo commands\n\ 00250 uint8 Off = 2 # turn off devices\n\ 00251 uint8 N_behaviors = 3\n\ 00252 \n\ 00253 "; } 00254 public: 00255 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00256 00257 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00258 00259 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00260 { 00261 ros::serialization::OStream stream(write_ptr, 1000000000); 00262 ros::serialization::serialize(stream, header); 00263 ros::serialization::serialize(stream, pilot); 00264 ros::serialization::serialize(stream, brake); 00265 ros::serialization::serialize(stream, imu); 00266 ros::serialization::serialize(stream, odom); 00267 ros::serialization::serialize(stream, shifter); 00268 ros::serialization::serialize(stream, steering); 00269 ros::serialization::serialize(stream, throttle); 00270 ros::serialization::serialize(stream, preempted); 00271 ros::serialization::serialize(stream, target); 00272 ros::serialization::serialize(stream, plan); 00273 ros::serialization::serialize(stream, current); 00274 return stream.getData(); 00275 } 00276 00277 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00278 { 00279 ros::serialization::IStream stream(read_ptr, 1000000000); 00280 ros::serialization::deserialize(stream, header); 00281 ros::serialization::deserialize(stream, pilot); 00282 ros::serialization::deserialize(stream, brake); 00283 ros::serialization::deserialize(stream, imu); 00284 ros::serialization::deserialize(stream, odom); 00285 ros::serialization::deserialize(stream, shifter); 00286 ros::serialization::deserialize(stream, steering); 00287 ros::serialization::deserialize(stream, throttle); 00288 ros::serialization::deserialize(stream, preempted); 00289 ros::serialization::deserialize(stream, target); 00290 ros::serialization::deserialize(stream, plan); 00291 ros::serialization::deserialize(stream, current); 00292 return stream.getData(); 00293 } 00294 00295 ROS_DEPRECATED virtual uint32_t serializationLength() const 00296 { 00297 uint32_t size = 0; 00298 size += ros::serialization::serializationLength(header); 00299 size += ros::serialization::serializationLength(pilot); 00300 size += ros::serialization::serializationLength(brake); 00301 size += ros::serialization::serializationLength(imu); 00302 size += ros::serialization::serializationLength(odom); 00303 size += ros::serialization::serializationLength(shifter); 00304 size += ros::serialization::serializationLength(steering); 00305 size += ros::serialization::serializationLength(throttle); 00306 size += ros::serialization::serializationLength(preempted); 00307 size += ros::serialization::serializationLength(target); 00308 size += ros::serialization::serializationLength(plan); 00309 size += ros::serialization::serializationLength(current); 00310 return size; 00311 } 00312 00313 typedef boost::shared_ptr< ::art_msgs::PilotState_<ContainerAllocator> > Ptr; 00314 typedef boost::shared_ptr< ::art_msgs::PilotState_<ContainerAllocator> const> ConstPtr; 00315 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00316 }; // struct PilotState 00317 typedef ::art_msgs::PilotState_<std::allocator<void> > PilotState; 00318 00319 typedef boost::shared_ptr< ::art_msgs::PilotState> PilotStatePtr; 00320 typedef boost::shared_ptr< ::art_msgs::PilotState const> PilotStateConstPtr; 00321 00322 00323 template<typename ContainerAllocator> 00324 std::ostream& operator<<(std::ostream& s, const ::art_msgs::PilotState_<ContainerAllocator> & v) 00325 { 00326 ros::message_operations::Printer< ::art_msgs::PilotState_<ContainerAllocator> >::stream(s, "", v); 00327 return s;} 00328 00329 } // namespace art_msgs 00330 00331 namespace ros 00332 { 00333 namespace message_traits 00334 { 00335 template<class ContainerAllocator> struct IsMessage< ::art_msgs::PilotState_<ContainerAllocator> > : public TrueType {}; 00336 template<class ContainerAllocator> struct IsMessage< ::art_msgs::PilotState_<ContainerAllocator> const> : public TrueType {}; 00337 template<class ContainerAllocator> 00338 struct MD5Sum< ::art_msgs::PilotState_<ContainerAllocator> > { 00339 static const char* value() 00340 { 00341 return "c177b89612055fab019341d1fcc8bc65"; 00342 } 00343 00344 static const char* value(const ::art_msgs::PilotState_<ContainerAllocator> &) { return value(); } 00345 static const uint64_t static_value1 = 0xc177b89612055fabULL; 00346 static const uint64_t static_value2 = 0x019341d1fcc8bc65ULL; 00347 }; 00348 00349 template<class ContainerAllocator> 00350 struct DataType< ::art_msgs::PilotState_<ContainerAllocator> > { 00351 static const char* value() 00352 { 00353 return "art_msgs/PilotState"; 00354 } 00355 00356 static const char* value(const ::art_msgs::PilotState_<ContainerAllocator> &) { return value(); } 00357 }; 00358 00359 template<class ContainerAllocator> 00360 struct Definition< ::art_msgs::PilotState_<ContainerAllocator> > { 00361 static const char* value() 00362 { 00363 return "# ART pilot state message\n\ 00364 \n\ 00365 # $Id: PilotState.msg 1541 2011-05-09 19:07:23Z jack.oquin $\n\ 00366 \n\ 00367 Header header\n\ 00368 \n\ 00369 DriverState pilot # pilot state\n\ 00370 \n\ 00371 # current states of individual devices\n\ 00372 # (considered CLOSED if device not publishing)\n\ 00373 DriverState brake\n\ 00374 DriverState imu\n\ 00375 DriverState odom\n\ 00376 DriverState shifter\n\ 00377 DriverState steering\n\ 00378 DriverState throttle\n\ 00379 \n\ 00380 # true if pilot preempted for learning speed control\n\ 00381 bool preempted\n\ 00382 \n\ 00383 # latest commanded goal and current status\n\ 00384 CarDrive target # current command\n\ 00385 CarDrive plan # intermediate goal\n\ 00386 CarDrive current # current status\n\ 00387 \n\ 00388 ================================================================================\n\ 00389 MSG: std_msgs/Header\n\ 00390 # Standard metadata for higher-level stamped data types.\n\ 00391 # This is generally used to communicate timestamped data \n\ 00392 # in a particular coordinate frame.\n\ 00393 # \n\ 00394 # sequence ID: consecutively increasing ID \n\ 00395 uint32 seq\n\ 00396 #Two-integer timestamp that is expressed as:\n\ 00397 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00398 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00399 # time-handling sugar is provided by the client library\n\ 00400 time stamp\n\ 00401 #Frame this data is associated with\n\ 00402 # 0: no frame\n\ 00403 # 1: global frame\n\ 00404 string frame_id\n\ 00405 \n\ 00406 ================================================================================\n\ 00407 MSG: art_msgs/DriverState\n\ 00408 # ART driver states -- similar to those in driver_base.\n\ 00409 \n\ 00410 # $Id: DriverState.msg 1161 2011-03-26 02:10:49Z jack.oquin $\n\ 00411 \n\ 00412 # constants\n\ 00413 uint32 CLOSED = 0 # Not connected to the hardware\n\ 00414 uint32 OPENED = 1 # Passively connected to the hardware\n\ 00415 uint32 RUNNING = 2 # Sending hardware commands\n\ 00416 \n\ 00417 uint32 state\n\ 00418 \n\ 00419 ================================================================================\n\ 00420 MSG: art_msgs/CarDrive\n\ 00421 # Driving command for a car-like vehicle using Ackermann steering.\n\ 00422 # $Id: CarDrive.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\ 00423 \n\ 00424 # Drive at requested speed, acceleration and jerk (the 1st, 2nd and\n\ 00425 # 3rd derivatives of position). All are non-negative scalars. \n\ 00426 #\n\ 00427 # Speed is defined as the scalar magnitude of the velocity\n\ 00428 # vector. Direction (forwards or backwards) is determined by the gear.\n\ 00429 #\n\ 00430 # Zero acceleration means change speed as quickly as\n\ 00431 # possible. Positive acceleration may include deceleration as needed\n\ 00432 # to match the desired speed. It represents a desired rate and also a\n\ 00433 # limit not to exceed.\n\ 00434 #\n\ 00435 # Zero jerk means change acceleration as quickly as possible. Positive\n\ 00436 # jerk describes the desired rate of acceleration change in both\n\ 00437 # directions (positive and negative).\n\ 00438 #\n\ 00439 float32 speed # magnitude of velocity vector (m/s)\n\ 00440 float32 acceleration # desired acceleration (m/s^2)\n\ 00441 float32 jerk # desired jerk (m/s^3)\n\ 00442 \n\ 00443 # Assumes Ackermann (front-wheel) steering. This angle is the average\n\ 00444 # yaw of the two front wheels in the vehicle frame of reference\n\ 00445 # (positive left), ignoring their slightly differing angles as if it\n\ 00446 # were a tricycle. This is *not* the angle of the steering wheel\n\ 00447 # inside the passenger compartment.\n\ 00448 #\n\ 00449 float32 steering_angle # steering angle (radians)\n\ 00450 \n\ 00451 Gear gear # requested gear (no change if Naught)\n\ 00452 PilotBehavior behavior # requested pilot behavior\n\ 00453 \n\ 00454 ================================================================================\n\ 00455 MSG: art_msgs/Gear\n\ 00456 # ART vehicle transmission gear numbers\n\ 00457 #\n\ 00458 # Used by several different messages.\n\ 00459 \n\ 00460 # $Id: Gear.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\ 00461 \n\ 00462 # Gear numbers. \n\ 00463 #\n\ 00464 # Naught means: reset all Shifter relays; no change of CarDrive gear.\n\ 00465 uint8 Naught = 0\n\ 00466 uint8 Park = 1\n\ 00467 uint8 Reverse = 2\n\ 00468 uint8 Neutral = 3\n\ 00469 uint8 Drive = 4\n\ 00470 uint8 N_gears = 5\n\ 00471 \n\ 00472 uint8 value # requested or reported gear number\n\ 00473 \n\ 00474 ================================================================================\n\ 00475 MSG: art_msgs/PilotBehavior\n\ 00476 # ART autonomous vehicle pilot node behaviors.\n\ 00477 #\n\ 00478 # Normally, the pilot node does Run, continually sending commands to\n\ 00479 # the servo device actuators and monitoring their state. With Pause,\n\ 00480 # the pilot becomes passive, allowing a learning algorithm or human\n\ 00481 # controller direct access to those devices. In the Off state,\n\ 00482 # various devices are shut down: the transmission in Park, the brake\n\ 00483 # released, the throttle at idle. The engine is not turned off, but\n\ 00484 # it could be.\n\ 00485 \n\ 00486 # $Id: PilotBehavior.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\ 00487 \n\ 00488 # Behavior value\n\ 00489 uint8 value\n\ 00490 \n\ 00491 # Behavior numbers:\n\ 00492 uint8 Run = 0 # normal driving\n\ 00493 uint8 Pause = 1 # stop issuing servo commands\n\ 00494 uint8 Off = 2 # turn off devices\n\ 00495 uint8 N_behaviors = 3\n\ 00496 \n\ 00497 "; 00498 } 00499 00500 static const char* value(const ::art_msgs::PilotState_<ContainerAllocator> &) { return value(); } 00501 }; 00502 00503 template<class ContainerAllocator> struct HasHeader< ::art_msgs::PilotState_<ContainerAllocator> > : public TrueType {}; 00504 template<class ContainerAllocator> struct HasHeader< const ::art_msgs::PilotState_<ContainerAllocator> > : public TrueType {}; 00505 } // namespace message_traits 00506 } // namespace ros 00507 00508 namespace ros 00509 { 00510 namespace serialization 00511 { 00512 00513 template<class ContainerAllocator> struct Serializer< ::art_msgs::PilotState_<ContainerAllocator> > 00514 { 00515 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00516 { 00517 stream.next(m.header); 00518 stream.next(m.pilot); 00519 stream.next(m.brake); 00520 stream.next(m.imu); 00521 stream.next(m.odom); 00522 stream.next(m.shifter); 00523 stream.next(m.steering); 00524 stream.next(m.throttle); 00525 stream.next(m.preempted); 00526 stream.next(m.target); 00527 stream.next(m.plan); 00528 stream.next(m.current); 00529 } 00530 00531 ROS_DECLARE_ALLINONE_SERIALIZER; 00532 }; // struct PilotState_ 00533 } // namespace serialization 00534 } // namespace ros 00535 00536 namespace ros 00537 { 00538 namespace message_operations 00539 { 00540 00541 template<class ContainerAllocator> 00542 struct Printer< ::art_msgs::PilotState_<ContainerAllocator> > 00543 { 00544 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::art_msgs::PilotState_<ContainerAllocator> & v) 00545 { 00546 s << indent << "header: "; 00547 s << std::endl; 00548 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00549 s << indent << "pilot: "; 00550 s << std::endl; 00551 Printer< ::art_msgs::DriverState_<ContainerAllocator> >::stream(s, indent + " ", v.pilot); 00552 s << indent << "brake: "; 00553 s << std::endl; 00554 Printer< ::art_msgs::DriverState_<ContainerAllocator> >::stream(s, indent + " ", v.brake); 00555 s << indent << "imu: "; 00556 s << std::endl; 00557 Printer< ::art_msgs::DriverState_<ContainerAllocator> >::stream(s, indent + " ", v.imu); 00558 s << indent << "odom: "; 00559 s << std::endl; 00560 Printer< ::art_msgs::DriverState_<ContainerAllocator> >::stream(s, indent + " ", v.odom); 00561 s << indent << "shifter: "; 00562 s << std::endl; 00563 Printer< ::art_msgs::DriverState_<ContainerAllocator> >::stream(s, indent + " ", v.shifter); 00564 s << indent << "steering: "; 00565 s << std::endl; 00566 Printer< ::art_msgs::DriverState_<ContainerAllocator> >::stream(s, indent + " ", v.steering); 00567 s << indent << "throttle: "; 00568 s << std::endl; 00569 Printer< ::art_msgs::DriverState_<ContainerAllocator> >::stream(s, indent + " ", v.throttle); 00570 s << indent << "preempted: "; 00571 Printer<uint8_t>::stream(s, indent + " ", v.preempted); 00572 s << indent << "target: "; 00573 s << std::endl; 00574 Printer< ::art_msgs::CarDrive_<ContainerAllocator> >::stream(s, indent + " ", v.target); 00575 s << indent << "plan: "; 00576 s << std::endl; 00577 Printer< ::art_msgs::CarDrive_<ContainerAllocator> >::stream(s, indent + " ", v.plan); 00578 s << indent << "current: "; 00579 s << std::endl; 00580 Printer< ::art_msgs::CarDrive_<ContainerAllocator> >::stream(s, indent + " ", v.current); 00581 } 00582 }; 00583 00584 00585 } // namespace message_operations 00586 } // namespace ros 00587 00588 #endif // ART_MSGS_MESSAGE_PILOTSTATE_H 00589