00001
00002 #ifndef SR_ROBOT_MSGS_MESSAGE_JOINTCONTROLLERSTATE_H
00003 #define SR_ROBOT_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 sr_robot_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 , commanded_velocity(0.0)
00031 , error(0.0)
00032 , time_step(0.0)
00033 , command(0.0)
00034 , measured_effort(0.0)
00035 , friction_compensation(0.0)
00036 , position_p(0.0)
00037 , position_i(0.0)
00038 , position_d(0.0)
00039 , position_i_clamp(0.0)
00040 , velocity_p(0.0)
00041 , velocity_i(0.0)
00042 , velocity_d(0.0)
00043 , velocity_i_clamp(0.0)
00044 {
00045 }
00046
00047 JointControllerState_(const ContainerAllocator& _alloc)
00048 : header(_alloc)
00049 , set_point(0.0)
00050 , process_value(0.0)
00051 , process_value_dot(0.0)
00052 , commanded_velocity(0.0)
00053 , error(0.0)
00054 , time_step(0.0)
00055 , command(0.0)
00056 , measured_effort(0.0)
00057 , friction_compensation(0.0)
00058 , position_p(0.0)
00059 , position_i(0.0)
00060 , position_d(0.0)
00061 , position_i_clamp(0.0)
00062 , velocity_p(0.0)
00063 , velocity_i(0.0)
00064 , velocity_d(0.0)
00065 , velocity_i_clamp(0.0)
00066 {
00067 }
00068
00069 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00070 ::std_msgs::Header_<ContainerAllocator> header;
00071
00072 typedef double _set_point_type;
00073 double set_point;
00074
00075 typedef double _process_value_type;
00076 double process_value;
00077
00078 typedef double _process_value_dot_type;
00079 double process_value_dot;
00080
00081 typedef double _commanded_velocity_type;
00082 double commanded_velocity;
00083
00084 typedef double _error_type;
00085 double error;
00086
00087 typedef double _time_step_type;
00088 double time_step;
00089
00090 typedef double _command_type;
00091 double command;
00092
00093 typedef double _measured_effort_type;
00094 double measured_effort;
00095
00096 typedef double _friction_compensation_type;
00097 double friction_compensation;
00098
00099 typedef double _position_p_type;
00100 double position_p;
00101
00102 typedef double _position_i_type;
00103 double position_i;
00104
00105 typedef double _position_d_type;
00106 double position_d;
00107
00108 typedef double _position_i_clamp_type;
00109 double position_i_clamp;
00110
00111 typedef double _velocity_p_type;
00112 double velocity_p;
00113
00114 typedef double _velocity_i_type;
00115 double velocity_i;
00116
00117 typedef double _velocity_d_type;
00118 double velocity_d;
00119
00120 typedef double _velocity_i_clamp_type;
00121 double velocity_i_clamp;
00122
00123
00124 typedef boost::shared_ptr< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > Ptr;
00125 typedef boost::shared_ptr< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> const> ConstPtr;
00126 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00127 };
00128 typedef ::sr_robot_msgs::JointControllerState_<std::allocator<void> > JointControllerState;
00129
00130 typedef boost::shared_ptr< ::sr_robot_msgs::JointControllerState> JointControllerStatePtr;
00131 typedef boost::shared_ptr< ::sr_robot_msgs::JointControllerState const> JointControllerStateConstPtr;
00132
00133
00134 template<typename ContainerAllocator>
00135 std::ostream& operator<<(std::ostream& s, const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> & v)
00136 {
00137 ros::message_operations::Printer< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> >::stream(s, "", v);
00138 return s;}
00139
00140 }
00141
00142 namespace ros
00143 {
00144 namespace message_traits
00145 {
00146 template<class ContainerAllocator> struct IsMessage< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > : public TrueType {};
00147 template<class ContainerAllocator> struct IsMessage< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> const> : public TrueType {};
00148 template<class ContainerAllocator>
00149 struct MD5Sum< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > {
00150 static const char* value()
00151 {
00152 return "6d5ccb5452fd11516b5e350fcf60090e";
00153 }
00154
00155 static const char* value(const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> &) { return value(); }
00156 static const uint64_t static_value1 = 0x6d5ccb5452fd1151ULL;
00157 static const uint64_t static_value2 = 0x6b5e350fcf60090eULL;
00158 };
00159
00160 template<class ContainerAllocator>
00161 struct DataType< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > {
00162 static const char* value()
00163 {
00164 return "sr_robot_msgs/JointControllerState";
00165 }
00166
00167 static const char* value(const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> &) { return value(); }
00168 };
00169
00170 template<class ContainerAllocator>
00171 struct Definition< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > {
00172 static const char* value()
00173 {
00174 return "Header header\n\
00175 float64 set_point\n\
00176 float64 process_value\n\
00177 float64 process_value_dot\n\
00178 float64 commanded_velocity\n\
00179 float64 error\n\
00180 float64 time_step\n\
00181 float64 command\n\
00182 float64 measured_effort\n\
00183 float64 friction_compensation\n\
00184 float64 position_p\n\
00185 float64 position_i\n\
00186 float64 position_d\n\
00187 float64 position_i_clamp\n\
00188 float64 velocity_p\n\
00189 float64 velocity_i\n\
00190 float64 velocity_d\n\
00191 float64 velocity_i_clamp\n\
00192 \n\
00193 ================================================================================\n\
00194 MSG: std_msgs/Header\n\
00195 # Standard metadata for higher-level stamped data types.\n\
00196 # This is generally used to communicate timestamped data \n\
00197 # in a particular coordinate frame.\n\
00198 # \n\
00199 # sequence ID: consecutively increasing ID \n\
00200 uint32 seq\n\
00201 #Two-integer timestamp that is expressed as:\n\
00202 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00203 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00204 # time-handling sugar is provided by the client library\n\
00205 time stamp\n\
00206 #Frame this data is associated with\n\
00207 # 0: no frame\n\
00208 # 1: global frame\n\
00209 string frame_id\n\
00210 \n\
00211 ";
00212 }
00213
00214 static const char* value(const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> &) { return value(); }
00215 };
00216
00217 template<class ContainerAllocator> struct HasHeader< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > : public TrueType {};
00218 template<class ContainerAllocator> struct HasHeader< const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > : public TrueType {};
00219 }
00220 }
00221
00222 namespace ros
00223 {
00224 namespace serialization
00225 {
00226
00227 template<class ContainerAllocator> struct Serializer< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> >
00228 {
00229 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00230 {
00231 stream.next(m.header);
00232 stream.next(m.set_point);
00233 stream.next(m.process_value);
00234 stream.next(m.process_value_dot);
00235 stream.next(m.commanded_velocity);
00236 stream.next(m.error);
00237 stream.next(m.time_step);
00238 stream.next(m.command);
00239 stream.next(m.measured_effort);
00240 stream.next(m.friction_compensation);
00241 stream.next(m.position_p);
00242 stream.next(m.position_i);
00243 stream.next(m.position_d);
00244 stream.next(m.position_i_clamp);
00245 stream.next(m.velocity_p);
00246 stream.next(m.velocity_i);
00247 stream.next(m.velocity_d);
00248 stream.next(m.velocity_i_clamp);
00249 }
00250
00251 ROS_DECLARE_ALLINONE_SERIALIZER;
00252 };
00253 }
00254 }
00255
00256 namespace ros
00257 {
00258 namespace message_operations
00259 {
00260
00261 template<class ContainerAllocator>
00262 struct Printer< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> >
00263 {
00264 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> & v)
00265 {
00266 s << indent << "header: ";
00267 s << std::endl;
00268 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00269 s << indent << "set_point: ";
00270 Printer<double>::stream(s, indent + " ", v.set_point);
00271 s << indent << "process_value: ";
00272 Printer<double>::stream(s, indent + " ", v.process_value);
00273 s << indent << "process_value_dot: ";
00274 Printer<double>::stream(s, indent + " ", v.process_value_dot);
00275 s << indent << "commanded_velocity: ";
00276 Printer<double>::stream(s, indent + " ", v.commanded_velocity);
00277 s << indent << "error: ";
00278 Printer<double>::stream(s, indent + " ", v.error);
00279 s << indent << "time_step: ";
00280 Printer<double>::stream(s, indent + " ", v.time_step);
00281 s << indent << "command: ";
00282 Printer<double>::stream(s, indent + " ", v.command);
00283 s << indent << "measured_effort: ";
00284 Printer<double>::stream(s, indent + " ", v.measured_effort);
00285 s << indent << "friction_compensation: ";
00286 Printer<double>::stream(s, indent + " ", v.friction_compensation);
00287 s << indent << "position_p: ";
00288 Printer<double>::stream(s, indent + " ", v.position_p);
00289 s << indent << "position_i: ";
00290 Printer<double>::stream(s, indent + " ", v.position_i);
00291 s << indent << "position_d: ";
00292 Printer<double>::stream(s, indent + " ", v.position_d);
00293 s << indent << "position_i_clamp: ";
00294 Printer<double>::stream(s, indent + " ", v.position_i_clamp);
00295 s << indent << "velocity_p: ";
00296 Printer<double>::stream(s, indent + " ", v.velocity_p);
00297 s << indent << "velocity_i: ";
00298 Printer<double>::stream(s, indent + " ", v.velocity_i);
00299 s << indent << "velocity_d: ";
00300 Printer<double>::stream(s, indent + " ", v.velocity_d);
00301 s << indent << "velocity_i_clamp: ";
00302 Printer<double>::stream(s, indent + " ", v.velocity_i_clamp);
00303 }
00304 };
00305
00306
00307 }
00308 }
00309
00310 #endif // SR_ROBOT_MSGS_MESSAGE_JOINTCONTROLLERSTATE_H
00311