00001
00002 #ifndef CLEARPATH_BASE_MESSAGE_DIFFERENTIALCONTROL_H
00003 #define CLEARPATH_BASE_MESSAGE_DIFFERENTIALCONTROL_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 DifferentialControl_ : public ros::Message
00019 {
00020 typedef DifferentialControl_<ContainerAllocator> Type;
00021
00022 DifferentialControl_()
00023 : header()
00024 , l_p(0.0)
00025 , l_i(0.0)
00026 , l_d(0.0)
00027 , l_ffwd(0.0)
00028 , l_stic(0.0)
00029 , l_sat(0.0)
00030 , r_p(0.0)
00031 , r_i(0.0)
00032 , r_d(0.0)
00033 , r_ffwd(0.0)
00034 , r_stic(0.0)
00035 , r_sat(0.0)
00036 {
00037 }
00038
00039 DifferentialControl_(const ContainerAllocator& _alloc)
00040 : header(_alloc)
00041 , l_p(0.0)
00042 , l_i(0.0)
00043 , l_d(0.0)
00044 , l_ffwd(0.0)
00045 , l_stic(0.0)
00046 , l_sat(0.0)
00047 , r_p(0.0)
00048 , r_i(0.0)
00049 , r_d(0.0)
00050 , r_ffwd(0.0)
00051 , r_stic(0.0)
00052 , r_sat(0.0)
00053 {
00054 }
00055
00056 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00057 ::std_msgs::Header_<ContainerAllocator> header;
00058
00059 typedef double _l_p_type;
00060 double l_p;
00061
00062 typedef double _l_i_type;
00063 double l_i;
00064
00065 typedef double _l_d_type;
00066 double l_d;
00067
00068 typedef double _l_ffwd_type;
00069 double l_ffwd;
00070
00071 typedef double _l_stic_type;
00072 double l_stic;
00073
00074 typedef double _l_sat_type;
00075 double l_sat;
00076
00077 typedef double _r_p_type;
00078 double r_p;
00079
00080 typedef double _r_i_type;
00081 double r_i;
00082
00083 typedef double _r_d_type;
00084 double r_d;
00085
00086 typedef double _r_ffwd_type;
00087 double r_ffwd;
00088
00089 typedef double _r_stic_type;
00090 double r_stic;
00091
00092 typedef double _r_sat_type;
00093 double r_sat;
00094
00095
00096 private:
00097 static const char* __s_getDataType_() { return "clearpath_base/DifferentialControl"; }
00098 public:
00099 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00100
00101 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00102
00103 private:
00104 static const char* __s_getMD5Sum_() { return "ae0672163e13fc0bb6491960c53a3259"; }
00105 public:
00106 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00107
00108 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00109
00110 private:
00111 static const char* __s_getMessageDefinition_() { return "Header header\n\
00112 float64 l_p\n\
00113 float64 l_i\n\
00114 float64 l_d\n\
00115 float64 l_ffwd\n\
00116 float64 l_stic\n\
00117 float64 l_sat\n\
00118 float64 r_p\n\
00119 float64 r_i\n\
00120 float64 r_d\n\
00121 float64 r_ffwd\n\
00122 float64 r_stic\n\
00123 float64 r_sat\n\
00124 \n\
00125 ================================================================================\n\
00126 MSG: std_msgs/Header\n\
00127 # Standard metadata for higher-level stamped data types.\n\
00128 # This is generally used to communicate timestamped data \n\
00129 # in a particular coordinate frame.\n\
00130 # \n\
00131 # sequence ID: consecutively increasing ID \n\
00132 uint32 seq\n\
00133 #Two-integer timestamp that is expressed as:\n\
00134 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00135 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00136 # time-handling sugar is provided by the client library\n\
00137 time stamp\n\
00138 #Frame this data is associated with\n\
00139 # 0: no frame\n\
00140 # 1: global frame\n\
00141 string frame_id\n\
00142 \n\
00143 "; }
00144 public:
00145 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00146
00147 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00148
00149 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00150 {
00151 ros::serialization::OStream stream(write_ptr, 1000000000);
00152 ros::serialization::serialize(stream, header);
00153 ros::serialization::serialize(stream, l_p);
00154 ros::serialization::serialize(stream, l_i);
00155 ros::serialization::serialize(stream, l_d);
00156 ros::serialization::serialize(stream, l_ffwd);
00157 ros::serialization::serialize(stream, l_stic);
00158 ros::serialization::serialize(stream, l_sat);
00159 ros::serialization::serialize(stream, r_p);
00160 ros::serialization::serialize(stream, r_i);
00161 ros::serialization::serialize(stream, r_d);
00162 ros::serialization::serialize(stream, r_ffwd);
00163 ros::serialization::serialize(stream, r_stic);
00164 ros::serialization::serialize(stream, r_sat);
00165 return stream.getData();
00166 }
00167
00168 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00169 {
00170 ros::serialization::IStream stream(read_ptr, 1000000000);
00171 ros::serialization::deserialize(stream, header);
00172 ros::serialization::deserialize(stream, l_p);
00173 ros::serialization::deserialize(stream, l_i);
00174 ros::serialization::deserialize(stream, l_d);
00175 ros::serialization::deserialize(stream, l_ffwd);
00176 ros::serialization::deserialize(stream, l_stic);
00177 ros::serialization::deserialize(stream, l_sat);
00178 ros::serialization::deserialize(stream, r_p);
00179 ros::serialization::deserialize(stream, r_i);
00180 ros::serialization::deserialize(stream, r_d);
00181 ros::serialization::deserialize(stream, r_ffwd);
00182 ros::serialization::deserialize(stream, r_stic);
00183 ros::serialization::deserialize(stream, r_sat);
00184 return stream.getData();
00185 }
00186
00187 ROS_DEPRECATED virtual uint32_t serializationLength() const
00188 {
00189 uint32_t size = 0;
00190 size += ros::serialization::serializationLength(header);
00191 size += ros::serialization::serializationLength(l_p);
00192 size += ros::serialization::serializationLength(l_i);
00193 size += ros::serialization::serializationLength(l_d);
00194 size += ros::serialization::serializationLength(l_ffwd);
00195 size += ros::serialization::serializationLength(l_stic);
00196 size += ros::serialization::serializationLength(l_sat);
00197 size += ros::serialization::serializationLength(r_p);
00198 size += ros::serialization::serializationLength(r_i);
00199 size += ros::serialization::serializationLength(r_d);
00200 size += ros::serialization::serializationLength(r_ffwd);
00201 size += ros::serialization::serializationLength(r_stic);
00202 size += ros::serialization::serializationLength(r_sat);
00203 return size;
00204 }
00205
00206 typedef boost::shared_ptr< ::clearpath_base::DifferentialControl_<ContainerAllocator> > Ptr;
00207 typedef boost::shared_ptr< ::clearpath_base::DifferentialControl_<ContainerAllocator> const> ConstPtr;
00208 };
00209 typedef ::clearpath_base::DifferentialControl_<std::allocator<void> > DifferentialControl;
00210
00211 typedef boost::shared_ptr< ::clearpath_base::DifferentialControl> DifferentialControlPtr;
00212 typedef boost::shared_ptr< ::clearpath_base::DifferentialControl const> DifferentialControlConstPtr;
00213
00214
00215 template<typename ContainerAllocator>
00216 std::ostream& operator<<(std::ostream& s, const ::clearpath_base::DifferentialControl_<ContainerAllocator> & v)
00217 {
00218 ros::message_operations::Printer< ::clearpath_base::DifferentialControl_<ContainerAllocator> >::stream(s, "", v);
00219 return s;}
00220
00221 }
00222
00223 namespace ros
00224 {
00225 namespace message_traits
00226 {
00227 template<class ContainerAllocator>
00228 struct MD5Sum< ::clearpath_base::DifferentialControl_<ContainerAllocator> > {
00229 static const char* value()
00230 {
00231 return "ae0672163e13fc0bb6491960c53a3259";
00232 }
00233
00234 static const char* value(const ::clearpath_base::DifferentialControl_<ContainerAllocator> &) { return value(); }
00235 static const uint64_t static_value1 = 0xae0672163e13fc0bULL;
00236 static const uint64_t static_value2 = 0xb6491960c53a3259ULL;
00237 };
00238
00239 template<class ContainerAllocator>
00240 struct DataType< ::clearpath_base::DifferentialControl_<ContainerAllocator> > {
00241 static const char* value()
00242 {
00243 return "clearpath_base/DifferentialControl";
00244 }
00245
00246 static const char* value(const ::clearpath_base::DifferentialControl_<ContainerAllocator> &) { return value(); }
00247 };
00248
00249 template<class ContainerAllocator>
00250 struct Definition< ::clearpath_base::DifferentialControl_<ContainerAllocator> > {
00251 static const char* value()
00252 {
00253 return "Header header\n\
00254 float64 l_p\n\
00255 float64 l_i\n\
00256 float64 l_d\n\
00257 float64 l_ffwd\n\
00258 float64 l_stic\n\
00259 float64 l_sat\n\
00260 float64 r_p\n\
00261 float64 r_i\n\
00262 float64 r_d\n\
00263 float64 r_ffwd\n\
00264 float64 r_stic\n\
00265 float64 r_sat\n\
00266 \n\
00267 ================================================================================\n\
00268 MSG: std_msgs/Header\n\
00269 # Standard metadata for higher-level stamped data types.\n\
00270 # This is generally used to communicate timestamped data \n\
00271 # in a particular coordinate frame.\n\
00272 # \n\
00273 # sequence ID: consecutively increasing ID \n\
00274 uint32 seq\n\
00275 #Two-integer timestamp that is expressed as:\n\
00276 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00277 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00278 # time-handling sugar is provided by the client library\n\
00279 time stamp\n\
00280 #Frame this data is associated with\n\
00281 # 0: no frame\n\
00282 # 1: global frame\n\
00283 string frame_id\n\
00284 \n\
00285 ";
00286 }
00287
00288 static const char* value(const ::clearpath_base::DifferentialControl_<ContainerAllocator> &) { return value(); }
00289 };
00290
00291 template<class ContainerAllocator> struct HasHeader< ::clearpath_base::DifferentialControl_<ContainerAllocator> > : public TrueType {};
00292 template<class ContainerAllocator> struct HasHeader< const ::clearpath_base::DifferentialControl_<ContainerAllocator> > : public TrueType {};
00293 }
00294 }
00295
00296 namespace ros
00297 {
00298 namespace serialization
00299 {
00300
00301 template<class ContainerAllocator> struct Serializer< ::clearpath_base::DifferentialControl_<ContainerAllocator> >
00302 {
00303 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00304 {
00305 stream.next(m.header);
00306 stream.next(m.l_p);
00307 stream.next(m.l_i);
00308 stream.next(m.l_d);
00309 stream.next(m.l_ffwd);
00310 stream.next(m.l_stic);
00311 stream.next(m.l_sat);
00312 stream.next(m.r_p);
00313 stream.next(m.r_i);
00314 stream.next(m.r_d);
00315 stream.next(m.r_ffwd);
00316 stream.next(m.r_stic);
00317 stream.next(m.r_sat);
00318 }
00319
00320 ROS_DECLARE_ALLINONE_SERIALIZER;
00321 };
00322 }
00323 }
00324
00325 namespace ros
00326 {
00327 namespace message_operations
00328 {
00329
00330 template<class ContainerAllocator>
00331 struct Printer< ::clearpath_base::DifferentialControl_<ContainerAllocator> >
00332 {
00333 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::clearpath_base::DifferentialControl_<ContainerAllocator> & v)
00334 {
00335 s << indent << "header: ";
00336 s << std::endl;
00337 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00338 s << indent << "l_p: ";
00339 Printer<double>::stream(s, indent + " ", v.l_p);
00340 s << indent << "l_i: ";
00341 Printer<double>::stream(s, indent + " ", v.l_i);
00342 s << indent << "l_d: ";
00343 Printer<double>::stream(s, indent + " ", v.l_d);
00344 s << indent << "l_ffwd: ";
00345 Printer<double>::stream(s, indent + " ", v.l_ffwd);
00346 s << indent << "l_stic: ";
00347 Printer<double>::stream(s, indent + " ", v.l_stic);
00348 s << indent << "l_sat: ";
00349 Printer<double>::stream(s, indent + " ", v.l_sat);
00350 s << indent << "r_p: ";
00351 Printer<double>::stream(s, indent + " ", v.r_p);
00352 s << indent << "r_i: ";
00353 Printer<double>::stream(s, indent + " ", v.r_i);
00354 s << indent << "r_d: ";
00355 Printer<double>::stream(s, indent + " ", v.r_d);
00356 s << indent << "r_ffwd: ";
00357 Printer<double>::stream(s, indent + " ", v.r_ffwd);
00358 s << indent << "r_stic: ";
00359 Printer<double>::stream(s, indent + " ", v.r_stic);
00360 s << indent << "r_sat: ";
00361 Printer<double>::stream(s, indent + " ", v.r_sat);
00362 }
00363 };
00364
00365
00366 }
00367 }
00368
00369 #endif // CLEARPATH_BASE_MESSAGE_DIFFERENTIALCONTROL_H
00370