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