$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-shadow_robot/doc_stacks/2013-03-02_13-32-28.994675/shadow_robot/sr_robot_msgs/msg/JointControllerState.msg */ 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 private: 00125 static const char* __s_getDataType_() { return "sr_robot_msgs/JointControllerState"; } 00126 public: 00127 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00128 00129 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00130 00131 private: 00132 static const char* __s_getMD5Sum_() { return "6d5ccb5452fd11516b5e350fcf60090e"; } 00133 public: 00134 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00135 00136 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00137 00138 private: 00139 static const char* __s_getMessageDefinition_() { return "Header header\n\ 00140 float64 set_point\n\ 00141 float64 process_value\n\ 00142 float64 process_value_dot\n\ 00143 float64 commanded_velocity\n\ 00144 float64 error\n\ 00145 float64 time_step\n\ 00146 float64 command\n\ 00147 float64 measured_effort\n\ 00148 float64 friction_compensation\n\ 00149 float64 position_p\n\ 00150 float64 position_i\n\ 00151 float64 position_d\n\ 00152 float64 position_i_clamp\n\ 00153 float64 velocity_p\n\ 00154 float64 velocity_i\n\ 00155 float64 velocity_d\n\ 00156 float64 velocity_i_clamp\n\ 00157 \n\ 00158 ================================================================================\n\ 00159 MSG: std_msgs/Header\n\ 00160 # Standard metadata for higher-level stamped data types.\n\ 00161 # This is generally used to communicate timestamped data \n\ 00162 # in a particular coordinate frame.\n\ 00163 # \n\ 00164 # sequence ID: consecutively increasing ID \n\ 00165 uint32 seq\n\ 00166 #Two-integer timestamp that is expressed as:\n\ 00167 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00168 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00169 # time-handling sugar is provided by the client library\n\ 00170 time stamp\n\ 00171 #Frame this data is associated with\n\ 00172 # 0: no frame\n\ 00173 # 1: global frame\n\ 00174 string frame_id\n\ 00175 \n\ 00176 "; } 00177 public: 00178 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00179 00180 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00181 00182 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00183 { 00184 ros::serialization::OStream stream(write_ptr, 1000000000); 00185 ros::serialization::serialize(stream, header); 00186 ros::serialization::serialize(stream, set_point); 00187 ros::serialization::serialize(stream, process_value); 00188 ros::serialization::serialize(stream, process_value_dot); 00189 ros::serialization::serialize(stream, commanded_velocity); 00190 ros::serialization::serialize(stream, error); 00191 ros::serialization::serialize(stream, time_step); 00192 ros::serialization::serialize(stream, command); 00193 ros::serialization::serialize(stream, measured_effort); 00194 ros::serialization::serialize(stream, friction_compensation); 00195 ros::serialization::serialize(stream, position_p); 00196 ros::serialization::serialize(stream, position_i); 00197 ros::serialization::serialize(stream, position_d); 00198 ros::serialization::serialize(stream, position_i_clamp); 00199 ros::serialization::serialize(stream, velocity_p); 00200 ros::serialization::serialize(stream, velocity_i); 00201 ros::serialization::serialize(stream, velocity_d); 00202 ros::serialization::serialize(stream, velocity_i_clamp); 00203 return stream.getData(); 00204 } 00205 00206 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00207 { 00208 ros::serialization::IStream stream(read_ptr, 1000000000); 00209 ros::serialization::deserialize(stream, header); 00210 ros::serialization::deserialize(stream, set_point); 00211 ros::serialization::deserialize(stream, process_value); 00212 ros::serialization::deserialize(stream, process_value_dot); 00213 ros::serialization::deserialize(stream, commanded_velocity); 00214 ros::serialization::deserialize(stream, error); 00215 ros::serialization::deserialize(stream, time_step); 00216 ros::serialization::deserialize(stream, command); 00217 ros::serialization::deserialize(stream, measured_effort); 00218 ros::serialization::deserialize(stream, friction_compensation); 00219 ros::serialization::deserialize(stream, position_p); 00220 ros::serialization::deserialize(stream, position_i); 00221 ros::serialization::deserialize(stream, position_d); 00222 ros::serialization::deserialize(stream, position_i_clamp); 00223 ros::serialization::deserialize(stream, velocity_p); 00224 ros::serialization::deserialize(stream, velocity_i); 00225 ros::serialization::deserialize(stream, velocity_d); 00226 ros::serialization::deserialize(stream, velocity_i_clamp); 00227 return stream.getData(); 00228 } 00229 00230 ROS_DEPRECATED virtual uint32_t serializationLength() const 00231 { 00232 uint32_t size = 0; 00233 size += ros::serialization::serializationLength(header); 00234 size += ros::serialization::serializationLength(set_point); 00235 size += ros::serialization::serializationLength(process_value); 00236 size += ros::serialization::serializationLength(process_value_dot); 00237 size += ros::serialization::serializationLength(commanded_velocity); 00238 size += ros::serialization::serializationLength(error); 00239 size += ros::serialization::serializationLength(time_step); 00240 size += ros::serialization::serializationLength(command); 00241 size += ros::serialization::serializationLength(measured_effort); 00242 size += ros::serialization::serializationLength(friction_compensation); 00243 size += ros::serialization::serializationLength(position_p); 00244 size += ros::serialization::serializationLength(position_i); 00245 size += ros::serialization::serializationLength(position_d); 00246 size += ros::serialization::serializationLength(position_i_clamp); 00247 size += ros::serialization::serializationLength(velocity_p); 00248 size += ros::serialization::serializationLength(velocity_i); 00249 size += ros::serialization::serializationLength(velocity_d); 00250 size += ros::serialization::serializationLength(velocity_i_clamp); 00251 return size; 00252 } 00253 00254 typedef boost::shared_ptr< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > Ptr; 00255 typedef boost::shared_ptr< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> const> ConstPtr; 00256 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00257 }; // struct JointControllerState 00258 typedef ::sr_robot_msgs::JointControllerState_<std::allocator<void> > JointControllerState; 00259 00260 typedef boost::shared_ptr< ::sr_robot_msgs::JointControllerState> JointControllerStatePtr; 00261 typedef boost::shared_ptr< ::sr_robot_msgs::JointControllerState const> JointControllerStateConstPtr; 00262 00263 00264 template<typename ContainerAllocator> 00265 std::ostream& operator<<(std::ostream& s, const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> & v) 00266 { 00267 ros::message_operations::Printer< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> >::stream(s, "", v); 00268 return s;} 00269 00270 } // namespace sr_robot_msgs 00271 00272 namespace ros 00273 { 00274 namespace message_traits 00275 { 00276 template<class ContainerAllocator> struct IsMessage< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > : public TrueType {}; 00277 template<class ContainerAllocator> struct IsMessage< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> const> : public TrueType {}; 00278 template<class ContainerAllocator> 00279 struct MD5Sum< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > { 00280 static const char* value() 00281 { 00282 return "6d5ccb5452fd11516b5e350fcf60090e"; 00283 } 00284 00285 static const char* value(const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> &) { return value(); } 00286 static const uint64_t static_value1 = 0x6d5ccb5452fd1151ULL; 00287 static const uint64_t static_value2 = 0x6b5e350fcf60090eULL; 00288 }; 00289 00290 template<class ContainerAllocator> 00291 struct DataType< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > { 00292 static const char* value() 00293 { 00294 return "sr_robot_msgs/JointControllerState"; 00295 } 00296 00297 static const char* value(const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> &) { return value(); } 00298 }; 00299 00300 template<class ContainerAllocator> 00301 struct Definition< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > { 00302 static const char* value() 00303 { 00304 return "Header header\n\ 00305 float64 set_point\n\ 00306 float64 process_value\n\ 00307 float64 process_value_dot\n\ 00308 float64 commanded_velocity\n\ 00309 float64 error\n\ 00310 float64 time_step\n\ 00311 float64 command\n\ 00312 float64 measured_effort\n\ 00313 float64 friction_compensation\n\ 00314 float64 position_p\n\ 00315 float64 position_i\n\ 00316 float64 position_d\n\ 00317 float64 position_i_clamp\n\ 00318 float64 velocity_p\n\ 00319 float64 velocity_i\n\ 00320 float64 velocity_d\n\ 00321 float64 velocity_i_clamp\n\ 00322 \n\ 00323 ================================================================================\n\ 00324 MSG: std_msgs/Header\n\ 00325 # Standard metadata for higher-level stamped data types.\n\ 00326 # This is generally used to communicate timestamped data \n\ 00327 # in a particular coordinate frame.\n\ 00328 # \n\ 00329 # sequence ID: consecutively increasing ID \n\ 00330 uint32 seq\n\ 00331 #Two-integer timestamp that is expressed as:\n\ 00332 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00333 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00334 # time-handling sugar is provided by the client library\n\ 00335 time stamp\n\ 00336 #Frame this data is associated with\n\ 00337 # 0: no frame\n\ 00338 # 1: global frame\n\ 00339 string frame_id\n\ 00340 \n\ 00341 "; 00342 } 00343 00344 static const char* value(const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> &) { return value(); } 00345 }; 00346 00347 template<class ContainerAllocator> struct HasHeader< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > : public TrueType {}; 00348 template<class ContainerAllocator> struct HasHeader< const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > : public TrueType {}; 00349 } // namespace message_traits 00350 } // namespace ros 00351 00352 namespace ros 00353 { 00354 namespace serialization 00355 { 00356 00357 template<class ContainerAllocator> struct Serializer< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > 00358 { 00359 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00360 { 00361 stream.next(m.header); 00362 stream.next(m.set_point); 00363 stream.next(m.process_value); 00364 stream.next(m.process_value_dot); 00365 stream.next(m.commanded_velocity); 00366 stream.next(m.error); 00367 stream.next(m.time_step); 00368 stream.next(m.command); 00369 stream.next(m.measured_effort); 00370 stream.next(m.friction_compensation); 00371 stream.next(m.position_p); 00372 stream.next(m.position_i); 00373 stream.next(m.position_d); 00374 stream.next(m.position_i_clamp); 00375 stream.next(m.velocity_p); 00376 stream.next(m.velocity_i); 00377 stream.next(m.velocity_d); 00378 stream.next(m.velocity_i_clamp); 00379 } 00380 00381 ROS_DECLARE_ALLINONE_SERIALIZER; 00382 }; // struct JointControllerState_ 00383 } // namespace serialization 00384 } // namespace ros 00385 00386 namespace ros 00387 { 00388 namespace message_operations 00389 { 00390 00391 template<class ContainerAllocator> 00392 struct Printer< ::sr_robot_msgs::JointControllerState_<ContainerAllocator> > 00393 { 00394 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sr_robot_msgs::JointControllerState_<ContainerAllocator> & v) 00395 { 00396 s << indent << "header: "; 00397 s << std::endl; 00398 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00399 s << indent << "set_point: "; 00400 Printer<double>::stream(s, indent + " ", v.set_point); 00401 s << indent << "process_value: "; 00402 Printer<double>::stream(s, indent + " ", v.process_value); 00403 s << indent << "process_value_dot: "; 00404 Printer<double>::stream(s, indent + " ", v.process_value_dot); 00405 s << indent << "commanded_velocity: "; 00406 Printer<double>::stream(s, indent + " ", v.commanded_velocity); 00407 s << indent << "error: "; 00408 Printer<double>::stream(s, indent + " ", v.error); 00409 s << indent << "time_step: "; 00410 Printer<double>::stream(s, indent + " ", v.time_step); 00411 s << indent << "command: "; 00412 Printer<double>::stream(s, indent + " ", v.command); 00413 s << indent << "measured_effort: "; 00414 Printer<double>::stream(s, indent + " ", v.measured_effort); 00415 s << indent << "friction_compensation: "; 00416 Printer<double>::stream(s, indent + " ", v.friction_compensation); 00417 s << indent << "position_p: "; 00418 Printer<double>::stream(s, indent + " ", v.position_p); 00419 s << indent << "position_i: "; 00420 Printer<double>::stream(s, indent + " ", v.position_i); 00421 s << indent << "position_d: "; 00422 Printer<double>::stream(s, indent + " ", v.position_d); 00423 s << indent << "position_i_clamp: "; 00424 Printer<double>::stream(s, indent + " ", v.position_i_clamp); 00425 s << indent << "velocity_p: "; 00426 Printer<double>::stream(s, indent + " ", v.velocity_p); 00427 s << indent << "velocity_i: "; 00428 Printer<double>::stream(s, indent + " ", v.velocity_i); 00429 s << indent << "velocity_d: "; 00430 Printer<double>::stream(s, indent + " ", v.velocity_d); 00431 s << indent << "velocity_i_clamp: "; 00432 Printer<double>::stream(s, indent + " ", v.velocity_i_clamp); 00433 } 00434 }; 00435 00436 00437 } // namespace message_operations 00438 } // namespace ros 00439 00440 #endif // SR_ROBOT_MSGS_MESSAGE_JOINTCONTROLLERSTATE_H 00441