$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-arm_navigation/doc_stacks/2013-03-01_14-05-03.553953/arm_navigation/kinematics_msgs/msg/PositionIKRequest.msg */ 00002 #ifndef KINEMATICS_MSGS_MESSAGE_POSITIONIKREQUEST_H 00003 #define KINEMATICS_MSGS_MESSAGE_POSITIONIKREQUEST_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/PoseStamped.h" 00018 #include "arm_navigation_msgs/RobotState.h" 00019 #include "arm_navigation_msgs/RobotState.h" 00020 00021 namespace kinematics_msgs 00022 { 00023 template <class ContainerAllocator> 00024 struct PositionIKRequest_ { 00025 typedef PositionIKRequest_<ContainerAllocator> Type; 00026 00027 PositionIKRequest_() 00028 : ik_link_name() 00029 , pose_stamped() 00030 , ik_seed_state() 00031 , robot_state() 00032 { 00033 } 00034 00035 PositionIKRequest_(const ContainerAllocator& _alloc) 00036 : ik_link_name(_alloc) 00037 , pose_stamped(_alloc) 00038 , ik_seed_state(_alloc) 00039 , robot_state(_alloc) 00040 { 00041 } 00042 00043 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _ik_link_name_type; 00044 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > ik_link_name; 00045 00046 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pose_stamped_type; 00047 ::geometry_msgs::PoseStamped_<ContainerAllocator> pose_stamped; 00048 00049 typedef ::arm_navigation_msgs::RobotState_<ContainerAllocator> _ik_seed_state_type; 00050 ::arm_navigation_msgs::RobotState_<ContainerAllocator> ik_seed_state; 00051 00052 typedef ::arm_navigation_msgs::RobotState_<ContainerAllocator> _robot_state_type; 00053 ::arm_navigation_msgs::RobotState_<ContainerAllocator> robot_state; 00054 00055 00056 private: 00057 static const char* __s_getDataType_() { return "kinematics_msgs/PositionIKRequest"; } 00058 public: 00059 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00060 00061 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00062 00063 private: 00064 static const char* __s_getMD5Sum_() { return "737bb756c6253bdd460b1383d0b12dac"; } 00065 public: 00066 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00067 00068 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00069 00070 private: 00071 static const char* __s_getMessageDefinition_() { return "# A Position IK request message\n\ 00072 # The name of the link for which we are computing IK\n\ 00073 string ik_link_name\n\ 00074 \n\ 00075 # The (stamped) pose of the link\n\ 00076 geometry_msgs/PoseStamped pose_stamped\n\ 00077 \n\ 00078 # A RobotState consisting of hint/seed positions for the IK computation. \n\ 00079 # These may be used to seed the IK search. \n\ 00080 # The seed state MUST contain state for all joints to be used by the IK solver\n\ 00081 # to compute IK. The list of joints that the IK solver deals with can be found using\n\ 00082 # the kinematics_msgs/GetKinematicSolverInfo\n\ 00083 arm_navigation_msgs/RobotState ik_seed_state\n\ 00084 \n\ 00085 # Additional state information can be provided here to specify the starting positions \n\ 00086 # of other joints/links on the robot.\n\ 00087 arm_navigation_msgs/RobotState robot_state\n\ 00088 \n\ 00089 ================================================================================\n\ 00090 MSG: geometry_msgs/PoseStamped\n\ 00091 # A Pose with reference coordinate frame and timestamp\n\ 00092 Header header\n\ 00093 Pose pose\n\ 00094 \n\ 00095 ================================================================================\n\ 00096 MSG: std_msgs/Header\n\ 00097 # Standard metadata for higher-level stamped data types.\n\ 00098 # This is generally used to communicate timestamped data \n\ 00099 # in a particular coordinate frame.\n\ 00100 # \n\ 00101 # sequence ID: consecutively increasing ID \n\ 00102 uint32 seq\n\ 00103 #Two-integer timestamp that is expressed as:\n\ 00104 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00105 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00106 # time-handling sugar is provided by the client library\n\ 00107 time stamp\n\ 00108 #Frame this data is associated with\n\ 00109 # 0: no frame\n\ 00110 # 1: global frame\n\ 00111 string frame_id\n\ 00112 \n\ 00113 ================================================================================\n\ 00114 MSG: geometry_msgs/Pose\n\ 00115 # A representation of pose in free space, composed of postion and orientation. \n\ 00116 Point position\n\ 00117 Quaternion orientation\n\ 00118 \n\ 00119 ================================================================================\n\ 00120 MSG: geometry_msgs/Point\n\ 00121 # This contains the position of a point in free space\n\ 00122 float64 x\n\ 00123 float64 y\n\ 00124 float64 z\n\ 00125 \n\ 00126 ================================================================================\n\ 00127 MSG: geometry_msgs/Quaternion\n\ 00128 # This represents an orientation in free space in quaternion form.\n\ 00129 \n\ 00130 float64 x\n\ 00131 float64 y\n\ 00132 float64 z\n\ 00133 float64 w\n\ 00134 \n\ 00135 ================================================================================\n\ 00136 MSG: arm_navigation_msgs/RobotState\n\ 00137 # This message contains information about the robot state, i.e. the positions of its joints and links\n\ 00138 sensor_msgs/JointState joint_state\n\ 00139 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state\n\ 00140 \n\ 00141 ================================================================================\n\ 00142 MSG: sensor_msgs/JointState\n\ 00143 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\ 00144 #\n\ 00145 # The state of each joint (revolute or prismatic) is defined by:\n\ 00146 # * the position of the joint (rad or m),\n\ 00147 # * the velocity of the joint (rad/s or m/s) and \n\ 00148 # * the effort that is applied in the joint (Nm or N).\n\ 00149 #\n\ 00150 # Each joint is uniquely identified by its name\n\ 00151 # The header specifies the time at which the joint states were recorded. All the joint states\n\ 00152 # in one message have to be recorded at the same time.\n\ 00153 #\n\ 00154 # This message consists of a multiple arrays, one for each part of the joint state. \n\ 00155 # The goal is to make each of the fields optional. When e.g. your joints have no\n\ 00156 # effort associated with them, you can leave the effort array empty. \n\ 00157 #\n\ 00158 # All arrays in this message should have the same size, or be empty.\n\ 00159 # This is the only way to uniquely associate the joint name with the correct\n\ 00160 # states.\n\ 00161 \n\ 00162 \n\ 00163 Header header\n\ 00164 \n\ 00165 string[] name\n\ 00166 float64[] position\n\ 00167 float64[] velocity\n\ 00168 float64[] effort\n\ 00169 \n\ 00170 ================================================================================\n\ 00171 MSG: arm_navigation_msgs/MultiDOFJointState\n\ 00172 #A representation of a multi-dof joint state\n\ 00173 time stamp\n\ 00174 string[] joint_names\n\ 00175 string[] frame_ids\n\ 00176 string[] child_frame_ids\n\ 00177 geometry_msgs/Pose[] poses\n\ 00178 \n\ 00179 "; } 00180 public: 00181 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00182 00183 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00184 00185 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00186 { 00187 ros::serialization::OStream stream(write_ptr, 1000000000); 00188 ros::serialization::serialize(stream, ik_link_name); 00189 ros::serialization::serialize(stream, pose_stamped); 00190 ros::serialization::serialize(stream, ik_seed_state); 00191 ros::serialization::serialize(stream, robot_state); 00192 return stream.getData(); 00193 } 00194 00195 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00196 { 00197 ros::serialization::IStream stream(read_ptr, 1000000000); 00198 ros::serialization::deserialize(stream, ik_link_name); 00199 ros::serialization::deserialize(stream, pose_stamped); 00200 ros::serialization::deserialize(stream, ik_seed_state); 00201 ros::serialization::deserialize(stream, robot_state); 00202 return stream.getData(); 00203 } 00204 00205 ROS_DEPRECATED virtual uint32_t serializationLength() const 00206 { 00207 uint32_t size = 0; 00208 size += ros::serialization::serializationLength(ik_link_name); 00209 size += ros::serialization::serializationLength(pose_stamped); 00210 size += ros::serialization::serializationLength(ik_seed_state); 00211 size += ros::serialization::serializationLength(robot_state); 00212 return size; 00213 } 00214 00215 typedef boost::shared_ptr< ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> > Ptr; 00216 typedef boost::shared_ptr< ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> const> ConstPtr; 00217 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00218 }; // struct PositionIKRequest 00219 typedef ::kinematics_msgs::PositionIKRequest_<std::allocator<void> > PositionIKRequest; 00220 00221 typedef boost::shared_ptr< ::kinematics_msgs::PositionIKRequest> PositionIKRequestPtr; 00222 typedef boost::shared_ptr< ::kinematics_msgs::PositionIKRequest const> PositionIKRequestConstPtr; 00223 00224 00225 template<typename ContainerAllocator> 00226 std::ostream& operator<<(std::ostream& s, const ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> & v) 00227 { 00228 ros::message_operations::Printer< ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> >::stream(s, "", v); 00229 return s;} 00230 00231 } // namespace kinematics_msgs 00232 00233 namespace ros 00234 { 00235 namespace message_traits 00236 { 00237 template<class ContainerAllocator> struct IsMessage< ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> > : public TrueType {}; 00238 template<class ContainerAllocator> struct IsMessage< ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> const> : public TrueType {}; 00239 template<class ContainerAllocator> 00240 struct MD5Sum< ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> > { 00241 static const char* value() 00242 { 00243 return "737bb756c6253bdd460b1383d0b12dac"; 00244 } 00245 00246 static const char* value(const ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> &) { return value(); } 00247 static const uint64_t static_value1 = 0x737bb756c6253bddULL; 00248 static const uint64_t static_value2 = 0x460b1383d0b12dacULL; 00249 }; 00250 00251 template<class ContainerAllocator> 00252 struct DataType< ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> > { 00253 static const char* value() 00254 { 00255 return "kinematics_msgs/PositionIKRequest"; 00256 } 00257 00258 static const char* value(const ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> &) { return value(); } 00259 }; 00260 00261 template<class ContainerAllocator> 00262 struct Definition< ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> > { 00263 static const char* value() 00264 { 00265 return "# A Position IK request message\n\ 00266 # The name of the link for which we are computing IK\n\ 00267 string ik_link_name\n\ 00268 \n\ 00269 # The (stamped) pose of the link\n\ 00270 geometry_msgs/PoseStamped pose_stamped\n\ 00271 \n\ 00272 # A RobotState consisting of hint/seed positions for the IK computation. \n\ 00273 # These may be used to seed the IK search. \n\ 00274 # The seed state MUST contain state for all joints to be used by the IK solver\n\ 00275 # to compute IK. The list of joints that the IK solver deals with can be found using\n\ 00276 # the kinematics_msgs/GetKinematicSolverInfo\n\ 00277 arm_navigation_msgs/RobotState ik_seed_state\n\ 00278 \n\ 00279 # Additional state information can be provided here to specify the starting positions \n\ 00280 # of other joints/links on the robot.\n\ 00281 arm_navigation_msgs/RobotState robot_state\n\ 00282 \n\ 00283 ================================================================================\n\ 00284 MSG: geometry_msgs/PoseStamped\n\ 00285 # A Pose with reference coordinate frame and timestamp\n\ 00286 Header header\n\ 00287 Pose pose\n\ 00288 \n\ 00289 ================================================================================\n\ 00290 MSG: std_msgs/Header\n\ 00291 # Standard metadata for higher-level stamped data types.\n\ 00292 # This is generally used to communicate timestamped data \n\ 00293 # in a particular coordinate frame.\n\ 00294 # \n\ 00295 # sequence ID: consecutively increasing ID \n\ 00296 uint32 seq\n\ 00297 #Two-integer timestamp that is expressed as:\n\ 00298 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00299 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00300 # time-handling sugar is provided by the client library\n\ 00301 time stamp\n\ 00302 #Frame this data is associated with\n\ 00303 # 0: no frame\n\ 00304 # 1: global frame\n\ 00305 string frame_id\n\ 00306 \n\ 00307 ================================================================================\n\ 00308 MSG: geometry_msgs/Pose\n\ 00309 # A representation of pose in free space, composed of postion and orientation. \n\ 00310 Point position\n\ 00311 Quaternion orientation\n\ 00312 \n\ 00313 ================================================================================\n\ 00314 MSG: geometry_msgs/Point\n\ 00315 # This contains the position of a point in free space\n\ 00316 float64 x\n\ 00317 float64 y\n\ 00318 float64 z\n\ 00319 \n\ 00320 ================================================================================\n\ 00321 MSG: geometry_msgs/Quaternion\n\ 00322 # This represents an orientation in free space in quaternion form.\n\ 00323 \n\ 00324 float64 x\n\ 00325 float64 y\n\ 00326 float64 z\n\ 00327 float64 w\n\ 00328 \n\ 00329 ================================================================================\n\ 00330 MSG: arm_navigation_msgs/RobotState\n\ 00331 # This message contains information about the robot state, i.e. the positions of its joints and links\n\ 00332 sensor_msgs/JointState joint_state\n\ 00333 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state\n\ 00334 \n\ 00335 ================================================================================\n\ 00336 MSG: sensor_msgs/JointState\n\ 00337 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\ 00338 #\n\ 00339 # The state of each joint (revolute or prismatic) is defined by:\n\ 00340 # * the position of the joint (rad or m),\n\ 00341 # * the velocity of the joint (rad/s or m/s) and \n\ 00342 # * the effort that is applied in the joint (Nm or N).\n\ 00343 #\n\ 00344 # Each joint is uniquely identified by its name\n\ 00345 # The header specifies the time at which the joint states were recorded. All the joint states\n\ 00346 # in one message have to be recorded at the same time.\n\ 00347 #\n\ 00348 # This message consists of a multiple arrays, one for each part of the joint state. \n\ 00349 # The goal is to make each of the fields optional. When e.g. your joints have no\n\ 00350 # effort associated with them, you can leave the effort array empty. \n\ 00351 #\n\ 00352 # All arrays in this message should have the same size, or be empty.\n\ 00353 # This is the only way to uniquely associate the joint name with the correct\n\ 00354 # states.\n\ 00355 \n\ 00356 \n\ 00357 Header header\n\ 00358 \n\ 00359 string[] name\n\ 00360 float64[] position\n\ 00361 float64[] velocity\n\ 00362 float64[] effort\n\ 00363 \n\ 00364 ================================================================================\n\ 00365 MSG: arm_navigation_msgs/MultiDOFJointState\n\ 00366 #A representation of a multi-dof joint state\n\ 00367 time stamp\n\ 00368 string[] joint_names\n\ 00369 string[] frame_ids\n\ 00370 string[] child_frame_ids\n\ 00371 geometry_msgs/Pose[] poses\n\ 00372 \n\ 00373 "; 00374 } 00375 00376 static const char* value(const ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> &) { return value(); } 00377 }; 00378 00379 } // namespace message_traits 00380 } // namespace ros 00381 00382 namespace ros 00383 { 00384 namespace serialization 00385 { 00386 00387 template<class ContainerAllocator> struct Serializer< ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> > 00388 { 00389 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00390 { 00391 stream.next(m.ik_link_name); 00392 stream.next(m.pose_stamped); 00393 stream.next(m.ik_seed_state); 00394 stream.next(m.robot_state); 00395 } 00396 00397 ROS_DECLARE_ALLINONE_SERIALIZER; 00398 }; // struct PositionIKRequest_ 00399 } // namespace serialization 00400 } // namespace ros 00401 00402 namespace ros 00403 { 00404 namespace message_operations 00405 { 00406 00407 template<class ContainerAllocator> 00408 struct Printer< ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> > 00409 { 00410 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> & v) 00411 { 00412 s << indent << "ik_link_name: "; 00413 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.ik_link_name); 00414 s << indent << "pose_stamped: "; 00415 s << std::endl; 00416 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.pose_stamped); 00417 s << indent << "ik_seed_state: "; 00418 s << std::endl; 00419 Printer< ::arm_navigation_msgs::RobotState_<ContainerAllocator> >::stream(s, indent + " ", v.ik_seed_state); 00420 s << indent << "robot_state: "; 00421 s << std::endl; 00422 Printer< ::arm_navigation_msgs::RobotState_<ContainerAllocator> >::stream(s, indent + " ", v.robot_state); 00423 } 00424 }; 00425 00426 00427 } // namespace message_operations 00428 } // namespace ros 00429 00430 #endif // KINEMATICS_MSGS_MESSAGE_POSITIONIKREQUEST_H 00431