IK.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-jsk-ros-pkg/doc_stacks/2013-03-23_12-16-27.483192/jsk-ros-pkg/openrave_planning/orrosplanning/srv/IK.srv */
00002 #ifndef ORROSPLANNING_SERVICE_IK_H
00003 #define ORROSPLANNING_SERVICE_IK_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 "ros/service_traits.h"
00018 
00019 #include "sensor_msgs/JointState.h"
00020 #include "geometry_msgs/PoseStamped.h"
00021 
00022 
00023 #include "trajectory_msgs/JointTrajectory.h"
00024 #include "arm_navigation_msgs/ArmNavigationErrorCodes.h"
00025 
00026 namespace orrosplanning
00027 {
00028 template <class ContainerAllocator>
00029 struct IKRequest_ {
00030   typedef IKRequest_<ContainerAllocator> Type;
00031 
00032   IKRequest_()
00033   : manip_name()
00034   , iktype()
00035   , joint_state()
00036   , pose_stamped()
00037   , filteroptions(0)
00038   {
00039   }
00040 
00041   IKRequest_(const ContainerAllocator& _alloc)
00042   : manip_name(_alloc)
00043   , iktype(_alloc)
00044   , joint_state(_alloc)
00045   , pose_stamped(_alloc)
00046   , filteroptions(0)
00047   {
00048   }
00049 
00050   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _manip_name_type;
00051   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  manip_name;
00052 
00053   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _iktype_type;
00054   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  iktype;
00055 
00056   typedef  ::sensor_msgs::JointState_<ContainerAllocator>  _joint_state_type;
00057    ::sensor_msgs::JointState_<ContainerAllocator>  joint_state;
00058 
00059   typedef  ::geometry_msgs::PoseStamped_<ContainerAllocator>  _pose_stamped_type;
00060    ::geometry_msgs::PoseStamped_<ContainerAllocator>  pose_stamped;
00061 
00062   typedef int32_t _filteroptions_type;
00063   int32_t filteroptions;
00064 
00065   enum { IGNORE_ENVIRONMENT_COLLISIONS = 1 };
00066   enum { IGNORE_SELF_COLLISIONS = 2 };
00067   enum { IGNORE_JOINT_LIMITS = 4 };
00068   enum { RETURN_CLOSEST_SOLUTION = 8 };
00069   enum { RETURN_ALL_SOLUTIONS = 16 };
00070 
00071   typedef boost::shared_ptr< ::orrosplanning::IKRequest_<ContainerAllocator> > Ptr;
00072   typedef boost::shared_ptr< ::orrosplanning::IKRequest_<ContainerAllocator>  const> ConstPtr;
00073   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00074 }; // struct IKRequest
00075 typedef  ::orrosplanning::IKRequest_<std::allocator<void> > IKRequest;
00076 
00077 typedef boost::shared_ptr< ::orrosplanning::IKRequest> IKRequestPtr;
00078 typedef boost::shared_ptr< ::orrosplanning::IKRequest const> IKRequestConstPtr;
00079 
00080 
00081 template <class ContainerAllocator>
00082 struct IKResponse_ {
00083   typedef IKResponse_<ContainerAllocator> Type;
00084 
00085   IKResponse_()
00086   : solutions()
00087   , error_code()
00088   {
00089   }
00090 
00091   IKResponse_(const ContainerAllocator& _alloc)
00092   : solutions(_alloc)
00093   , error_code(_alloc)
00094   {
00095   }
00096 
00097   typedef  ::trajectory_msgs::JointTrajectory_<ContainerAllocator>  _solutions_type;
00098    ::trajectory_msgs::JointTrajectory_<ContainerAllocator>  solutions;
00099 
00100   typedef  ::arm_navigation_msgs::ArmNavigationErrorCodes_<ContainerAllocator>  _error_code_type;
00101    ::arm_navigation_msgs::ArmNavigationErrorCodes_<ContainerAllocator>  error_code;
00102 
00103 
00104   typedef boost::shared_ptr< ::orrosplanning::IKResponse_<ContainerAllocator> > Ptr;
00105   typedef boost::shared_ptr< ::orrosplanning::IKResponse_<ContainerAllocator>  const> ConstPtr;
00106   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00107 }; // struct IKResponse
00108 typedef  ::orrosplanning::IKResponse_<std::allocator<void> > IKResponse;
00109 
00110 typedef boost::shared_ptr< ::orrosplanning::IKResponse> IKResponsePtr;
00111 typedef boost::shared_ptr< ::orrosplanning::IKResponse const> IKResponseConstPtr;
00112 
00113 struct IK
00114 {
00115 
00116 typedef IKRequest Request;
00117 typedef IKResponse Response;
00118 Request request;
00119 Response response;
00120 
00121 typedef Request RequestType;
00122 typedef Response ResponseType;
00123 }; // struct IK
00124 } // namespace orrosplanning
00125 
00126 namespace ros
00127 {
00128 namespace message_traits
00129 {
00130 template<class ContainerAllocator> struct IsMessage< ::orrosplanning::IKRequest_<ContainerAllocator> > : public TrueType {};
00131 template<class ContainerAllocator> struct IsMessage< ::orrosplanning::IKRequest_<ContainerAllocator>  const> : public TrueType {};
00132 template<class ContainerAllocator>
00133 struct MD5Sum< ::orrosplanning::IKRequest_<ContainerAllocator> > {
00134   static const char* value() 
00135   {
00136     return "6c7c32c8815dff364106532bc2227956";
00137   }
00138 
00139   static const char* value(const  ::orrosplanning::IKRequest_<ContainerAllocator> &) { return value(); } 
00140   static const uint64_t static_value1 = 0x6c7c32c8815dff36ULL;
00141   static const uint64_t static_value2 = 0x4106532bc2227956ULL;
00142 };
00143 
00144 template<class ContainerAllocator>
00145 struct DataType< ::orrosplanning::IKRequest_<ContainerAllocator> > {
00146   static const char* value() 
00147   {
00148     return "orrosplanning/IKRequest";
00149   }
00150 
00151   static const char* value(const  ::orrosplanning::IKRequest_<ContainerAllocator> &) { return value(); } 
00152 };
00153 
00154 template<class ContainerAllocator>
00155 struct Definition< ::orrosplanning::IKRequest_<ContainerAllocator> > {
00156   static const char* value() 
00157   {
00158     return "\n\
00159 \n\
00160 string manip_name\n\
00161 \n\
00162 \n\
00163 \n\
00164 string iktype\n\
00165 \n\
00166 \n\
00167 sensor_msgs/JointState joint_state\n\
00168 \n\
00169 \n\
00170 geometry_msgs/PoseStamped pose_stamped\n\
00171 \n\
00172 \n\
00173 int32 filteroptions\n\
00174 \n\
00175 \n\
00176 int32 IGNORE_ENVIRONMENT_COLLISIONS=1\n\
00177 int32 IGNORE_SELF_COLLISIONS=2\n\
00178 int32 IGNORE_JOINT_LIMITS=4\n\
00179 int32 RETURN_CLOSEST_SOLUTION=8\n\
00180 int32 RETURN_ALL_SOLUTIONS=16\n\
00181 \n\
00182 \n\
00183 ================================================================================\n\
00184 MSG: sensor_msgs/JointState\n\
00185 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00186 #\n\
00187 # The state of each joint (revolute or prismatic) is defined by:\n\
00188 #  * the position of the joint (rad or m),\n\
00189 #  * the velocity of the joint (rad/s or m/s) and \n\
00190 #  * the effort that is applied in the joint (Nm or N).\n\
00191 #\n\
00192 # Each joint is uniquely identified by its name\n\
00193 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00194 # in one message have to be recorded at the same time.\n\
00195 #\n\
00196 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00197 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00198 # effort associated with them, you can leave the effort array empty. \n\
00199 #\n\
00200 # All arrays in this message should have the same size, or be empty.\n\
00201 # This is the only way to uniquely associate the joint name with the correct\n\
00202 # states.\n\
00203 \n\
00204 \n\
00205 Header header\n\
00206 \n\
00207 string[] name\n\
00208 float64[] position\n\
00209 float64[] velocity\n\
00210 float64[] effort\n\
00211 \n\
00212 ================================================================================\n\
00213 MSG: std_msgs/Header\n\
00214 # Standard metadata for higher-level stamped data types.\n\
00215 # This is generally used to communicate timestamped data \n\
00216 # in a particular coordinate frame.\n\
00217 # \n\
00218 # sequence ID: consecutively increasing ID \n\
00219 uint32 seq\n\
00220 #Two-integer timestamp that is expressed as:\n\
00221 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00222 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00223 # time-handling sugar is provided by the client library\n\
00224 time stamp\n\
00225 #Frame this data is associated with\n\
00226 # 0: no frame\n\
00227 # 1: global frame\n\
00228 string frame_id\n\
00229 \n\
00230 ================================================================================\n\
00231 MSG: geometry_msgs/PoseStamped\n\
00232 # A Pose with reference coordinate frame and timestamp\n\
00233 Header header\n\
00234 Pose pose\n\
00235 \n\
00236 ================================================================================\n\
00237 MSG: geometry_msgs/Pose\n\
00238 # A representation of pose in free space, composed of postion and orientation. \n\
00239 Point position\n\
00240 Quaternion orientation\n\
00241 \n\
00242 ================================================================================\n\
00243 MSG: geometry_msgs/Point\n\
00244 # This contains the position of a point in free space\n\
00245 float64 x\n\
00246 float64 y\n\
00247 float64 z\n\
00248 \n\
00249 ================================================================================\n\
00250 MSG: geometry_msgs/Quaternion\n\
00251 # This represents an orientation in free space in quaternion form.\n\
00252 \n\
00253 float64 x\n\
00254 float64 y\n\
00255 float64 z\n\
00256 float64 w\n\
00257 \n\
00258 ";
00259   }
00260 
00261   static const char* value(const  ::orrosplanning::IKRequest_<ContainerAllocator> &) { return value(); } 
00262 };
00263 
00264 } // namespace message_traits
00265 } // namespace ros
00266 
00267 
00268 namespace ros
00269 {
00270 namespace message_traits
00271 {
00272 template<class ContainerAllocator> struct IsMessage< ::orrosplanning::IKResponse_<ContainerAllocator> > : public TrueType {};
00273 template<class ContainerAllocator> struct IsMessage< ::orrosplanning::IKResponse_<ContainerAllocator>  const> : public TrueType {};
00274 template<class ContainerAllocator>
00275 struct MD5Sum< ::orrosplanning::IKResponse_<ContainerAllocator> > {
00276   static const char* value() 
00277   {
00278     return "5f574f395e24640186b5db7e64e4180d";
00279   }
00280 
00281   static const char* value(const  ::orrosplanning::IKResponse_<ContainerAllocator> &) { return value(); } 
00282   static const uint64_t static_value1 = 0x5f574f395e246401ULL;
00283   static const uint64_t static_value2 = 0x86b5db7e64e4180dULL;
00284 };
00285 
00286 template<class ContainerAllocator>
00287 struct DataType< ::orrosplanning::IKResponse_<ContainerAllocator> > {
00288   static const char* value() 
00289   {
00290     return "orrosplanning/IKResponse";
00291   }
00292 
00293   static const char* value(const  ::orrosplanning::IKResponse_<ContainerAllocator> &) { return value(); } 
00294 };
00295 
00296 template<class ContainerAllocator>
00297 struct Definition< ::orrosplanning::IKResponse_<ContainerAllocator> > {
00298   static const char* value() 
00299   {
00300     return "\n\
00301 trajectory_msgs/JointTrajectory solutions\n\
00302 arm_navigation_msgs/ArmNavigationErrorCodes error_code\n\
00303 \n\
00304 \n\
00305 ================================================================================\n\
00306 MSG: trajectory_msgs/JointTrajectory\n\
00307 Header header\n\
00308 string[] joint_names\n\
00309 JointTrajectoryPoint[] points\n\
00310 ================================================================================\n\
00311 MSG: std_msgs/Header\n\
00312 # Standard metadata for higher-level stamped data types.\n\
00313 # This is generally used to communicate timestamped data \n\
00314 # in a particular coordinate frame.\n\
00315 # \n\
00316 # sequence ID: consecutively increasing ID \n\
00317 uint32 seq\n\
00318 #Two-integer timestamp that is expressed as:\n\
00319 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00320 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00321 # time-handling sugar is provided by the client library\n\
00322 time stamp\n\
00323 #Frame this data is associated with\n\
00324 # 0: no frame\n\
00325 # 1: global frame\n\
00326 string frame_id\n\
00327 \n\
00328 ================================================================================\n\
00329 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00330 float64[] positions\n\
00331 float64[] velocities\n\
00332 float64[] accelerations\n\
00333 duration time_from_start\n\
00334 ================================================================================\n\
00335 MSG: arm_navigation_msgs/ArmNavigationErrorCodes\n\
00336 int32 val\n\
00337 \n\
00338 # overall behavior\n\
00339 int32 PLANNING_FAILED=-1\n\
00340 int32 SUCCESS=1\n\
00341 int32 TIMED_OUT=-2\n\
00342 \n\
00343 # start state errors\n\
00344 int32 START_STATE_IN_COLLISION=-3\n\
00345 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00346 \n\
00347 # goal errors\n\
00348 int32 GOAL_IN_COLLISION=-5\n\
00349 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00350 \n\
00351 # robot state\n\
00352 int32 INVALID_ROBOT_STATE=-7\n\
00353 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00354 \n\
00355 # planning request errors\n\
00356 int32 INVALID_PLANNER_ID=-9\n\
00357 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00358 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00359 int32 INVALID_GROUP_NAME=-12\n\
00360 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00361 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00362 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00363 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00364 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00365 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00366 \n\
00367 # state/trajectory monitor errors\n\
00368 int32 INVALID_TRAJECTORY=-19\n\
00369 int32 INVALID_INDEX=-20\n\
00370 int32 JOINT_LIMITS_VIOLATED=-21\n\
00371 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00372 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00373 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00374 int32 JOINTS_NOT_MOVING=-25\n\
00375 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00376 \n\
00377 # system errors\n\
00378 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00379 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00380 int32 ROBOT_STATE_STALE=-29\n\
00381 int32 SENSOR_INFO_STALE=-30\n\
00382 \n\
00383 # kinematics errors\n\
00384 int32 NO_IK_SOLUTION=-31\n\
00385 int32 INVALID_LINK_NAME=-32\n\
00386 int32 IK_LINK_IN_COLLISION=-33\n\
00387 int32 NO_FK_SOLUTION=-34\n\
00388 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00389 \n\
00390 # general errors\n\
00391 int32 INVALID_TIMEOUT=-36\n\
00392 \n\
00393 \n\
00394 ";
00395   }
00396 
00397   static const char* value(const  ::orrosplanning::IKResponse_<ContainerAllocator> &) { return value(); } 
00398 };
00399 
00400 } // namespace message_traits
00401 } // namespace ros
00402 
00403 namespace ros
00404 {
00405 namespace serialization
00406 {
00407 
00408 template<class ContainerAllocator> struct Serializer< ::orrosplanning::IKRequest_<ContainerAllocator> >
00409 {
00410   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00411   {
00412     stream.next(m.manip_name);
00413     stream.next(m.iktype);
00414     stream.next(m.joint_state);
00415     stream.next(m.pose_stamped);
00416     stream.next(m.filteroptions);
00417   }
00418 
00419   ROS_DECLARE_ALLINONE_SERIALIZER;
00420 }; // struct IKRequest_
00421 } // namespace serialization
00422 } // namespace ros
00423 
00424 
00425 namespace ros
00426 {
00427 namespace serialization
00428 {
00429 
00430 template<class ContainerAllocator> struct Serializer< ::orrosplanning::IKResponse_<ContainerAllocator> >
00431 {
00432   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00433   {
00434     stream.next(m.solutions);
00435     stream.next(m.error_code);
00436   }
00437 
00438   ROS_DECLARE_ALLINONE_SERIALIZER;
00439 }; // struct IKResponse_
00440 } // namespace serialization
00441 } // namespace ros
00442 
00443 namespace ros
00444 {
00445 namespace service_traits
00446 {
00447 template<>
00448 struct MD5Sum<orrosplanning::IK> {
00449   static const char* value() 
00450   {
00451     return "31cc39758dd73da8b3d6340b2388f6a8";
00452   }
00453 
00454   static const char* value(const orrosplanning::IK&) { return value(); } 
00455 };
00456 
00457 template<>
00458 struct DataType<orrosplanning::IK> {
00459   static const char* value() 
00460   {
00461     return "orrosplanning/IK";
00462   }
00463 
00464   static const char* value(const orrosplanning::IK&) { return value(); } 
00465 };
00466 
00467 template<class ContainerAllocator>
00468 struct MD5Sum<orrosplanning::IKRequest_<ContainerAllocator> > {
00469   static const char* value() 
00470   {
00471     return "31cc39758dd73da8b3d6340b2388f6a8";
00472   }
00473 
00474   static const char* value(const orrosplanning::IKRequest_<ContainerAllocator> &) { return value(); } 
00475 };
00476 
00477 template<class ContainerAllocator>
00478 struct DataType<orrosplanning::IKRequest_<ContainerAllocator> > {
00479   static const char* value() 
00480   {
00481     return "orrosplanning/IK";
00482   }
00483 
00484   static const char* value(const orrosplanning::IKRequest_<ContainerAllocator> &) { return value(); } 
00485 };
00486 
00487 template<class ContainerAllocator>
00488 struct MD5Sum<orrosplanning::IKResponse_<ContainerAllocator> > {
00489   static const char* value() 
00490   {
00491     return "31cc39758dd73da8b3d6340b2388f6a8";
00492   }
00493 
00494   static const char* value(const orrosplanning::IKResponse_<ContainerAllocator> &) { return value(); } 
00495 };
00496 
00497 template<class ContainerAllocator>
00498 struct DataType<orrosplanning::IKResponse_<ContainerAllocator> > {
00499   static const char* value() 
00500   {
00501     return "orrosplanning/IK";
00502   }
00503 
00504   static const char* value(const orrosplanning::IKResponse_<ContainerAllocator> &) { return value(); } 
00505 };
00506 
00507 } // namespace service_traits
00508 } // namespace ros
00509 
00510 #endif // ORROSPLANNING_SERVICE_IK_H
00511 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


orrosplanning
Author(s): Rosen Diankov (rosen.diankov@gmail.com)
autogenerated on Sat Mar 23 2013 22:32:57