00001
00002 #ifndef MOTION_PLANNING_MSGS_SERVICE_CONVERTTOJOINTCONSTRAINT_H
00003 #define MOTION_PLANNING_MSGS_SERVICE_CONVERTTOJOINTCONSTRAINT_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/service_traits.h"
00014
00015 #include "motion_planning_msgs/WorkspaceParameters.h"
00016 #include "motion_planning_msgs/RobotState.h"
00017 #include "motion_planning_msgs/RobotState.h"
00018 #include "motion_planning_msgs/Constraints.h"
00019
00020
00021 #include "motion_planning_msgs/JointConstraint.h"
00022
00023 namespace motion_planning_msgs
00024 {
00025 template <class ContainerAllocator>
00026 struct ConvertToJointConstraintRequest_ : public ros::Message
00027 {
00028 typedef ConvertToJointConstraintRequest_<ContainerAllocator> Type;
00029
00030 ConvertToJointConstraintRequest_()
00031 : model_id()
00032 , workspace_parameters()
00033 , start_state()
00034 , joint_names()
00035 , init_states()
00036 , constraints()
00037 , allowed_time(0.0)
00038 {
00039 }
00040
00041 ConvertToJointConstraintRequest_(const ContainerAllocator& _alloc)
00042 : model_id(_alloc)
00043 , workspace_parameters(_alloc)
00044 , start_state(_alloc)
00045 , joint_names(_alloc)
00046 , init_states(_alloc)
00047 , constraints(_alloc)
00048 , allowed_time(0.0)
00049 {
00050 }
00051
00052 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _model_id_type;
00053 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > model_id;
00054
00055 typedef ::motion_planning_msgs::WorkspaceParameters_<ContainerAllocator> _workspace_parameters_type;
00056 ::motion_planning_msgs::WorkspaceParameters_<ContainerAllocator> workspace_parameters;
00057
00058 typedef ::motion_planning_msgs::RobotState_<ContainerAllocator> _start_state_type;
00059 ::motion_planning_msgs::RobotState_<ContainerAllocator> start_state;
00060
00061 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;
00062 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;
00063
00064 typedef std::vector< ::motion_planning_msgs::RobotState_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::RobotState_<ContainerAllocator> >::other > _init_states_type;
00065 std::vector< ::motion_planning_msgs::RobotState_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::RobotState_<ContainerAllocator> >::other > init_states;
00066
00067 typedef ::motion_planning_msgs::Constraints_<ContainerAllocator> _constraints_type;
00068 ::motion_planning_msgs::Constraints_<ContainerAllocator> constraints;
00069
00070 typedef double _allowed_time_type;
00071 double allowed_time;
00072
00073
00074 ROS_DEPRECATED uint32_t get_joint_names_size() const { return (uint32_t)joint_names.size(); }
00075 ROS_DEPRECATED void set_joint_names_size(uint32_t size) { joint_names.resize((size_t)size); }
00076 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; }
00077 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; }
00078 ROS_DEPRECATED uint32_t get_init_states_size() const { return (uint32_t)init_states.size(); }
00079 ROS_DEPRECATED void set_init_states_size(uint32_t size) { init_states.resize((size_t)size); }
00080 ROS_DEPRECATED void get_init_states_vec(std::vector< ::motion_planning_msgs::RobotState_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::RobotState_<ContainerAllocator> >::other > & vec) const { vec = this->init_states; }
00081 ROS_DEPRECATED void set_init_states_vec(const std::vector< ::motion_planning_msgs::RobotState_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::RobotState_<ContainerAllocator> >::other > & vec) { this->init_states = vec; }
00082 private:
00083 static const char* __s_getDataType_() { return "motion_planning_msgs/ConvertToJointConstraintRequest"; }
00084 public:
00085 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00086
00087 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00088
00089 private:
00090 static const char* __s_getMD5Sum_() { return "8b3ecfc1134a2ed8c555c48c08a7aff2"; }
00091 public:
00092 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00093
00094 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00095
00096 private:
00097 static const char* __s_getServerMD5Sum_() { return "44f1f1ccbb08264490b769e8b8b79668"; }
00098 public:
00099 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00100
00101 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00102
00103 private:
00104 static const char* __s_getMessageDefinition_() { return "string model_id\n\
00105 \n\
00106 \n\
00107 motion_planning_msgs/WorkspaceParameters workspace_parameters\n\
00108 \n\
00109 \n\
00110 \n\
00111 \n\
00112 motion_planning_msgs/RobotState start_state\n\
00113 \n\
00114 \n\
00115 string[] joint_names\n\
00116 \n\
00117 \n\
00118 motion_planning_msgs/RobotState[] init_states\n\
00119 \n\
00120 \n\
00121 motion_planning_msgs/Constraints constraints\n\
00122 \n\
00123 \n\
00124 float64 allowed_time\n\
00125 \n\
00126 \n\
00127 ================================================================================\n\
00128 MSG: motion_planning_msgs/WorkspaceParameters\n\
00129 # This message contains a set of parameters useful in\n\
00130 # setting up the workspace for planning\n\
00131 geometric_shapes_msgs/Shape workspace_region_shape\n\
00132 geometry_msgs/PoseStamped workspace_region_pose\n\
00133 \n\
00134 \n\
00135 ================================================================================\n\
00136 MSG: geometric_shapes_msgs/Shape\n\
00137 byte SPHERE=0\n\
00138 byte BOX=1\n\
00139 byte CYLINDER=2\n\
00140 byte MESH=3\n\
00141 \n\
00142 byte type\n\
00143 \n\
00144 \n\
00145 #### define sphere, box, cylinder ####\n\
00146 # the origin of each shape is considered at the shape's center\n\
00147 \n\
00148 # for sphere\n\
00149 # radius := dimensions[0]\n\
00150 \n\
00151 # for cylinder\n\
00152 # radius := dimensions[0]\n\
00153 # length := dimensions[1]\n\
00154 # the length is along the Z axis\n\
00155 \n\
00156 # for box\n\
00157 # size_x := dimensions[0]\n\
00158 # size_y := dimensions[1]\n\
00159 # size_z := dimensions[2]\n\
00160 float64[] dimensions\n\
00161 \n\
00162 \n\
00163 #### define mesh ####\n\
00164 \n\
00165 # list of triangles; triangle k is defined by tre vertices located\n\
00166 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00167 int32[] triangles\n\
00168 geometry_msgs/Point[] vertices\n\
00169 \n\
00170 ================================================================================\n\
00171 MSG: geometry_msgs/Point\n\
00172 # This contains the position of a point in free space\n\
00173 float64 x\n\
00174 float64 y\n\
00175 float64 z\n\
00176 \n\
00177 ================================================================================\n\
00178 MSG: geometry_msgs/PoseStamped\n\
00179 # A Pose with reference coordinate frame and timestamp\n\
00180 Header header\n\
00181 Pose pose\n\
00182 \n\
00183 ================================================================================\n\
00184 MSG: std_msgs/Header\n\
00185 # Standard metadata for higher-level stamped data types.\n\
00186 # This is generally used to communicate timestamped data \n\
00187 # in a particular coordinate frame.\n\
00188 # \n\
00189 # sequence ID: consecutively increasing ID \n\
00190 uint32 seq\n\
00191 #Two-integer timestamp that is expressed as:\n\
00192 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00193 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00194 # time-handling sugar is provided by the client library\n\
00195 time stamp\n\
00196 #Frame this data is associated with\n\
00197 # 0: no frame\n\
00198 # 1: global frame\n\
00199 string frame_id\n\
00200 \n\
00201 ================================================================================\n\
00202 MSG: geometry_msgs/Pose\n\
00203 # A representation of pose in free space, composed of postion and orientation. \n\
00204 Point position\n\
00205 Quaternion orientation\n\
00206 \n\
00207 ================================================================================\n\
00208 MSG: geometry_msgs/Quaternion\n\
00209 # This represents an orientation in free space in quaternion form.\n\
00210 \n\
00211 float64 x\n\
00212 float64 y\n\
00213 float64 z\n\
00214 float64 w\n\
00215 \n\
00216 ================================================================================\n\
00217 MSG: motion_planning_msgs/RobotState\n\
00218 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00219 sensor_msgs/JointState joint_state\n\
00220 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00221 ================================================================================\n\
00222 MSG: sensor_msgs/JointState\n\
00223 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00224 #\n\
00225 # The state of each joint (revolute or prismatic) is defined by:\n\
00226 # * the position of the joint (rad or m),\n\
00227 # * the velocity of the joint (rad/s or m/s) and \n\
00228 # * the effort that is applied in the joint (Nm or N).\n\
00229 #\n\
00230 # Each joint is uniquely identified by its name\n\
00231 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00232 # in one message have to be recorded at the same time.\n\
00233 #\n\
00234 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00235 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00236 # effort associated with them, you can leave the effort array empty. \n\
00237 #\n\
00238 # All arrays in this message should have the same size, or be empty.\n\
00239 # This is the only way to uniquely associate the joint name with the correct\n\
00240 # states.\n\
00241 \n\
00242 \n\
00243 Header header\n\
00244 \n\
00245 string[] name\n\
00246 float64[] position\n\
00247 float64[] velocity\n\
00248 float64[] effort\n\
00249 \n\
00250 ================================================================================\n\
00251 MSG: motion_planning_msgs/MultiDOFJointState\n\
00252 #A representation of a multi-dof joint state\n\
00253 time stamp\n\
00254 string[] joint_names\n\
00255 string[] frame_ids\n\
00256 string[] child_frame_ids\n\
00257 geometry_msgs/Pose[] poses\n\
00258 \n\
00259 ================================================================================\n\
00260 MSG: motion_planning_msgs/Constraints\n\
00261 # This message contains a list of motion planning constraints.\n\
00262 \n\
00263 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00264 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00265 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00266 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00267 \n\
00268 ================================================================================\n\
00269 MSG: motion_planning_msgs/JointConstraint\n\
00270 # Constrain the position of a joint to be within a certain bound\n\
00271 string joint_name\n\
00272 \n\
00273 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00274 float64 position\n\
00275 float64 tolerance_above\n\
00276 float64 tolerance_below\n\
00277 \n\
00278 # A weighting factor for this constraint\n\
00279 float64 weight\n\
00280 ================================================================================\n\
00281 MSG: motion_planning_msgs/PositionConstraint\n\
00282 # This message contains the definition of a position constraint.\n\
00283 Header header\n\
00284 \n\
00285 # The robot link this constraint refers to\n\
00286 string link_name\n\
00287 \n\
00288 # The offset (in the link frame) for the target point on the link we are planning for\n\
00289 geometry_msgs/Point target_point_offset\n\
00290 \n\
00291 # The nominal/target position for the point we are planning for\n\
00292 geometry_msgs/Point position\n\
00293 \n\
00294 # The shape of the bounded region that constrains the position of the end-effector\n\
00295 # This region is always centered at the position defined above\n\
00296 geometric_shapes_msgs/Shape constraint_region_shape\n\
00297 \n\
00298 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00299 # This allows the specification of non-axis aligned constraints\n\
00300 geometry_msgs/Quaternion constraint_region_orientation\n\
00301 \n\
00302 # Constraint weighting factor - a weight for this constraint\n\
00303 float64 weight\n\
00304 ================================================================================\n\
00305 MSG: motion_planning_msgs/OrientationConstraint\n\
00306 # This message contains the definition of an orientation constraint.\n\
00307 Header header\n\
00308 \n\
00309 # The robot link this constraint refers to\n\
00310 string link_name\n\
00311 \n\
00312 # The type of the constraint\n\
00313 int32 type\n\
00314 int32 LINK_FRAME=0\n\
00315 int32 HEADER_FRAME=1\n\
00316 \n\
00317 # The desired orientation of the robot link specified as a quaternion\n\
00318 geometry_msgs/Quaternion orientation\n\
00319 \n\
00320 # optional RPY error tolerances specified if \n\
00321 float64 absolute_roll_tolerance\n\
00322 float64 absolute_pitch_tolerance\n\
00323 float64 absolute_yaw_tolerance\n\
00324 \n\
00325 # Constraint weighting factor - a weight for this constraint\n\
00326 float64 weight\n\
00327 \n\
00328 ================================================================================\n\
00329 MSG: motion_planning_msgs/VisibilityConstraint\n\
00330 # This message contains the definition of a visibility constraint.\n\
00331 Header header\n\
00332 \n\
00333 # The point stamped target that needs to be kept within view of the sensor\n\
00334 geometry_msgs/PointStamped target\n\
00335 \n\
00336 # The local pose of the frame in which visibility is to be maintained\n\
00337 # The frame id should represent the robot link to which the sensor is attached\n\
00338 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00339 geometry_msgs/PoseStamped sensor_pose\n\
00340 \n\
00341 # The deviation (in radians) that will be tolerated\n\
00342 # Constraint error will be measured as the solid angle between the \n\
00343 # X axis of the frame defined above and the vector between the origin \n\
00344 # of the frame defined above and the target location\n\
00345 float64 absolute_tolerance\n\
00346 \n\
00347 \n\
00348 ================================================================================\n\
00349 MSG: geometry_msgs/PointStamped\n\
00350 # This represents a Point with reference coordinate frame and timestamp\n\
00351 Header header\n\
00352 Point point\n\
00353 \n\
00354 "; }
00355 public:
00356 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00357
00358 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00359
00360 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00361 {
00362 ros::serialization::OStream stream(write_ptr, 1000000000);
00363 ros::serialization::serialize(stream, model_id);
00364 ros::serialization::serialize(stream, workspace_parameters);
00365 ros::serialization::serialize(stream, start_state);
00366 ros::serialization::serialize(stream, joint_names);
00367 ros::serialization::serialize(stream, init_states);
00368 ros::serialization::serialize(stream, constraints);
00369 ros::serialization::serialize(stream, allowed_time);
00370 return stream.getData();
00371 }
00372
00373 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00374 {
00375 ros::serialization::IStream stream(read_ptr, 1000000000);
00376 ros::serialization::deserialize(stream, model_id);
00377 ros::serialization::deserialize(stream, workspace_parameters);
00378 ros::serialization::deserialize(stream, start_state);
00379 ros::serialization::deserialize(stream, joint_names);
00380 ros::serialization::deserialize(stream, init_states);
00381 ros::serialization::deserialize(stream, constraints);
00382 ros::serialization::deserialize(stream, allowed_time);
00383 return stream.getData();
00384 }
00385
00386 ROS_DEPRECATED virtual uint32_t serializationLength() const
00387 {
00388 uint32_t size = 0;
00389 size += ros::serialization::serializationLength(model_id);
00390 size += ros::serialization::serializationLength(workspace_parameters);
00391 size += ros::serialization::serializationLength(start_state);
00392 size += ros::serialization::serializationLength(joint_names);
00393 size += ros::serialization::serializationLength(init_states);
00394 size += ros::serialization::serializationLength(constraints);
00395 size += ros::serialization::serializationLength(allowed_time);
00396 return size;
00397 }
00398
00399 typedef boost::shared_ptr< ::motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> > Ptr;
00400 typedef boost::shared_ptr< ::motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> const> ConstPtr;
00401 };
00402 typedef ::motion_planning_msgs::ConvertToJointConstraintRequest_<std::allocator<void> > ConvertToJointConstraintRequest;
00403
00404 typedef boost::shared_ptr< ::motion_planning_msgs::ConvertToJointConstraintRequest> ConvertToJointConstraintRequestPtr;
00405 typedef boost::shared_ptr< ::motion_planning_msgs::ConvertToJointConstraintRequest const> ConvertToJointConstraintRequestConstPtr;
00406
00407
00408 template <class ContainerAllocator>
00409 struct ConvertToJointConstraintResponse_ : public ros::Message
00410 {
00411 typedef ConvertToJointConstraintResponse_<ContainerAllocator> Type;
00412
00413 ConvertToJointConstraintResponse_()
00414 : joint_constraints()
00415 {
00416 }
00417
00418 ConvertToJointConstraintResponse_(const ContainerAllocator& _alloc)
00419 : joint_constraints(_alloc)
00420 {
00421 }
00422
00423 typedef std::vector< ::motion_planning_msgs::JointConstraint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::JointConstraint_<ContainerAllocator> >::other > _joint_constraints_type;
00424 std::vector< ::motion_planning_msgs::JointConstraint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::JointConstraint_<ContainerAllocator> >::other > joint_constraints;
00425
00426
00427 ROS_DEPRECATED uint32_t get_joint_constraints_size() const { return (uint32_t)joint_constraints.size(); }
00428 ROS_DEPRECATED void set_joint_constraints_size(uint32_t size) { joint_constraints.resize((size_t)size); }
00429 ROS_DEPRECATED void get_joint_constraints_vec(std::vector< ::motion_planning_msgs::JointConstraint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::JointConstraint_<ContainerAllocator> >::other > & vec) const { vec = this->joint_constraints; }
00430 ROS_DEPRECATED void set_joint_constraints_vec(const std::vector< ::motion_planning_msgs::JointConstraint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::JointConstraint_<ContainerAllocator> >::other > & vec) { this->joint_constraints = vec; }
00431 private:
00432 static const char* __s_getDataType_() { return "motion_planning_msgs/ConvertToJointConstraintResponse"; }
00433 public:
00434 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00435
00436 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00437
00438 private:
00439 static const char* __s_getMD5Sum_() { return "d7a8073958b17b9bc926b7fb8d466ac6"; }
00440 public:
00441 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00442
00443 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00444
00445 private:
00446 static const char* __s_getServerMD5Sum_() { return "44f1f1ccbb08264490b769e8b8b79668"; }
00447 public:
00448 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00449
00450 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00451
00452 private:
00453 static const char* __s_getMessageDefinition_() { return "\n\
00454 \n\
00455 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00456 \n\
00457 \n\
00458 ================================================================================\n\
00459 MSG: motion_planning_msgs/JointConstraint\n\
00460 # Constrain the position of a joint to be within a certain bound\n\
00461 string joint_name\n\
00462 \n\
00463 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00464 float64 position\n\
00465 float64 tolerance_above\n\
00466 float64 tolerance_below\n\
00467 \n\
00468 # A weighting factor for this constraint\n\
00469 float64 weight\n\
00470 "; }
00471 public:
00472 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00473
00474 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00475
00476 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00477 {
00478 ros::serialization::OStream stream(write_ptr, 1000000000);
00479 ros::serialization::serialize(stream, joint_constraints);
00480 return stream.getData();
00481 }
00482
00483 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00484 {
00485 ros::serialization::IStream stream(read_ptr, 1000000000);
00486 ros::serialization::deserialize(stream, joint_constraints);
00487 return stream.getData();
00488 }
00489
00490 ROS_DEPRECATED virtual uint32_t serializationLength() const
00491 {
00492 uint32_t size = 0;
00493 size += ros::serialization::serializationLength(joint_constraints);
00494 return size;
00495 }
00496
00497 typedef boost::shared_ptr< ::motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> > Ptr;
00498 typedef boost::shared_ptr< ::motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> const> ConstPtr;
00499 };
00500 typedef ::motion_planning_msgs::ConvertToJointConstraintResponse_<std::allocator<void> > ConvertToJointConstraintResponse;
00501
00502 typedef boost::shared_ptr< ::motion_planning_msgs::ConvertToJointConstraintResponse> ConvertToJointConstraintResponsePtr;
00503 typedef boost::shared_ptr< ::motion_planning_msgs::ConvertToJointConstraintResponse const> ConvertToJointConstraintResponseConstPtr;
00504
00505 struct ConvertToJointConstraint
00506 {
00507
00508 typedef ConvertToJointConstraintRequest Request;
00509 typedef ConvertToJointConstraintResponse Response;
00510 Request request;
00511 Response response;
00512
00513 typedef Request RequestType;
00514 typedef Response ResponseType;
00515 };
00516 }
00517
00518 namespace ros
00519 {
00520 namespace message_traits
00521 {
00522 template<class ContainerAllocator>
00523 struct MD5Sum< ::motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> > {
00524 static const char* value()
00525 {
00526 return "8b3ecfc1134a2ed8c555c48c08a7aff2";
00527 }
00528
00529 static const char* value(const ::motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> &) { return value(); }
00530 static const uint64_t static_value1 = 0x8b3ecfc1134a2ed8ULL;
00531 static const uint64_t static_value2 = 0xc555c48c08a7aff2ULL;
00532 };
00533
00534 template<class ContainerAllocator>
00535 struct DataType< ::motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> > {
00536 static const char* value()
00537 {
00538 return "motion_planning_msgs/ConvertToJointConstraintRequest";
00539 }
00540
00541 static const char* value(const ::motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> &) { return value(); }
00542 };
00543
00544 template<class ContainerAllocator>
00545 struct Definition< ::motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> > {
00546 static const char* value()
00547 {
00548 return "string model_id\n\
00549 \n\
00550 \n\
00551 motion_planning_msgs/WorkspaceParameters workspace_parameters\n\
00552 \n\
00553 \n\
00554 \n\
00555 \n\
00556 motion_planning_msgs/RobotState start_state\n\
00557 \n\
00558 \n\
00559 string[] joint_names\n\
00560 \n\
00561 \n\
00562 motion_planning_msgs/RobotState[] init_states\n\
00563 \n\
00564 \n\
00565 motion_planning_msgs/Constraints constraints\n\
00566 \n\
00567 \n\
00568 float64 allowed_time\n\
00569 \n\
00570 \n\
00571 ================================================================================\n\
00572 MSG: motion_planning_msgs/WorkspaceParameters\n\
00573 # This message contains a set of parameters useful in\n\
00574 # setting up the workspace for planning\n\
00575 geometric_shapes_msgs/Shape workspace_region_shape\n\
00576 geometry_msgs/PoseStamped workspace_region_pose\n\
00577 \n\
00578 \n\
00579 ================================================================================\n\
00580 MSG: geometric_shapes_msgs/Shape\n\
00581 byte SPHERE=0\n\
00582 byte BOX=1\n\
00583 byte CYLINDER=2\n\
00584 byte MESH=3\n\
00585 \n\
00586 byte type\n\
00587 \n\
00588 \n\
00589 #### define sphere, box, cylinder ####\n\
00590 # the origin of each shape is considered at the shape's center\n\
00591 \n\
00592 # for sphere\n\
00593 # radius := dimensions[0]\n\
00594 \n\
00595 # for cylinder\n\
00596 # radius := dimensions[0]\n\
00597 # length := dimensions[1]\n\
00598 # the length is along the Z axis\n\
00599 \n\
00600 # for box\n\
00601 # size_x := dimensions[0]\n\
00602 # size_y := dimensions[1]\n\
00603 # size_z := dimensions[2]\n\
00604 float64[] dimensions\n\
00605 \n\
00606 \n\
00607 #### define mesh ####\n\
00608 \n\
00609 # list of triangles; triangle k is defined by tre vertices located\n\
00610 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00611 int32[] triangles\n\
00612 geometry_msgs/Point[] vertices\n\
00613 \n\
00614 ================================================================================\n\
00615 MSG: geometry_msgs/Point\n\
00616 # This contains the position of a point in free space\n\
00617 float64 x\n\
00618 float64 y\n\
00619 float64 z\n\
00620 \n\
00621 ================================================================================\n\
00622 MSG: geometry_msgs/PoseStamped\n\
00623 # A Pose with reference coordinate frame and timestamp\n\
00624 Header header\n\
00625 Pose pose\n\
00626 \n\
00627 ================================================================================\n\
00628 MSG: std_msgs/Header\n\
00629 # Standard metadata for higher-level stamped data types.\n\
00630 # This is generally used to communicate timestamped data \n\
00631 # in a particular coordinate frame.\n\
00632 # \n\
00633 # sequence ID: consecutively increasing ID \n\
00634 uint32 seq\n\
00635 #Two-integer timestamp that is expressed as:\n\
00636 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00637 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00638 # time-handling sugar is provided by the client library\n\
00639 time stamp\n\
00640 #Frame this data is associated with\n\
00641 # 0: no frame\n\
00642 # 1: global frame\n\
00643 string frame_id\n\
00644 \n\
00645 ================================================================================\n\
00646 MSG: geometry_msgs/Pose\n\
00647 # A representation of pose in free space, composed of postion and orientation. \n\
00648 Point position\n\
00649 Quaternion orientation\n\
00650 \n\
00651 ================================================================================\n\
00652 MSG: geometry_msgs/Quaternion\n\
00653 # This represents an orientation in free space in quaternion form.\n\
00654 \n\
00655 float64 x\n\
00656 float64 y\n\
00657 float64 z\n\
00658 float64 w\n\
00659 \n\
00660 ================================================================================\n\
00661 MSG: motion_planning_msgs/RobotState\n\
00662 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00663 sensor_msgs/JointState joint_state\n\
00664 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00665 ================================================================================\n\
00666 MSG: sensor_msgs/JointState\n\
00667 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00668 #\n\
00669 # The state of each joint (revolute or prismatic) is defined by:\n\
00670 # * the position of the joint (rad or m),\n\
00671 # * the velocity of the joint (rad/s or m/s) and \n\
00672 # * the effort that is applied in the joint (Nm or N).\n\
00673 #\n\
00674 # Each joint is uniquely identified by its name\n\
00675 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00676 # in one message have to be recorded at the same time.\n\
00677 #\n\
00678 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00679 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00680 # effort associated with them, you can leave the effort array empty. \n\
00681 #\n\
00682 # All arrays in this message should have the same size, or be empty.\n\
00683 # This is the only way to uniquely associate the joint name with the correct\n\
00684 # states.\n\
00685 \n\
00686 \n\
00687 Header header\n\
00688 \n\
00689 string[] name\n\
00690 float64[] position\n\
00691 float64[] velocity\n\
00692 float64[] effort\n\
00693 \n\
00694 ================================================================================\n\
00695 MSG: motion_planning_msgs/MultiDOFJointState\n\
00696 #A representation of a multi-dof joint state\n\
00697 time stamp\n\
00698 string[] joint_names\n\
00699 string[] frame_ids\n\
00700 string[] child_frame_ids\n\
00701 geometry_msgs/Pose[] poses\n\
00702 \n\
00703 ================================================================================\n\
00704 MSG: motion_planning_msgs/Constraints\n\
00705 # This message contains a list of motion planning constraints.\n\
00706 \n\
00707 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00708 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00709 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00710 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00711 \n\
00712 ================================================================================\n\
00713 MSG: motion_planning_msgs/JointConstraint\n\
00714 # Constrain the position of a joint to be within a certain bound\n\
00715 string joint_name\n\
00716 \n\
00717 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00718 float64 position\n\
00719 float64 tolerance_above\n\
00720 float64 tolerance_below\n\
00721 \n\
00722 # A weighting factor for this constraint\n\
00723 float64 weight\n\
00724 ================================================================================\n\
00725 MSG: motion_planning_msgs/PositionConstraint\n\
00726 # This message contains the definition of a position constraint.\n\
00727 Header header\n\
00728 \n\
00729 # The robot link this constraint refers to\n\
00730 string link_name\n\
00731 \n\
00732 # The offset (in the link frame) for the target point on the link we are planning for\n\
00733 geometry_msgs/Point target_point_offset\n\
00734 \n\
00735 # The nominal/target position for the point we are planning for\n\
00736 geometry_msgs/Point position\n\
00737 \n\
00738 # The shape of the bounded region that constrains the position of the end-effector\n\
00739 # This region is always centered at the position defined above\n\
00740 geometric_shapes_msgs/Shape constraint_region_shape\n\
00741 \n\
00742 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00743 # This allows the specification of non-axis aligned constraints\n\
00744 geometry_msgs/Quaternion constraint_region_orientation\n\
00745 \n\
00746 # Constraint weighting factor - a weight for this constraint\n\
00747 float64 weight\n\
00748 ================================================================================\n\
00749 MSG: motion_planning_msgs/OrientationConstraint\n\
00750 # This message contains the definition of an orientation constraint.\n\
00751 Header header\n\
00752 \n\
00753 # The robot link this constraint refers to\n\
00754 string link_name\n\
00755 \n\
00756 # The type of the constraint\n\
00757 int32 type\n\
00758 int32 LINK_FRAME=0\n\
00759 int32 HEADER_FRAME=1\n\
00760 \n\
00761 # The desired orientation of the robot link specified as a quaternion\n\
00762 geometry_msgs/Quaternion orientation\n\
00763 \n\
00764 # optional RPY error tolerances specified if \n\
00765 float64 absolute_roll_tolerance\n\
00766 float64 absolute_pitch_tolerance\n\
00767 float64 absolute_yaw_tolerance\n\
00768 \n\
00769 # Constraint weighting factor - a weight for this constraint\n\
00770 float64 weight\n\
00771 \n\
00772 ================================================================================\n\
00773 MSG: motion_planning_msgs/VisibilityConstraint\n\
00774 # This message contains the definition of a visibility constraint.\n\
00775 Header header\n\
00776 \n\
00777 # The point stamped target that needs to be kept within view of the sensor\n\
00778 geometry_msgs/PointStamped target\n\
00779 \n\
00780 # The local pose of the frame in which visibility is to be maintained\n\
00781 # The frame id should represent the robot link to which the sensor is attached\n\
00782 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00783 geometry_msgs/PoseStamped sensor_pose\n\
00784 \n\
00785 # The deviation (in radians) that will be tolerated\n\
00786 # Constraint error will be measured as the solid angle between the \n\
00787 # X axis of the frame defined above and the vector between the origin \n\
00788 # of the frame defined above and the target location\n\
00789 float64 absolute_tolerance\n\
00790 \n\
00791 \n\
00792 ================================================================================\n\
00793 MSG: geometry_msgs/PointStamped\n\
00794 # This represents a Point with reference coordinate frame and timestamp\n\
00795 Header header\n\
00796 Point point\n\
00797 \n\
00798 ";
00799 }
00800
00801 static const char* value(const ::motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> &) { return value(); }
00802 };
00803
00804 }
00805 }
00806
00807
00808 namespace ros
00809 {
00810 namespace message_traits
00811 {
00812 template<class ContainerAllocator>
00813 struct MD5Sum< ::motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> > {
00814 static const char* value()
00815 {
00816 return "d7a8073958b17b9bc926b7fb8d466ac6";
00817 }
00818
00819 static const char* value(const ::motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> &) { return value(); }
00820 static const uint64_t static_value1 = 0xd7a8073958b17b9bULL;
00821 static const uint64_t static_value2 = 0xc926b7fb8d466ac6ULL;
00822 };
00823
00824 template<class ContainerAllocator>
00825 struct DataType< ::motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> > {
00826 static const char* value()
00827 {
00828 return "motion_planning_msgs/ConvertToJointConstraintResponse";
00829 }
00830
00831 static const char* value(const ::motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> &) { return value(); }
00832 };
00833
00834 template<class ContainerAllocator>
00835 struct Definition< ::motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> > {
00836 static const char* value()
00837 {
00838 return "\n\
00839 \n\
00840 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00841 \n\
00842 \n\
00843 ================================================================================\n\
00844 MSG: motion_planning_msgs/JointConstraint\n\
00845 # Constrain the position of a joint to be within a certain bound\n\
00846 string joint_name\n\
00847 \n\
00848 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00849 float64 position\n\
00850 float64 tolerance_above\n\
00851 float64 tolerance_below\n\
00852 \n\
00853 # A weighting factor for this constraint\n\
00854 float64 weight\n\
00855 ";
00856 }
00857
00858 static const char* value(const ::motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> &) { return value(); }
00859 };
00860
00861 }
00862 }
00863
00864 namespace ros
00865 {
00866 namespace serialization
00867 {
00868
00869 template<class ContainerAllocator> struct Serializer< ::motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> >
00870 {
00871 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00872 {
00873 stream.next(m.model_id);
00874 stream.next(m.workspace_parameters);
00875 stream.next(m.start_state);
00876 stream.next(m.joint_names);
00877 stream.next(m.init_states);
00878 stream.next(m.constraints);
00879 stream.next(m.allowed_time);
00880 }
00881
00882 ROS_DECLARE_ALLINONE_SERIALIZER;
00883 };
00884 }
00885 }
00886
00887
00888 namespace ros
00889 {
00890 namespace serialization
00891 {
00892
00893 template<class ContainerAllocator> struct Serializer< ::motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> >
00894 {
00895 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00896 {
00897 stream.next(m.joint_constraints);
00898 }
00899
00900 ROS_DECLARE_ALLINONE_SERIALIZER;
00901 };
00902 }
00903 }
00904
00905 namespace ros
00906 {
00907 namespace service_traits
00908 {
00909 template<>
00910 struct MD5Sum<motion_planning_msgs::ConvertToJointConstraint> {
00911 static const char* value()
00912 {
00913 return "44f1f1ccbb08264490b769e8b8b79668";
00914 }
00915
00916 static const char* value(const motion_planning_msgs::ConvertToJointConstraint&) { return value(); }
00917 };
00918
00919 template<>
00920 struct DataType<motion_planning_msgs::ConvertToJointConstraint> {
00921 static const char* value()
00922 {
00923 return "motion_planning_msgs/ConvertToJointConstraint";
00924 }
00925
00926 static const char* value(const motion_planning_msgs::ConvertToJointConstraint&) { return value(); }
00927 };
00928
00929 template<class ContainerAllocator>
00930 struct MD5Sum<motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> > {
00931 static const char* value()
00932 {
00933 return "44f1f1ccbb08264490b769e8b8b79668";
00934 }
00935
00936 static const char* value(const motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> &) { return value(); }
00937 };
00938
00939 template<class ContainerAllocator>
00940 struct DataType<motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> > {
00941 static const char* value()
00942 {
00943 return "motion_planning_msgs/ConvertToJointConstraint";
00944 }
00945
00946 static const char* value(const motion_planning_msgs::ConvertToJointConstraintRequest_<ContainerAllocator> &) { return value(); }
00947 };
00948
00949 template<class ContainerAllocator>
00950 struct MD5Sum<motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> > {
00951 static const char* value()
00952 {
00953 return "44f1f1ccbb08264490b769e8b8b79668";
00954 }
00955
00956 static const char* value(const motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> &) { return value(); }
00957 };
00958
00959 template<class ContainerAllocator>
00960 struct DataType<motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> > {
00961 static const char* value()
00962 {
00963 return "motion_planning_msgs/ConvertToJointConstraint";
00964 }
00965
00966 static const char* value(const motion_planning_msgs::ConvertToJointConstraintResponse_<ContainerAllocator> &) { return value(); }
00967 };
00968
00969 }
00970 }
00971
00972 #endif // MOTION_PLANNING_MSGS_SERVICE_CONVERTTOJOINTCONSTRAINT_H
00973