00001
00002 #ifndef ART_MSGS_MESSAGE_CARDRIVESTAMPED_H
00003 #define ART_MSGS_MESSAGE_CARDRIVESTAMPED_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "std_msgs/Header.h"
00014 #include "art_msgs/CarDrive.h"
00015
00016 namespace art_msgs
00017 {
00018 template <class ContainerAllocator>
00019 struct CarDriveStamped_ : public ros::Message
00020 {
00021 typedef CarDriveStamped_<ContainerAllocator> Type;
00022
00023 CarDriveStamped_()
00024 : header()
00025 , control()
00026 {
00027 }
00028
00029 CarDriveStamped_(const ContainerAllocator& _alloc)
00030 : header(_alloc)
00031 , control(_alloc)
00032 {
00033 }
00034
00035 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00036 ::std_msgs::Header_<ContainerAllocator> header;
00037
00038 typedef ::art_msgs::CarDrive_<ContainerAllocator> _control_type;
00039 ::art_msgs::CarDrive_<ContainerAllocator> control;
00040
00041
00042 private:
00043 static const char* __s_getDataType_() { return "art_msgs/CarDriveStamped"; }
00044 public:
00045 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00046
00047 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00048
00049 private:
00050 static const char* __s_getMD5Sum_() { return "d243ac5e38754a52c8788d4d37db7a05"; }
00051 public:
00052 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00053
00054 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00055
00056 private:
00057 static const char* __s_getMessageDefinition_() { return "# CarDrive message with timestamp.\n\
00058 # $Id: CarDriveStamped.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\
00059 \n\
00060 Header header\n\
00061 CarDrive control\n\
00062 \n\
00063 ================================================================================\n\
00064 MSG: std_msgs/Header\n\
00065 # Standard metadata for higher-level stamped data types.\n\
00066 # This is generally used to communicate timestamped data \n\
00067 # in a particular coordinate frame.\n\
00068 # \n\
00069 # sequence ID: consecutively increasing ID \n\
00070 uint32 seq\n\
00071 #Two-integer timestamp that is expressed as:\n\
00072 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00073 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00074 # time-handling sugar is provided by the client library\n\
00075 time stamp\n\
00076 #Frame this data is associated with\n\
00077 # 0: no frame\n\
00078 # 1: global frame\n\
00079 string frame_id\n\
00080 \n\
00081 ================================================================================\n\
00082 MSG: art_msgs/CarDrive\n\
00083 # Driving command for a car-like vehicle using Ackermann steering.\n\
00084 # $Id: CarDrive.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\
00085 \n\
00086 # Drive at requested speed, acceleration and jerk (the 1st, 2nd and\n\
00087 # 3rd derivatives of position). All are non-negative scalars. \n\
00088 #\n\
00089 # Speed is defined as the scalar magnitude of the velocity\n\
00090 # vector. Direction (forwards or backwards) is determined by the gear.\n\
00091 #\n\
00092 # Zero acceleration means change speed as quickly as\n\
00093 # possible. Positive acceleration may include deceleration as needed\n\
00094 # to match the desired speed. It represents a desired rate and also a\n\
00095 # limit not to exceed.\n\
00096 #\n\
00097 # Zero jerk means change acceleration as quickly as possible. Positive\n\
00098 # jerk describes the desired rate of acceleration change in both\n\
00099 # directions (positive and negative).\n\
00100 #\n\
00101 float32 speed # magnitude of velocity vector (m/s)\n\
00102 float32 acceleration # desired acceleration (m/s^2)\n\
00103 float32 jerk # desired jerk (m/s^3)\n\
00104 \n\
00105 # Assumes Ackermann (front-wheel) steering. This angle is the average\n\
00106 # yaw of the two front wheels in the vehicle frame of reference\n\
00107 # (positive left), ignoring their slightly differing angles as if it\n\
00108 # were a tricycle. This is *not* the angle of the steering wheel\n\
00109 # inside the passenger compartment.\n\
00110 #\n\
00111 float32 steering_angle # steering angle (radians)\n\
00112 \n\
00113 Gear gear # requested gear (no change if Naught)\n\
00114 PilotBehavior behavior # requested pilot behavior\n\
00115 \n\
00116 ================================================================================\n\
00117 MSG: art_msgs/Gear\n\
00118 # ART vehicle transmission gear numbers\n\
00119 #\n\
00120 # Used by several different messages.\n\
00121 \n\
00122 # $Id: Gear.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\
00123 \n\
00124 # Gear numbers. \n\
00125 #\n\
00126 # Naught means: reset all Shifter relays; no change of CarDrive gear.\n\
00127 uint8 Naught = 0\n\
00128 uint8 Park = 1\n\
00129 uint8 Reverse = 2\n\
00130 uint8 Neutral = 3\n\
00131 uint8 Drive = 4\n\
00132 uint8 N_gears = 5\n\
00133 \n\
00134 uint8 value # requested or reported gear number\n\
00135 \n\
00136 ================================================================================\n\
00137 MSG: art_msgs/PilotBehavior\n\
00138 # ART autonomous vehicle pilot node behaviors.\n\
00139 #\n\
00140 # Normally, the pilot node does Run, continually sending commands to\n\
00141 # the servo device actuators and monitoring their state. With Pause,\n\
00142 # the pilot becomes passive, allowing a learning algorithm or human\n\
00143 # controller direct access to those devices. In the Off state,\n\
00144 # various devices are shut down: the transmission in Park, the brake\n\
00145 # released, the throttle at idle. The engine is not turned off, but\n\
00146 # it could be.\n\
00147 \n\
00148 # $Id: PilotBehavior.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\
00149 \n\
00150 # Behavior value\n\
00151 uint8 value\n\
00152 \n\
00153 # Behavior numbers:\n\
00154 uint8 Run = 0 # normal driving\n\
00155 uint8 Pause = 1 # stop issuing servo commands\n\
00156 uint8 Off = 2 # turn off devices\n\
00157 uint8 N_behaviors = 3\n\
00158 \n\
00159 "; }
00160 public:
00161 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00162
00163 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00164
00165 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00166 {
00167 ros::serialization::OStream stream(write_ptr, 1000000000);
00168 ros::serialization::serialize(stream, header);
00169 ros::serialization::serialize(stream, control);
00170 return stream.getData();
00171 }
00172
00173 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00174 {
00175 ros::serialization::IStream stream(read_ptr, 1000000000);
00176 ros::serialization::deserialize(stream, header);
00177 ros::serialization::deserialize(stream, control);
00178 return stream.getData();
00179 }
00180
00181 ROS_DEPRECATED virtual uint32_t serializationLength() const
00182 {
00183 uint32_t size = 0;
00184 size += ros::serialization::serializationLength(header);
00185 size += ros::serialization::serializationLength(control);
00186 return size;
00187 }
00188
00189 typedef boost::shared_ptr< ::art_msgs::CarDriveStamped_<ContainerAllocator> > Ptr;
00190 typedef boost::shared_ptr< ::art_msgs::CarDriveStamped_<ContainerAllocator> const> ConstPtr;
00191 };
00192 typedef ::art_msgs::CarDriveStamped_<std::allocator<void> > CarDriveStamped;
00193
00194 typedef boost::shared_ptr< ::art_msgs::CarDriveStamped> CarDriveStampedPtr;
00195 typedef boost::shared_ptr< ::art_msgs::CarDriveStamped const> CarDriveStampedConstPtr;
00196
00197
00198 template<typename ContainerAllocator>
00199 std::ostream& operator<<(std::ostream& s, const ::art_msgs::CarDriveStamped_<ContainerAllocator> & v)
00200 {
00201 ros::message_operations::Printer< ::art_msgs::CarDriveStamped_<ContainerAllocator> >::stream(s, "", v);
00202 return s;}
00203
00204 }
00205
00206 namespace ros
00207 {
00208 namespace message_traits
00209 {
00210 template<class ContainerAllocator>
00211 struct MD5Sum< ::art_msgs::CarDriveStamped_<ContainerAllocator> > {
00212 static const char* value()
00213 {
00214 return "d243ac5e38754a52c8788d4d37db7a05";
00215 }
00216
00217 static const char* value(const ::art_msgs::CarDriveStamped_<ContainerAllocator> &) { return value(); }
00218 static const uint64_t static_value1 = 0xd243ac5e38754a52ULL;
00219 static const uint64_t static_value2 = 0xc8788d4d37db7a05ULL;
00220 };
00221
00222 template<class ContainerAllocator>
00223 struct DataType< ::art_msgs::CarDriveStamped_<ContainerAllocator> > {
00224 static const char* value()
00225 {
00226 return "art_msgs/CarDriveStamped";
00227 }
00228
00229 static const char* value(const ::art_msgs::CarDriveStamped_<ContainerAllocator> &) { return value(); }
00230 };
00231
00232 template<class ContainerAllocator>
00233 struct Definition< ::art_msgs::CarDriveStamped_<ContainerAllocator> > {
00234 static const char* value()
00235 {
00236 return "# CarDrive message with timestamp.\n\
00237 # $Id: CarDriveStamped.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\
00238 \n\
00239 Header header\n\
00240 CarDrive control\n\
00241 \n\
00242 ================================================================================\n\
00243 MSG: std_msgs/Header\n\
00244 # Standard metadata for higher-level stamped data types.\n\
00245 # This is generally used to communicate timestamped data \n\
00246 # in a particular coordinate frame.\n\
00247 # \n\
00248 # sequence ID: consecutively increasing ID \n\
00249 uint32 seq\n\
00250 #Two-integer timestamp that is expressed as:\n\
00251 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00252 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00253 # time-handling sugar is provided by the client library\n\
00254 time stamp\n\
00255 #Frame this data is associated with\n\
00256 # 0: no frame\n\
00257 # 1: global frame\n\
00258 string frame_id\n\
00259 \n\
00260 ================================================================================\n\
00261 MSG: art_msgs/CarDrive\n\
00262 # Driving command for a car-like vehicle using Ackermann steering.\n\
00263 # $Id: CarDrive.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\
00264 \n\
00265 # Drive at requested speed, acceleration and jerk (the 1st, 2nd and\n\
00266 # 3rd derivatives of position). All are non-negative scalars. \n\
00267 #\n\
00268 # Speed is defined as the scalar magnitude of the velocity\n\
00269 # vector. Direction (forwards or backwards) is determined by the gear.\n\
00270 #\n\
00271 # Zero acceleration means change speed as quickly as\n\
00272 # possible. Positive acceleration may include deceleration as needed\n\
00273 # to match the desired speed. It represents a desired rate and also a\n\
00274 # limit not to exceed.\n\
00275 #\n\
00276 # Zero jerk means change acceleration as quickly as possible. Positive\n\
00277 # jerk describes the desired rate of acceleration change in both\n\
00278 # directions (positive and negative).\n\
00279 #\n\
00280 float32 speed # magnitude of velocity vector (m/s)\n\
00281 float32 acceleration # desired acceleration (m/s^2)\n\
00282 float32 jerk # desired jerk (m/s^3)\n\
00283 \n\
00284 # Assumes Ackermann (front-wheel) steering. This angle is the average\n\
00285 # yaw of the two front wheels in the vehicle frame of reference\n\
00286 # (positive left), ignoring their slightly differing angles as if it\n\
00287 # were a tricycle. This is *not* the angle of the steering wheel\n\
00288 # inside the passenger compartment.\n\
00289 #\n\
00290 float32 steering_angle # steering angle (radians)\n\
00291 \n\
00292 Gear gear # requested gear (no change if Naught)\n\
00293 PilotBehavior behavior # requested pilot behavior\n\
00294 \n\
00295 ================================================================================\n\
00296 MSG: art_msgs/Gear\n\
00297 # ART vehicle transmission gear numbers\n\
00298 #\n\
00299 # Used by several different messages.\n\
00300 \n\
00301 # $Id: Gear.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\
00302 \n\
00303 # Gear numbers. \n\
00304 #\n\
00305 # Naught means: reset all Shifter relays; no change of CarDrive gear.\n\
00306 uint8 Naught = 0\n\
00307 uint8 Park = 1\n\
00308 uint8 Reverse = 2\n\
00309 uint8 Neutral = 3\n\
00310 uint8 Drive = 4\n\
00311 uint8 N_gears = 5\n\
00312 \n\
00313 uint8 value # requested or reported gear number\n\
00314 \n\
00315 ================================================================================\n\
00316 MSG: art_msgs/PilotBehavior\n\
00317 # ART autonomous vehicle pilot node behaviors.\n\
00318 #\n\
00319 # Normally, the pilot node does Run, continually sending commands to\n\
00320 # the servo device actuators and monitoring their state. With Pause,\n\
00321 # the pilot becomes passive, allowing a learning algorithm or human\n\
00322 # controller direct access to those devices. In the Off state,\n\
00323 # various devices are shut down: the transmission in Park, the brake\n\
00324 # released, the throttle at idle. The engine is not turned off, but\n\
00325 # it could be.\n\
00326 \n\
00327 # $Id: PilotBehavior.msg 1539 2011-05-09 04:09:20Z jack.oquin $\n\
00328 \n\
00329 # Behavior value\n\
00330 uint8 value\n\
00331 \n\
00332 # Behavior numbers:\n\
00333 uint8 Run = 0 # normal driving\n\
00334 uint8 Pause = 1 # stop issuing servo commands\n\
00335 uint8 Off = 2 # turn off devices\n\
00336 uint8 N_behaviors = 3\n\
00337 \n\
00338 ";
00339 }
00340
00341 static const char* value(const ::art_msgs::CarDriveStamped_<ContainerAllocator> &) { return value(); }
00342 };
00343
00344 template<class ContainerAllocator> struct HasHeader< ::art_msgs::CarDriveStamped_<ContainerAllocator> > : public TrueType {};
00345 template<class ContainerAllocator> struct HasHeader< const ::art_msgs::CarDriveStamped_<ContainerAllocator> > : public TrueType {};
00346 }
00347 }
00348
00349 namespace ros
00350 {
00351 namespace serialization
00352 {
00353
00354 template<class ContainerAllocator> struct Serializer< ::art_msgs::CarDriveStamped_<ContainerAllocator> >
00355 {
00356 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00357 {
00358 stream.next(m.header);
00359 stream.next(m.control);
00360 }
00361
00362 ROS_DECLARE_ALLINONE_SERIALIZER;
00363 };
00364 }
00365 }
00366
00367 namespace ros
00368 {
00369 namespace message_operations
00370 {
00371
00372 template<class ContainerAllocator>
00373 struct Printer< ::art_msgs::CarDriveStamped_<ContainerAllocator> >
00374 {
00375 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::art_msgs::CarDriveStamped_<ContainerAllocator> & v)
00376 {
00377 s << indent << "header: ";
00378 s << std::endl;
00379 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00380 s << indent << "control: ";
00381 s << std::endl;
00382 Printer< ::art_msgs::CarDrive_<ContainerAllocator> >::stream(s, indent + " ", v.control);
00383 }
00384 };
00385
00386
00387 }
00388 }
00389
00390 #endif // ART_MSGS_MESSAGE_CARDRIVESTAMPED_H
00391