00001
00002 #ifndef CLEARPATH_BASE_MESSAGE_DIFFERENTIALSPEED_H
00003 #define CLEARPATH_BASE_MESSAGE_DIFFERENTIALSPEED_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
00015 namespace clearpath_base
00016 {
00017 template <class ContainerAllocator>
00018 struct DifferentialSpeed_ : public ros::Message
00019 {
00020 typedef DifferentialSpeed_<ContainerAllocator> Type;
00021
00022 DifferentialSpeed_()
00023 : header()
00024 , left_speed(0.0)
00025 , right_speed(0.0)
00026 , left_accel(0.0)
00027 , right_accel(0.0)
00028 {
00029 }
00030
00031 DifferentialSpeed_(const ContainerAllocator& _alloc)
00032 : header(_alloc)
00033 , left_speed(0.0)
00034 , right_speed(0.0)
00035 , left_accel(0.0)
00036 , right_accel(0.0)
00037 {
00038 }
00039
00040 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00041 ::std_msgs::Header_<ContainerAllocator> header;
00042
00043 typedef double _left_speed_type;
00044 double left_speed;
00045
00046 typedef double _right_speed_type;
00047 double right_speed;
00048
00049 typedef double _left_accel_type;
00050 double left_accel;
00051
00052 typedef double _right_accel_type;
00053 double right_accel;
00054
00055
00056 private:
00057 static const char* __s_getDataType_() { return "clearpath_base/DifferentialSpeed"; }
00058 public:
00059 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00060
00061 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00062
00063 private:
00064 static const char* __s_getMD5Sum_() { return "4b62e763320bacb9c7f63f6ebd46ceba"; }
00065 public:
00066 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00067
00068 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00069
00070 private:
00071 static const char* __s_getMessageDefinition_() { return "Header header\n\
00072 float64 left_speed\n\
00073 float64 right_speed\n\
00074 float64 left_accel\n\
00075 float64 right_accel\n\
00076 \n\
00077 ================================================================================\n\
00078 MSG: std_msgs/Header\n\
00079 # Standard metadata for higher-level stamped data types.\n\
00080 # This is generally used to communicate timestamped data \n\
00081 # in a particular coordinate frame.\n\
00082 # \n\
00083 # sequence ID: consecutively increasing ID \n\
00084 uint32 seq\n\
00085 #Two-integer timestamp that is expressed as:\n\
00086 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00087 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00088 # time-handling sugar is provided by the client library\n\
00089 time stamp\n\
00090 #Frame this data is associated with\n\
00091 # 0: no frame\n\
00092 # 1: global frame\n\
00093 string frame_id\n\
00094 \n\
00095 "; }
00096 public:
00097 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00098
00099 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00100
00101 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00102 {
00103 ros::serialization::OStream stream(write_ptr, 1000000000);
00104 ros::serialization::serialize(stream, header);
00105 ros::serialization::serialize(stream, left_speed);
00106 ros::serialization::serialize(stream, right_speed);
00107 ros::serialization::serialize(stream, left_accel);
00108 ros::serialization::serialize(stream, right_accel);
00109 return stream.getData();
00110 }
00111
00112 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00113 {
00114 ros::serialization::IStream stream(read_ptr, 1000000000);
00115 ros::serialization::deserialize(stream, header);
00116 ros::serialization::deserialize(stream, left_speed);
00117 ros::serialization::deserialize(stream, right_speed);
00118 ros::serialization::deserialize(stream, left_accel);
00119 ros::serialization::deserialize(stream, right_accel);
00120 return stream.getData();
00121 }
00122
00123 ROS_DEPRECATED virtual uint32_t serializationLength() const
00124 {
00125 uint32_t size = 0;
00126 size += ros::serialization::serializationLength(header);
00127 size += ros::serialization::serializationLength(left_speed);
00128 size += ros::serialization::serializationLength(right_speed);
00129 size += ros::serialization::serializationLength(left_accel);
00130 size += ros::serialization::serializationLength(right_accel);
00131 return size;
00132 }
00133
00134 typedef boost::shared_ptr< ::clearpath_base::DifferentialSpeed_<ContainerAllocator> > Ptr;
00135 typedef boost::shared_ptr< ::clearpath_base::DifferentialSpeed_<ContainerAllocator> const> ConstPtr;
00136 };
00137 typedef ::clearpath_base::DifferentialSpeed_<std::allocator<void> > DifferentialSpeed;
00138
00139 typedef boost::shared_ptr< ::clearpath_base::DifferentialSpeed> DifferentialSpeedPtr;
00140 typedef boost::shared_ptr< ::clearpath_base::DifferentialSpeed const> DifferentialSpeedConstPtr;
00141
00142
00143 template<typename ContainerAllocator>
00144 std::ostream& operator<<(std::ostream& s, const ::clearpath_base::DifferentialSpeed_<ContainerAllocator> & v)
00145 {
00146 ros::message_operations::Printer< ::clearpath_base::DifferentialSpeed_<ContainerAllocator> >::stream(s, "", v);
00147 return s;}
00148
00149 }
00150
00151 namespace ros
00152 {
00153 namespace message_traits
00154 {
00155 template<class ContainerAllocator>
00156 struct MD5Sum< ::clearpath_base::DifferentialSpeed_<ContainerAllocator> > {
00157 static const char* value()
00158 {
00159 return "4b62e763320bacb9c7f63f6ebd46ceba";
00160 }
00161
00162 static const char* value(const ::clearpath_base::DifferentialSpeed_<ContainerAllocator> &) { return value(); }
00163 static const uint64_t static_value1 = 0x4b62e763320bacb9ULL;
00164 static const uint64_t static_value2 = 0xc7f63f6ebd46cebaULL;
00165 };
00166
00167 template<class ContainerAllocator>
00168 struct DataType< ::clearpath_base::DifferentialSpeed_<ContainerAllocator> > {
00169 static const char* value()
00170 {
00171 return "clearpath_base/DifferentialSpeed";
00172 }
00173
00174 static const char* value(const ::clearpath_base::DifferentialSpeed_<ContainerAllocator> &) { return value(); }
00175 };
00176
00177 template<class ContainerAllocator>
00178 struct Definition< ::clearpath_base::DifferentialSpeed_<ContainerAllocator> > {
00179 static const char* value()
00180 {
00181 return "Header header\n\
00182 float64 left_speed\n\
00183 float64 right_speed\n\
00184 float64 left_accel\n\
00185 float64 right_accel\n\
00186 \n\
00187 ================================================================================\n\
00188 MSG: std_msgs/Header\n\
00189 # Standard metadata for higher-level stamped data types.\n\
00190 # This is generally used to communicate timestamped data \n\
00191 # in a particular coordinate frame.\n\
00192 # \n\
00193 # sequence ID: consecutively increasing ID \n\
00194 uint32 seq\n\
00195 #Two-integer timestamp that is expressed as:\n\
00196 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00197 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00198 # time-handling sugar is provided by the client library\n\
00199 time stamp\n\
00200 #Frame this data is associated with\n\
00201 # 0: no frame\n\
00202 # 1: global frame\n\
00203 string frame_id\n\
00204 \n\
00205 ";
00206 }
00207
00208 static const char* value(const ::clearpath_base::DifferentialSpeed_<ContainerAllocator> &) { return value(); }
00209 };
00210
00211 template<class ContainerAllocator> struct HasHeader< ::clearpath_base::DifferentialSpeed_<ContainerAllocator> > : public TrueType {};
00212 template<class ContainerAllocator> struct HasHeader< const ::clearpath_base::DifferentialSpeed_<ContainerAllocator> > : public TrueType {};
00213 }
00214 }
00215
00216 namespace ros
00217 {
00218 namespace serialization
00219 {
00220
00221 template<class ContainerAllocator> struct Serializer< ::clearpath_base::DifferentialSpeed_<ContainerAllocator> >
00222 {
00223 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00224 {
00225 stream.next(m.header);
00226 stream.next(m.left_speed);
00227 stream.next(m.right_speed);
00228 stream.next(m.left_accel);
00229 stream.next(m.right_accel);
00230 }
00231
00232 ROS_DECLARE_ALLINONE_SERIALIZER;
00233 };
00234 }
00235 }
00236
00237 namespace ros
00238 {
00239 namespace message_operations
00240 {
00241
00242 template<class ContainerAllocator>
00243 struct Printer< ::clearpath_base::DifferentialSpeed_<ContainerAllocator> >
00244 {
00245 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::clearpath_base::DifferentialSpeed_<ContainerAllocator> & v)
00246 {
00247 s << indent << "header: ";
00248 s << std::endl;
00249 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00250 s << indent << "left_speed: ";
00251 Printer<double>::stream(s, indent + " ", v.left_speed);
00252 s << indent << "right_speed: ";
00253 Printer<double>::stream(s, indent + " ", v.right_speed);
00254 s << indent << "left_accel: ";
00255 Printer<double>::stream(s, indent + " ", v.left_accel);
00256 s << indent << "right_accel: ";
00257 Printer<double>::stream(s, indent + " ", v.right_accel);
00258 }
00259 };
00260
00261
00262 }
00263 }
00264
00265 #endif // CLEARPATH_BASE_MESSAGE_DIFFERENTIALSPEED_H
00266