$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_controllers/doc_stacks/2013-03-01_16-45-23.561928/pr2_controllers/pr2_mechanism_controllers/msg/BaseControllerState2.msg */ 00002 #ifndef PR2_MECHANISM_CONTROLLERS_MESSAGE_BASECONTROLLERSTATE2_H 00003 #define PR2_MECHANISM_CONTROLLERS_MESSAGE_BASECONTROLLERSTATE2_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 "geometry_msgs/Twist.h" 00018 00019 namespace pr2_mechanism_controllers 00020 { 00021 template <class ContainerAllocator> 00022 struct BaseControllerState2_ { 00023 typedef BaseControllerState2_<ContainerAllocator> Type; 00024 00025 BaseControllerState2_() 00026 : command() 00027 , joint_command() 00028 , joint_error() 00029 , joint_velocity_commanded() 00030 , joint_velocity_measured() 00031 , joint_effort_measured() 00032 , joint_effort_commanded() 00033 , joint_effort_error() 00034 , joint_names() 00035 { 00036 } 00037 00038 BaseControllerState2_(const ContainerAllocator& _alloc) 00039 : command(_alloc) 00040 , joint_command(_alloc) 00041 , joint_error(_alloc) 00042 , joint_velocity_commanded(_alloc) 00043 , joint_velocity_measured(_alloc) 00044 , joint_effort_measured(_alloc) 00045 , joint_effort_commanded(_alloc) 00046 , joint_effort_error(_alloc) 00047 , joint_names(_alloc) 00048 { 00049 } 00050 00051 typedef ::geometry_msgs::Twist_<ContainerAllocator> _command_type; 00052 ::geometry_msgs::Twist_<ContainerAllocator> command; 00053 00054 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_command_type; 00055 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_command; 00056 00057 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_error_type; 00058 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_error; 00059 00060 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_velocity_commanded_type; 00061 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_velocity_commanded; 00062 00063 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_velocity_measured_type; 00064 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_velocity_measured; 00065 00066 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_effort_measured_type; 00067 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_effort_measured; 00068 00069 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_effort_commanded_type; 00070 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_effort_commanded; 00071 00072 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_effort_error_type; 00073 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_effort_error; 00074 00075 typedef std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > _joint_names_type; 00076 std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > joint_names; 00077 00078 00079 ROS_DEPRECATED uint32_t get_joint_command_size() const { return (uint32_t)joint_command.size(); } 00080 ROS_DEPRECATED void set_joint_command_size(uint32_t size) { joint_command.resize((size_t)size); } 00081 ROS_DEPRECATED void get_joint_command_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->joint_command; } 00082 ROS_DEPRECATED void set_joint_command_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->joint_command = vec; } 00083 ROS_DEPRECATED uint32_t get_joint_error_size() const { return (uint32_t)joint_error.size(); } 00084 ROS_DEPRECATED void set_joint_error_size(uint32_t size) { joint_error.resize((size_t)size); } 00085 ROS_DEPRECATED void get_joint_error_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->joint_error; } 00086 ROS_DEPRECATED void set_joint_error_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->joint_error = vec; } 00087 ROS_DEPRECATED uint32_t get_joint_velocity_commanded_size() const { return (uint32_t)joint_velocity_commanded.size(); } 00088 ROS_DEPRECATED void set_joint_velocity_commanded_size(uint32_t size) { joint_velocity_commanded.resize((size_t)size); } 00089 ROS_DEPRECATED void get_joint_velocity_commanded_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->joint_velocity_commanded; } 00090 ROS_DEPRECATED void set_joint_velocity_commanded_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->joint_velocity_commanded = vec; } 00091 ROS_DEPRECATED uint32_t get_joint_velocity_measured_size() const { return (uint32_t)joint_velocity_measured.size(); } 00092 ROS_DEPRECATED void set_joint_velocity_measured_size(uint32_t size) { joint_velocity_measured.resize((size_t)size); } 00093 ROS_DEPRECATED void get_joint_velocity_measured_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->joint_velocity_measured; } 00094 ROS_DEPRECATED void set_joint_velocity_measured_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->joint_velocity_measured = vec; } 00095 ROS_DEPRECATED uint32_t get_joint_effort_measured_size() const { return (uint32_t)joint_effort_measured.size(); } 00096 ROS_DEPRECATED void set_joint_effort_measured_size(uint32_t size) { joint_effort_measured.resize((size_t)size); } 00097 ROS_DEPRECATED void get_joint_effort_measured_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->joint_effort_measured; } 00098 ROS_DEPRECATED void set_joint_effort_measured_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->joint_effort_measured = vec; } 00099 ROS_DEPRECATED uint32_t get_joint_effort_commanded_size() const { return (uint32_t)joint_effort_commanded.size(); } 00100 ROS_DEPRECATED void set_joint_effort_commanded_size(uint32_t size) { joint_effort_commanded.resize((size_t)size); } 00101 ROS_DEPRECATED void get_joint_effort_commanded_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->joint_effort_commanded; } 00102 ROS_DEPRECATED void set_joint_effort_commanded_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->joint_effort_commanded = vec; } 00103 ROS_DEPRECATED uint32_t get_joint_effort_error_size() const { return (uint32_t)joint_effort_error.size(); } 00104 ROS_DEPRECATED void set_joint_effort_error_size(uint32_t size) { joint_effort_error.resize((size_t)size); } 00105 ROS_DEPRECATED void get_joint_effort_error_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->joint_effort_error; } 00106 ROS_DEPRECATED void set_joint_effort_error_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->joint_effort_error = vec; } 00107 ROS_DEPRECATED uint32_t get_joint_names_size() const { return (uint32_t)joint_names.size(); } 00108 ROS_DEPRECATED void set_joint_names_size(uint32_t size) { joint_names.resize((size_t)size); } 00109 ROS_DEPRECATED void get_joint_names_vec(std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) const { vec = this->joint_names; } 00110 ROS_DEPRECATED void set_joint_names_vec(const std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) { this->joint_names = vec; } 00111 private: 00112 static const char* __s_getDataType_() { return "pr2_mechanism_controllers/BaseControllerState2"; } 00113 public: 00114 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00115 00116 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00117 00118 private: 00119 static const char* __s_getMD5Sum_() { return "d4b64baf09d8cb133f3f2bc279de1137"; } 00120 public: 00121 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00122 00123 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00124 00125 private: 00126 static const char* __s_getMessageDefinition_() { return "geometry_msgs/Twist command\n\ 00127 float64[] joint_command\n\ 00128 float64[] joint_error\n\ 00129 float64[] joint_velocity_commanded\n\ 00130 float64[] joint_velocity_measured\n\ 00131 float64[] joint_effort_measured\n\ 00132 float64[] joint_effort_commanded\n\ 00133 float64[] joint_effort_error\n\ 00134 string[] joint_names\n\ 00135 \n\ 00136 \n\ 00137 ================================================================================\n\ 00138 MSG: geometry_msgs/Twist\n\ 00139 # This expresses velocity in free space broken into it's linear and angular parts. \n\ 00140 Vector3 linear\n\ 00141 Vector3 angular\n\ 00142 \n\ 00143 ================================================================================\n\ 00144 MSG: geometry_msgs/Vector3\n\ 00145 # This represents a vector in free space. \n\ 00146 \n\ 00147 float64 x\n\ 00148 float64 y\n\ 00149 float64 z\n\ 00150 "; } 00151 public: 00152 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00153 00154 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00155 00156 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00157 { 00158 ros::serialization::OStream stream(write_ptr, 1000000000); 00159 ros::serialization::serialize(stream, command); 00160 ros::serialization::serialize(stream, joint_command); 00161 ros::serialization::serialize(stream, joint_error); 00162 ros::serialization::serialize(stream, joint_velocity_commanded); 00163 ros::serialization::serialize(stream, joint_velocity_measured); 00164 ros::serialization::serialize(stream, joint_effort_measured); 00165 ros::serialization::serialize(stream, joint_effort_commanded); 00166 ros::serialization::serialize(stream, joint_effort_error); 00167 ros::serialization::serialize(stream, joint_names); 00168 return stream.getData(); 00169 } 00170 00171 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00172 { 00173 ros::serialization::IStream stream(read_ptr, 1000000000); 00174 ros::serialization::deserialize(stream, command); 00175 ros::serialization::deserialize(stream, joint_command); 00176 ros::serialization::deserialize(stream, joint_error); 00177 ros::serialization::deserialize(stream, joint_velocity_commanded); 00178 ros::serialization::deserialize(stream, joint_velocity_measured); 00179 ros::serialization::deserialize(stream, joint_effort_measured); 00180 ros::serialization::deserialize(stream, joint_effort_commanded); 00181 ros::serialization::deserialize(stream, joint_effort_error); 00182 ros::serialization::deserialize(stream, joint_names); 00183 return stream.getData(); 00184 } 00185 00186 ROS_DEPRECATED virtual uint32_t serializationLength() const 00187 { 00188 uint32_t size = 0; 00189 size += ros::serialization::serializationLength(command); 00190 size += ros::serialization::serializationLength(joint_command); 00191 size += ros::serialization::serializationLength(joint_error); 00192 size += ros::serialization::serializationLength(joint_velocity_commanded); 00193 size += ros::serialization::serializationLength(joint_velocity_measured); 00194 size += ros::serialization::serializationLength(joint_effort_measured); 00195 size += ros::serialization::serializationLength(joint_effort_commanded); 00196 size += ros::serialization::serializationLength(joint_effort_error); 00197 size += ros::serialization::serializationLength(joint_names); 00198 return size; 00199 } 00200 00201 typedef boost::shared_ptr< ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> > Ptr; 00202 typedef boost::shared_ptr< ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> const> ConstPtr; 00203 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00204 }; // struct BaseControllerState2 00205 typedef ::pr2_mechanism_controllers::BaseControllerState2_<std::allocator<void> > BaseControllerState2; 00206 00207 typedef boost::shared_ptr< ::pr2_mechanism_controllers::BaseControllerState2> BaseControllerState2Ptr; 00208 typedef boost::shared_ptr< ::pr2_mechanism_controllers::BaseControllerState2 const> BaseControllerState2ConstPtr; 00209 00210 00211 template<typename ContainerAllocator> 00212 std::ostream& operator<<(std::ostream& s, const ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> & v) 00213 { 00214 ros::message_operations::Printer< ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> >::stream(s, "", v); 00215 return s;} 00216 00217 } // namespace pr2_mechanism_controllers 00218 00219 namespace ros 00220 { 00221 namespace message_traits 00222 { 00223 template<class ContainerAllocator> struct IsMessage< ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> > : public TrueType {}; 00224 template<class ContainerAllocator> struct IsMessage< ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> const> : public TrueType {}; 00225 template<class ContainerAllocator> 00226 struct MD5Sum< ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> > { 00227 static const char* value() 00228 { 00229 return "d4b64baf09d8cb133f3f2bc279de1137"; 00230 } 00231 00232 static const char* value(const ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> &) { return value(); } 00233 static const uint64_t static_value1 = 0xd4b64baf09d8cb13ULL; 00234 static const uint64_t static_value2 = 0x3f3f2bc279de1137ULL; 00235 }; 00236 00237 template<class ContainerAllocator> 00238 struct DataType< ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> > { 00239 static const char* value() 00240 { 00241 return "pr2_mechanism_controllers/BaseControllerState2"; 00242 } 00243 00244 static const char* value(const ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> &) { return value(); } 00245 }; 00246 00247 template<class ContainerAllocator> 00248 struct Definition< ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> > { 00249 static const char* value() 00250 { 00251 return "geometry_msgs/Twist command\n\ 00252 float64[] joint_command\n\ 00253 float64[] joint_error\n\ 00254 float64[] joint_velocity_commanded\n\ 00255 float64[] joint_velocity_measured\n\ 00256 float64[] joint_effort_measured\n\ 00257 float64[] joint_effort_commanded\n\ 00258 float64[] joint_effort_error\n\ 00259 string[] joint_names\n\ 00260 \n\ 00261 \n\ 00262 ================================================================================\n\ 00263 MSG: geometry_msgs/Twist\n\ 00264 # This expresses velocity in free space broken into it's linear and angular parts. \n\ 00265 Vector3 linear\n\ 00266 Vector3 angular\n\ 00267 \n\ 00268 ================================================================================\n\ 00269 MSG: geometry_msgs/Vector3\n\ 00270 # This represents a vector in free space. \n\ 00271 \n\ 00272 float64 x\n\ 00273 float64 y\n\ 00274 float64 z\n\ 00275 "; 00276 } 00277 00278 static const char* value(const ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> &) { return value(); } 00279 }; 00280 00281 } // namespace message_traits 00282 } // namespace ros 00283 00284 namespace ros 00285 { 00286 namespace serialization 00287 { 00288 00289 template<class ContainerAllocator> struct Serializer< ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> > 00290 { 00291 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00292 { 00293 stream.next(m.command); 00294 stream.next(m.joint_command); 00295 stream.next(m.joint_error); 00296 stream.next(m.joint_velocity_commanded); 00297 stream.next(m.joint_velocity_measured); 00298 stream.next(m.joint_effort_measured); 00299 stream.next(m.joint_effort_commanded); 00300 stream.next(m.joint_effort_error); 00301 stream.next(m.joint_names); 00302 } 00303 00304 ROS_DECLARE_ALLINONE_SERIALIZER; 00305 }; // struct BaseControllerState2_ 00306 } // namespace serialization 00307 } // namespace ros 00308 00309 namespace ros 00310 { 00311 namespace message_operations 00312 { 00313 00314 template<class ContainerAllocator> 00315 struct Printer< ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> > 00316 { 00317 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_mechanism_controllers::BaseControllerState2_<ContainerAllocator> & v) 00318 { 00319 s << indent << "command: "; 00320 s << std::endl; 00321 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.command); 00322 s << indent << "joint_command[]" << std::endl; 00323 for (size_t i = 0; i < v.joint_command.size(); ++i) 00324 { 00325 s << indent << " joint_command[" << i << "]: "; 00326 Printer<double>::stream(s, indent + " ", v.joint_command[i]); 00327 } 00328 s << indent << "joint_error[]" << std::endl; 00329 for (size_t i = 0; i < v.joint_error.size(); ++i) 00330 { 00331 s << indent << " joint_error[" << i << "]: "; 00332 Printer<double>::stream(s, indent + " ", v.joint_error[i]); 00333 } 00334 s << indent << "joint_velocity_commanded[]" << std::endl; 00335 for (size_t i = 0; i < v.joint_velocity_commanded.size(); ++i) 00336 { 00337 s << indent << " joint_velocity_commanded[" << i << "]: "; 00338 Printer<double>::stream(s, indent + " ", v.joint_velocity_commanded[i]); 00339 } 00340 s << indent << "joint_velocity_measured[]" << std::endl; 00341 for (size_t i = 0; i < v.joint_velocity_measured.size(); ++i) 00342 { 00343 s << indent << " joint_velocity_measured[" << i << "]: "; 00344 Printer<double>::stream(s, indent + " ", v.joint_velocity_measured[i]); 00345 } 00346 s << indent << "joint_effort_measured[]" << std::endl; 00347 for (size_t i = 0; i < v.joint_effort_measured.size(); ++i) 00348 { 00349 s << indent << " joint_effort_measured[" << i << "]: "; 00350 Printer<double>::stream(s, indent + " ", v.joint_effort_measured[i]); 00351 } 00352 s << indent << "joint_effort_commanded[]" << std::endl; 00353 for (size_t i = 0; i < v.joint_effort_commanded.size(); ++i) 00354 { 00355 s << indent << " joint_effort_commanded[" << i << "]: "; 00356 Printer<double>::stream(s, indent + " ", v.joint_effort_commanded[i]); 00357 } 00358 s << indent << "joint_effort_error[]" << std::endl; 00359 for (size_t i = 0; i < v.joint_effort_error.size(); ++i) 00360 { 00361 s << indent << " joint_effort_error[" << i << "]: "; 00362 Printer<double>::stream(s, indent + " ", v.joint_effort_error[i]); 00363 } 00364 s << indent << "joint_names[]" << std::endl; 00365 for (size_t i = 0; i < v.joint_names.size(); ++i) 00366 { 00367 s << indent << " joint_names[" << i << "]: "; 00368 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.joint_names[i]); 00369 } 00370 } 00371 }; 00372 00373 00374 } // namespace message_operations 00375 } // namespace ros 00376 00377 #endif // PR2_MECHANISM_CONTROLLERS_MESSAGE_BASECONTROLLERSTATE2_H 00378