00001
00002 #ifndef PLANNING_ENVIRONMENT_MSGS_SERVICE_GETJOINTTRAJECTORYVALIDITY_H
00003 #define PLANNING_ENVIRONMENT_MSGS_SERVICE_GETJOINTTRAJECTORYVALIDITY_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 "trajectory_msgs/JointTrajectory.h"
00016 #include "motion_planning_msgs/RobotState.h"
00017 #include "motion_planning_msgs/OrderedCollisionOperations.h"
00018 #include "motion_planning_msgs/AllowedContactSpecification.h"
00019 #include "motion_planning_msgs/Constraints.h"
00020 #include "motion_planning_msgs/Constraints.h"
00021 #include "motion_planning_msgs/LinkPadding.h"
00022
00023
00024 #include "motion_planning_msgs/ArmNavigationErrorCodes.h"
00025 #include "motion_planning_msgs/ArmNavigationErrorCodes.h"
00026 #include "planning_environment_msgs/ContactInformation.h"
00027
00028 namespace planning_environment_msgs
00029 {
00030 template <class ContainerAllocator>
00031 struct GetJointTrajectoryValidityRequest_ : public ros::Message
00032 {
00033 typedef GetJointTrajectoryValidityRequest_<ContainerAllocator> Type;
00034
00035 GetJointTrajectoryValidityRequest_()
00036 : trajectory()
00037 , robot_state()
00038 , check_collisions(false)
00039 , check_path_constraints(false)
00040 , check_goal_constraints(false)
00041 , check_joint_limits(false)
00042 , check_full_trajectory(false)
00043 , ordered_collision_operations()
00044 , allowed_contacts()
00045 , path_constraints()
00046 , goal_constraints()
00047 , link_padding()
00048 {
00049 }
00050
00051 GetJointTrajectoryValidityRequest_(const ContainerAllocator& _alloc)
00052 : trajectory(_alloc)
00053 , robot_state(_alloc)
00054 , check_collisions(false)
00055 , check_path_constraints(false)
00056 , check_goal_constraints(false)
00057 , check_joint_limits(false)
00058 , check_full_trajectory(false)
00059 , ordered_collision_operations(_alloc)
00060 , allowed_contacts(_alloc)
00061 , path_constraints(_alloc)
00062 , goal_constraints(_alloc)
00063 , link_padding(_alloc)
00064 {
00065 }
00066
00067 typedef ::trajectory_msgs::JointTrajectory_<ContainerAllocator> _trajectory_type;
00068 ::trajectory_msgs::JointTrajectory_<ContainerAllocator> trajectory;
00069
00070 typedef ::motion_planning_msgs::RobotState_<ContainerAllocator> _robot_state_type;
00071 ::motion_planning_msgs::RobotState_<ContainerAllocator> robot_state;
00072
00073 typedef uint8_t _check_collisions_type;
00074 uint8_t check_collisions;
00075
00076 typedef uint8_t _check_path_constraints_type;
00077 uint8_t check_path_constraints;
00078
00079 typedef uint8_t _check_goal_constraints_type;
00080 uint8_t check_goal_constraints;
00081
00082 typedef uint8_t _check_joint_limits_type;
00083 uint8_t check_joint_limits;
00084
00085 typedef uint8_t _check_full_trajectory_type;
00086 uint8_t check_full_trajectory;
00087
00088 typedef ::motion_planning_msgs::OrderedCollisionOperations_<ContainerAllocator> _ordered_collision_operations_type;
00089 ::motion_planning_msgs::OrderedCollisionOperations_<ContainerAllocator> ordered_collision_operations;
00090
00091 typedef std::vector< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> >::other > _allowed_contacts_type;
00092 std::vector< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> >::other > allowed_contacts;
00093
00094 typedef ::motion_planning_msgs::Constraints_<ContainerAllocator> _path_constraints_type;
00095 ::motion_planning_msgs::Constraints_<ContainerAllocator> path_constraints;
00096
00097 typedef ::motion_planning_msgs::Constraints_<ContainerAllocator> _goal_constraints_type;
00098 ::motion_planning_msgs::Constraints_<ContainerAllocator> goal_constraints;
00099
00100 typedef std::vector< ::motion_planning_msgs::LinkPadding_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::LinkPadding_<ContainerAllocator> >::other > _link_padding_type;
00101 std::vector< ::motion_planning_msgs::LinkPadding_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::LinkPadding_<ContainerAllocator> >::other > link_padding;
00102
00103
00104 ROS_DEPRECATED uint32_t get_allowed_contacts_size() const { return (uint32_t)allowed_contacts.size(); }
00105 ROS_DEPRECATED void set_allowed_contacts_size(uint32_t size) { allowed_contacts.resize((size_t)size); }
00106 ROS_DEPRECATED void get_allowed_contacts_vec(std::vector< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> >::other > & vec) const { vec = this->allowed_contacts; }
00107 ROS_DEPRECATED void set_allowed_contacts_vec(const std::vector< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> >::other > & vec) { this->allowed_contacts = vec; }
00108 ROS_DEPRECATED uint32_t get_link_padding_size() const { return (uint32_t)link_padding.size(); }
00109 ROS_DEPRECATED void set_link_padding_size(uint32_t size) { link_padding.resize((size_t)size); }
00110 ROS_DEPRECATED void get_link_padding_vec(std::vector< ::motion_planning_msgs::LinkPadding_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::LinkPadding_<ContainerAllocator> >::other > & vec) const { vec = this->link_padding; }
00111 ROS_DEPRECATED void set_link_padding_vec(const std::vector< ::motion_planning_msgs::LinkPadding_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::LinkPadding_<ContainerAllocator> >::other > & vec) { this->link_padding = vec; }
00112 private:
00113 static const char* __s_getDataType_() { return "planning_environment_msgs/GetJointTrajectoryValidityRequest"; }
00114 public:
00115 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00116
00117 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00118
00119 private:
00120 static const char* __s_getMD5Sum_() { return "0124ee37717bcb209db4f92b2871a148"; }
00121 public:
00122 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00123
00124 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00125
00126 private:
00127 static const char* __s_getServerMD5Sum_() { return "5149e4523f6ccd435092fd5fc26e2c33"; }
00128 public:
00129 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00130
00131 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00132
00133 private:
00134 static const char* __s_getMessageDefinition_() { return "\n\
00135 trajectory_msgs/JointTrajectory trajectory\n\
00136 \n\
00137 \n\
00138 \n\
00139 \n\
00140 \n\
00141 \n\
00142 \n\
00143 motion_planning_msgs/RobotState robot_state\n\
00144 \n\
00145 \n\
00146 bool check_collisions\n\
00147 \n\
00148 \n\
00149 bool check_path_constraints\n\
00150 \n\
00151 \n\
00152 bool check_goal_constraints\n\
00153 \n\
00154 \n\
00155 bool check_joint_limits\n\
00156 \n\
00157 \n\
00158 \n\
00159 \n\
00160 bool check_full_trajectory\n\
00161 \n\
00162 \n\
00163 \n\
00164 \n\
00165 motion_planning_msgs/OrderedCollisionOperations ordered_collision_operations\n\
00166 \n\
00167 \n\
00168 \n\
00169 motion_planning_msgs/AllowedContactSpecification[] allowed_contacts\n\
00170 \n\
00171 \n\
00172 \n\
00173 \n\
00174 motion_planning_msgs/Constraints path_constraints\n\
00175 \n\
00176 \n\
00177 \n\
00178 \n\
00179 motion_planning_msgs/Constraints goal_constraints\n\
00180 \n\
00181 \n\
00182 \n\
00183 motion_planning_msgs/LinkPadding[] link_padding\n\
00184 \n\
00185 \n\
00186 ================================================================================\n\
00187 MSG: trajectory_msgs/JointTrajectory\n\
00188 Header header\n\
00189 string[] joint_names\n\
00190 JointTrajectoryPoint[] points\n\
00191 ================================================================================\n\
00192 MSG: std_msgs/Header\n\
00193 # Standard metadata for higher-level stamped data types.\n\
00194 # This is generally used to communicate timestamped data \n\
00195 # in a particular coordinate frame.\n\
00196 # \n\
00197 # sequence ID: consecutively increasing ID \n\
00198 uint32 seq\n\
00199 #Two-integer timestamp that is expressed as:\n\
00200 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00201 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00202 # time-handling sugar is provided by the client library\n\
00203 time stamp\n\
00204 #Frame this data is associated with\n\
00205 # 0: no frame\n\
00206 # 1: global frame\n\
00207 string frame_id\n\
00208 \n\
00209 ================================================================================\n\
00210 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00211 float64[] positions\n\
00212 float64[] velocities\n\
00213 float64[] accelerations\n\
00214 duration time_from_start\n\
00215 ================================================================================\n\
00216 MSG: motion_planning_msgs/RobotState\n\
00217 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00218 sensor_msgs/JointState joint_state\n\
00219 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00220 ================================================================================\n\
00221 MSG: sensor_msgs/JointState\n\
00222 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00223 #\n\
00224 # The state of each joint (revolute or prismatic) is defined by:\n\
00225 # * the position of the joint (rad or m),\n\
00226 # * the velocity of the joint (rad/s or m/s) and \n\
00227 # * the effort that is applied in the joint (Nm or N).\n\
00228 #\n\
00229 # Each joint is uniquely identified by its name\n\
00230 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00231 # in one message have to be recorded at the same time.\n\
00232 #\n\
00233 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00234 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00235 # effort associated with them, you can leave the effort array empty. \n\
00236 #\n\
00237 # All arrays in this message should have the same size, or be empty.\n\
00238 # This is the only way to uniquely associate the joint name with the correct\n\
00239 # states.\n\
00240 \n\
00241 \n\
00242 Header header\n\
00243 \n\
00244 string[] name\n\
00245 float64[] position\n\
00246 float64[] velocity\n\
00247 float64[] effort\n\
00248 \n\
00249 ================================================================================\n\
00250 MSG: motion_planning_msgs/MultiDOFJointState\n\
00251 #A representation of a multi-dof joint state\n\
00252 time stamp\n\
00253 string[] joint_names\n\
00254 string[] frame_ids\n\
00255 string[] child_frame_ids\n\
00256 geometry_msgs/Pose[] poses\n\
00257 \n\
00258 ================================================================================\n\
00259 MSG: geometry_msgs/Pose\n\
00260 # A representation of pose in free space, composed of postion and orientation. \n\
00261 Point position\n\
00262 Quaternion orientation\n\
00263 \n\
00264 ================================================================================\n\
00265 MSG: geometry_msgs/Point\n\
00266 # This contains the position of a point in free space\n\
00267 float64 x\n\
00268 float64 y\n\
00269 float64 z\n\
00270 \n\
00271 ================================================================================\n\
00272 MSG: geometry_msgs/Quaternion\n\
00273 # This represents an orientation in free space in quaternion form.\n\
00274 \n\
00275 float64 x\n\
00276 float64 y\n\
00277 float64 z\n\
00278 float64 w\n\
00279 \n\
00280 ================================================================================\n\
00281 MSG: motion_planning_msgs/OrderedCollisionOperations\n\
00282 # A set of collision operations that will be performed in the order they are specified\n\
00283 CollisionOperation[] collision_operations\n\
00284 ================================================================================\n\
00285 MSG: motion_planning_msgs/CollisionOperation\n\
00286 # A definition of a collision operation\n\
00287 # E.g. (\"gripper\",COLLISION_SET_ALL,ENABLE) will enable collisions \n\
00288 # between the gripper and all objects in the collision space\n\
00289 \n\
00290 string object1\n\
00291 string object2\n\
00292 string COLLISION_SET_ALL=\"all\"\n\
00293 string COLLISION_SET_OBJECTS=\"objects\"\n\
00294 string COLLISION_SET_ATTACHED_OBJECTS=\"attached\"\n\
00295 \n\
00296 # The penetration distance to which collisions are allowed. This is 0.0 by default.\n\
00297 float64 penetration_distance\n\
00298 \n\
00299 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above\n\
00300 int32 operation\n\
00301 int32 DISABLE=0\n\
00302 int32 ENABLE=1\n\
00303 \n\
00304 ================================================================================\n\
00305 MSG: motion_planning_msgs/AllowedContactSpecification\n\
00306 # The names of the regions\n\
00307 string name\n\
00308 \n\
00309 # The shape of the region in the environment\n\
00310 geometric_shapes_msgs/Shape shape\n\
00311 \n\
00312 # The pose of the space defining the region\n\
00313 geometry_msgs/PoseStamped pose_stamped\n\
00314 \n\
00315 # The set of links that will be allowed to have penetration contact within this region\n\
00316 string[] link_names\n\
00317 \n\
00318 # The maximum penetration depth allowed for every link\n\
00319 float64 penetration_depth\n\
00320 ================================================================================\n\
00321 MSG: geometric_shapes_msgs/Shape\n\
00322 byte SPHERE=0\n\
00323 byte BOX=1\n\
00324 byte CYLINDER=2\n\
00325 byte MESH=3\n\
00326 \n\
00327 byte type\n\
00328 \n\
00329 \n\
00330 #### define sphere, box, cylinder ####\n\
00331 # the origin of each shape is considered at the shape's center\n\
00332 \n\
00333 # for sphere\n\
00334 # radius := dimensions[0]\n\
00335 \n\
00336 # for cylinder\n\
00337 # radius := dimensions[0]\n\
00338 # length := dimensions[1]\n\
00339 # the length is along the Z axis\n\
00340 \n\
00341 # for box\n\
00342 # size_x := dimensions[0]\n\
00343 # size_y := dimensions[1]\n\
00344 # size_z := dimensions[2]\n\
00345 float64[] dimensions\n\
00346 \n\
00347 \n\
00348 #### define mesh ####\n\
00349 \n\
00350 # list of triangles; triangle k is defined by tre vertices located\n\
00351 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00352 int32[] triangles\n\
00353 geometry_msgs/Point[] vertices\n\
00354 \n\
00355 ================================================================================\n\
00356 MSG: geometry_msgs/PoseStamped\n\
00357 # A Pose with reference coordinate frame and timestamp\n\
00358 Header header\n\
00359 Pose pose\n\
00360 \n\
00361 ================================================================================\n\
00362 MSG: motion_planning_msgs/Constraints\n\
00363 # This message contains a list of motion planning constraints.\n\
00364 \n\
00365 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00366 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00367 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00368 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00369 \n\
00370 ================================================================================\n\
00371 MSG: motion_planning_msgs/JointConstraint\n\
00372 # Constrain the position of a joint to be within a certain bound\n\
00373 string joint_name\n\
00374 \n\
00375 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00376 float64 position\n\
00377 float64 tolerance_above\n\
00378 float64 tolerance_below\n\
00379 \n\
00380 # A weighting factor for this constraint\n\
00381 float64 weight\n\
00382 ================================================================================\n\
00383 MSG: motion_planning_msgs/PositionConstraint\n\
00384 # This message contains the definition of a position constraint.\n\
00385 Header header\n\
00386 \n\
00387 # The robot link this constraint refers to\n\
00388 string link_name\n\
00389 \n\
00390 # The offset (in the link frame) for the target point on the link we are planning for\n\
00391 geometry_msgs/Point target_point_offset\n\
00392 \n\
00393 # The nominal/target position for the point we are planning for\n\
00394 geometry_msgs/Point position\n\
00395 \n\
00396 # The shape of the bounded region that constrains the position of the end-effector\n\
00397 # This region is always centered at the position defined above\n\
00398 geometric_shapes_msgs/Shape constraint_region_shape\n\
00399 \n\
00400 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00401 # This allows the specification of non-axis aligned constraints\n\
00402 geometry_msgs/Quaternion constraint_region_orientation\n\
00403 \n\
00404 # Constraint weighting factor - a weight for this constraint\n\
00405 float64 weight\n\
00406 ================================================================================\n\
00407 MSG: motion_planning_msgs/OrientationConstraint\n\
00408 # This message contains the definition of an orientation constraint.\n\
00409 Header header\n\
00410 \n\
00411 # The robot link this constraint refers to\n\
00412 string link_name\n\
00413 \n\
00414 # The type of the constraint\n\
00415 int32 type\n\
00416 int32 LINK_FRAME=0\n\
00417 int32 HEADER_FRAME=1\n\
00418 \n\
00419 # The desired orientation of the robot link specified as a quaternion\n\
00420 geometry_msgs/Quaternion orientation\n\
00421 \n\
00422 # optional RPY error tolerances specified if \n\
00423 float64 absolute_roll_tolerance\n\
00424 float64 absolute_pitch_tolerance\n\
00425 float64 absolute_yaw_tolerance\n\
00426 \n\
00427 # Constraint weighting factor - a weight for this constraint\n\
00428 float64 weight\n\
00429 \n\
00430 ================================================================================\n\
00431 MSG: motion_planning_msgs/VisibilityConstraint\n\
00432 # This message contains the definition of a visibility constraint.\n\
00433 Header header\n\
00434 \n\
00435 # The point stamped target that needs to be kept within view of the sensor\n\
00436 geometry_msgs/PointStamped target\n\
00437 \n\
00438 # The local pose of the frame in which visibility is to be maintained\n\
00439 # The frame id should represent the robot link to which the sensor is attached\n\
00440 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00441 geometry_msgs/PoseStamped sensor_pose\n\
00442 \n\
00443 # The deviation (in radians) that will be tolerated\n\
00444 # Constraint error will be measured as the solid angle between the \n\
00445 # X axis of the frame defined above and the vector between the origin \n\
00446 # of the frame defined above and the target location\n\
00447 float64 absolute_tolerance\n\
00448 \n\
00449 \n\
00450 ================================================================================\n\
00451 MSG: geometry_msgs/PointStamped\n\
00452 # This represents a Point with reference coordinate frame and timestamp\n\
00453 Header header\n\
00454 Point point\n\
00455 \n\
00456 ================================================================================\n\
00457 MSG: motion_planning_msgs/LinkPadding\n\
00458 #name for the link\n\
00459 string link_name\n\
00460 \n\
00461 # padding to apply to the link\n\
00462 float64 padding\n\
00463 \n\
00464 "; }
00465 public:
00466 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00467
00468 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00469
00470 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00471 {
00472 ros::serialization::OStream stream(write_ptr, 1000000000);
00473 ros::serialization::serialize(stream, trajectory);
00474 ros::serialization::serialize(stream, robot_state);
00475 ros::serialization::serialize(stream, check_collisions);
00476 ros::serialization::serialize(stream, check_path_constraints);
00477 ros::serialization::serialize(stream, check_goal_constraints);
00478 ros::serialization::serialize(stream, check_joint_limits);
00479 ros::serialization::serialize(stream, check_full_trajectory);
00480 ros::serialization::serialize(stream, ordered_collision_operations);
00481 ros::serialization::serialize(stream, allowed_contacts);
00482 ros::serialization::serialize(stream, path_constraints);
00483 ros::serialization::serialize(stream, goal_constraints);
00484 ros::serialization::serialize(stream, link_padding);
00485 return stream.getData();
00486 }
00487
00488 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00489 {
00490 ros::serialization::IStream stream(read_ptr, 1000000000);
00491 ros::serialization::deserialize(stream, trajectory);
00492 ros::serialization::deserialize(stream, robot_state);
00493 ros::serialization::deserialize(stream, check_collisions);
00494 ros::serialization::deserialize(stream, check_path_constraints);
00495 ros::serialization::deserialize(stream, check_goal_constraints);
00496 ros::serialization::deserialize(stream, check_joint_limits);
00497 ros::serialization::deserialize(stream, check_full_trajectory);
00498 ros::serialization::deserialize(stream, ordered_collision_operations);
00499 ros::serialization::deserialize(stream, allowed_contacts);
00500 ros::serialization::deserialize(stream, path_constraints);
00501 ros::serialization::deserialize(stream, goal_constraints);
00502 ros::serialization::deserialize(stream, link_padding);
00503 return stream.getData();
00504 }
00505
00506 ROS_DEPRECATED virtual uint32_t serializationLength() const
00507 {
00508 uint32_t size = 0;
00509 size += ros::serialization::serializationLength(trajectory);
00510 size += ros::serialization::serializationLength(robot_state);
00511 size += ros::serialization::serializationLength(check_collisions);
00512 size += ros::serialization::serializationLength(check_path_constraints);
00513 size += ros::serialization::serializationLength(check_goal_constraints);
00514 size += ros::serialization::serializationLength(check_joint_limits);
00515 size += ros::serialization::serializationLength(check_full_trajectory);
00516 size += ros::serialization::serializationLength(ordered_collision_operations);
00517 size += ros::serialization::serializationLength(allowed_contacts);
00518 size += ros::serialization::serializationLength(path_constraints);
00519 size += ros::serialization::serializationLength(goal_constraints);
00520 size += ros::serialization::serializationLength(link_padding);
00521 return size;
00522 }
00523
00524 typedef boost::shared_ptr< ::planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> > Ptr;
00525 typedef boost::shared_ptr< ::planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> const> ConstPtr;
00526 };
00527 typedef ::planning_environment_msgs::GetJointTrajectoryValidityRequest_<std::allocator<void> > GetJointTrajectoryValidityRequest;
00528
00529 typedef boost::shared_ptr< ::planning_environment_msgs::GetJointTrajectoryValidityRequest> GetJointTrajectoryValidityRequestPtr;
00530 typedef boost::shared_ptr< ::planning_environment_msgs::GetJointTrajectoryValidityRequest const> GetJointTrajectoryValidityRequestConstPtr;
00531
00532
00533 template <class ContainerAllocator>
00534 struct GetJointTrajectoryValidityResponse_ : public ros::Message
00535 {
00536 typedef GetJointTrajectoryValidityResponse_<ContainerAllocator> Type;
00537
00538 GetJointTrajectoryValidityResponse_()
00539 : error_code()
00540 , trajectory_error_codes()
00541 , contacts()
00542 {
00543 }
00544
00545 GetJointTrajectoryValidityResponse_(const ContainerAllocator& _alloc)
00546 : error_code(_alloc)
00547 , trajectory_error_codes(_alloc)
00548 , contacts(_alloc)
00549 {
00550 }
00551
00552 typedef ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> _error_code_type;
00553 ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> error_code;
00554
00555 typedef std::vector< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> >::other > _trajectory_error_codes_type;
00556 std::vector< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> >::other > trajectory_error_codes;
00557
00558 typedef std::vector< ::planning_environment_msgs::ContactInformation_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::planning_environment_msgs::ContactInformation_<ContainerAllocator> >::other > _contacts_type;
00559 std::vector< ::planning_environment_msgs::ContactInformation_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::planning_environment_msgs::ContactInformation_<ContainerAllocator> >::other > contacts;
00560
00561
00562 ROS_DEPRECATED uint32_t get_trajectory_error_codes_size() const { return (uint32_t)trajectory_error_codes.size(); }
00563 ROS_DEPRECATED void set_trajectory_error_codes_size(uint32_t size) { trajectory_error_codes.resize((size_t)size); }
00564 ROS_DEPRECATED void get_trajectory_error_codes_vec(std::vector< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> >::other > & vec) const { vec = this->trajectory_error_codes; }
00565 ROS_DEPRECATED void set_trajectory_error_codes_vec(const std::vector< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> >::other > & vec) { this->trajectory_error_codes = vec; }
00566 ROS_DEPRECATED uint32_t get_contacts_size() const { return (uint32_t)contacts.size(); }
00567 ROS_DEPRECATED void set_contacts_size(uint32_t size) { contacts.resize((size_t)size); }
00568 ROS_DEPRECATED void get_contacts_vec(std::vector< ::planning_environment_msgs::ContactInformation_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::planning_environment_msgs::ContactInformation_<ContainerAllocator> >::other > & vec) const { vec = this->contacts; }
00569 ROS_DEPRECATED void set_contacts_vec(const std::vector< ::planning_environment_msgs::ContactInformation_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::planning_environment_msgs::ContactInformation_<ContainerAllocator> >::other > & vec) { this->contacts = vec; }
00570 private:
00571 static const char* __s_getDataType_() { return "planning_environment_msgs/GetJointTrajectoryValidityResponse"; }
00572 public:
00573 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00574
00575 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00576
00577 private:
00578 static const char* __s_getMD5Sum_() { return "a739823e2969bedb7e3343a4d8c097d4"; }
00579 public:
00580 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00581
00582 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00583
00584 private:
00585 static const char* __s_getServerMD5Sum_() { return "5149e4523f6ccd435092fd5fc26e2c33"; }
00586 public:
00587 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00588
00589 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00590
00591 private:
00592 static const char* __s_getMessageDefinition_() { return "\n\
00593 \n\
00594 \n\
00595 \n\
00596 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
00597 \n\
00598 \n\
00599 \n\
00600 \n\
00601 motion_planning_msgs/ArmNavigationErrorCodes[] trajectory_error_codes\n\
00602 \n\
00603 planning_environment_msgs/ContactInformation[] contacts\n\
00604 \n\
00605 \n\
00606 ================================================================================\n\
00607 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00608 int32 val\n\
00609 \n\
00610 # overall behavior\n\
00611 int32 PLANNING_FAILED=-1\n\
00612 int32 SUCCESS=1\n\
00613 int32 TIMED_OUT=-2\n\
00614 \n\
00615 # start state errors\n\
00616 int32 START_STATE_IN_COLLISION=-3\n\
00617 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00618 \n\
00619 # goal errors\n\
00620 int32 GOAL_IN_COLLISION=-5\n\
00621 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00622 \n\
00623 # robot state\n\
00624 int32 INVALID_ROBOT_STATE=-7\n\
00625 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00626 \n\
00627 # planning request errors\n\
00628 int32 INVALID_PLANNER_ID=-9\n\
00629 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00630 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00631 int32 INVALID_GROUP_NAME=-12\n\
00632 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00633 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00634 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00635 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00636 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00637 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00638 \n\
00639 # state/trajectory monitor errors\n\
00640 int32 INVALID_TRAJECTORY=-19\n\
00641 int32 INVALID_INDEX=-20\n\
00642 int32 JOINT_LIMITS_VIOLATED=-21\n\
00643 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00644 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00645 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00646 int32 JOINTS_NOT_MOVING=-25\n\
00647 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00648 \n\
00649 # system errors\n\
00650 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00651 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00652 int32 ROBOT_STATE_STALE=-29\n\
00653 int32 SENSOR_INFO_STALE=-30\n\
00654 \n\
00655 # kinematics errors\n\
00656 int32 NO_IK_SOLUTION=-31\n\
00657 int32 INVALID_LINK_NAME=-32\n\
00658 int32 IK_LINK_IN_COLLISION=-33\n\
00659 int32 NO_FK_SOLUTION=-34\n\
00660 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00661 \n\
00662 # general errors\n\
00663 int32 INVALID_TIMEOUT=-36\n\
00664 \n\
00665 \n\
00666 ================================================================================\n\
00667 MSG: planning_environment_msgs/ContactInformation\n\
00668 # Standard ROS header contains information \n\
00669 # about the frame in which this \n\
00670 # contact is specified\n\
00671 Header header\n\
00672 \n\
00673 # Position of the contact point\n\
00674 geometry_msgs/Point position\n\
00675 \n\
00676 # Normal corresponding to the contact point\n\
00677 geometry_msgs/Vector3 normal \n\
00678 \n\
00679 # Depth of contact point\n\
00680 float64 depth\n\
00681 \n\
00682 # Name of the first body that is in contact\n\
00683 # This could be a link or a namespace that represents a body\n\
00684 string contact_body_1\n\
00685 string attached_body_1\n\
00686 uint32 body_type_1\n\
00687 \n\
00688 # Name of the second body that is in contact\n\
00689 # This could be a link or a namespace that represents a body\n\
00690 string contact_body_2\n\
00691 string attached_body_2\n\
00692 uint32 body_type_2\n\
00693 \n\
00694 uint32 ROBOT_LINK=0\n\
00695 uint32 OBJECT=1\n\
00696 uint32 ATTACHED_BODY=2\n\
00697 ================================================================================\n\
00698 MSG: std_msgs/Header\n\
00699 # Standard metadata for higher-level stamped data types.\n\
00700 # This is generally used to communicate timestamped data \n\
00701 # in a particular coordinate frame.\n\
00702 # \n\
00703 # sequence ID: consecutively increasing ID \n\
00704 uint32 seq\n\
00705 #Two-integer timestamp that is expressed as:\n\
00706 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00707 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00708 # time-handling sugar is provided by the client library\n\
00709 time stamp\n\
00710 #Frame this data is associated with\n\
00711 # 0: no frame\n\
00712 # 1: global frame\n\
00713 string frame_id\n\
00714 \n\
00715 ================================================================================\n\
00716 MSG: geometry_msgs/Point\n\
00717 # This contains the position of a point in free space\n\
00718 float64 x\n\
00719 float64 y\n\
00720 float64 z\n\
00721 \n\
00722 ================================================================================\n\
00723 MSG: geometry_msgs/Vector3\n\
00724 # This represents a vector in free space. \n\
00725 \n\
00726 float64 x\n\
00727 float64 y\n\
00728 float64 z\n\
00729 "; }
00730 public:
00731 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00732
00733 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00734
00735 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00736 {
00737 ros::serialization::OStream stream(write_ptr, 1000000000);
00738 ros::serialization::serialize(stream, error_code);
00739 ros::serialization::serialize(stream, trajectory_error_codes);
00740 ros::serialization::serialize(stream, contacts);
00741 return stream.getData();
00742 }
00743
00744 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00745 {
00746 ros::serialization::IStream stream(read_ptr, 1000000000);
00747 ros::serialization::deserialize(stream, error_code);
00748 ros::serialization::deserialize(stream, trajectory_error_codes);
00749 ros::serialization::deserialize(stream, contacts);
00750 return stream.getData();
00751 }
00752
00753 ROS_DEPRECATED virtual uint32_t serializationLength() const
00754 {
00755 uint32_t size = 0;
00756 size += ros::serialization::serializationLength(error_code);
00757 size += ros::serialization::serializationLength(trajectory_error_codes);
00758 size += ros::serialization::serializationLength(contacts);
00759 return size;
00760 }
00761
00762 typedef boost::shared_ptr< ::planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> > Ptr;
00763 typedef boost::shared_ptr< ::planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> const> ConstPtr;
00764 };
00765 typedef ::planning_environment_msgs::GetJointTrajectoryValidityResponse_<std::allocator<void> > GetJointTrajectoryValidityResponse;
00766
00767 typedef boost::shared_ptr< ::planning_environment_msgs::GetJointTrajectoryValidityResponse> GetJointTrajectoryValidityResponsePtr;
00768 typedef boost::shared_ptr< ::planning_environment_msgs::GetJointTrajectoryValidityResponse const> GetJointTrajectoryValidityResponseConstPtr;
00769
00770 struct GetJointTrajectoryValidity
00771 {
00772
00773 typedef GetJointTrajectoryValidityRequest Request;
00774 typedef GetJointTrajectoryValidityResponse Response;
00775 Request request;
00776 Response response;
00777
00778 typedef Request RequestType;
00779 typedef Response ResponseType;
00780 };
00781 }
00782
00783 namespace ros
00784 {
00785 namespace message_traits
00786 {
00787 template<class ContainerAllocator>
00788 struct MD5Sum< ::planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> > {
00789 static const char* value()
00790 {
00791 return "0124ee37717bcb209db4f92b2871a148";
00792 }
00793
00794 static const char* value(const ::planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> &) { return value(); }
00795 static const uint64_t static_value1 = 0x0124ee37717bcb20ULL;
00796 static const uint64_t static_value2 = 0x9db4f92b2871a148ULL;
00797 };
00798
00799 template<class ContainerAllocator>
00800 struct DataType< ::planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> > {
00801 static const char* value()
00802 {
00803 return "planning_environment_msgs/GetJointTrajectoryValidityRequest";
00804 }
00805
00806 static const char* value(const ::planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> &) { return value(); }
00807 };
00808
00809 template<class ContainerAllocator>
00810 struct Definition< ::planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> > {
00811 static const char* value()
00812 {
00813 return "\n\
00814 trajectory_msgs/JointTrajectory trajectory\n\
00815 \n\
00816 \n\
00817 \n\
00818 \n\
00819 \n\
00820 \n\
00821 \n\
00822 motion_planning_msgs/RobotState robot_state\n\
00823 \n\
00824 \n\
00825 bool check_collisions\n\
00826 \n\
00827 \n\
00828 bool check_path_constraints\n\
00829 \n\
00830 \n\
00831 bool check_goal_constraints\n\
00832 \n\
00833 \n\
00834 bool check_joint_limits\n\
00835 \n\
00836 \n\
00837 \n\
00838 \n\
00839 bool check_full_trajectory\n\
00840 \n\
00841 \n\
00842 \n\
00843 \n\
00844 motion_planning_msgs/OrderedCollisionOperations ordered_collision_operations\n\
00845 \n\
00846 \n\
00847 \n\
00848 motion_planning_msgs/AllowedContactSpecification[] allowed_contacts\n\
00849 \n\
00850 \n\
00851 \n\
00852 \n\
00853 motion_planning_msgs/Constraints path_constraints\n\
00854 \n\
00855 \n\
00856 \n\
00857 \n\
00858 motion_planning_msgs/Constraints goal_constraints\n\
00859 \n\
00860 \n\
00861 \n\
00862 motion_planning_msgs/LinkPadding[] link_padding\n\
00863 \n\
00864 \n\
00865 ================================================================================\n\
00866 MSG: trajectory_msgs/JointTrajectory\n\
00867 Header header\n\
00868 string[] joint_names\n\
00869 JointTrajectoryPoint[] points\n\
00870 ================================================================================\n\
00871 MSG: std_msgs/Header\n\
00872 # Standard metadata for higher-level stamped data types.\n\
00873 # This is generally used to communicate timestamped data \n\
00874 # in a particular coordinate frame.\n\
00875 # \n\
00876 # sequence ID: consecutively increasing ID \n\
00877 uint32 seq\n\
00878 #Two-integer timestamp that is expressed as:\n\
00879 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00880 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00881 # time-handling sugar is provided by the client library\n\
00882 time stamp\n\
00883 #Frame this data is associated with\n\
00884 # 0: no frame\n\
00885 # 1: global frame\n\
00886 string frame_id\n\
00887 \n\
00888 ================================================================================\n\
00889 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00890 float64[] positions\n\
00891 float64[] velocities\n\
00892 float64[] accelerations\n\
00893 duration time_from_start\n\
00894 ================================================================================\n\
00895 MSG: motion_planning_msgs/RobotState\n\
00896 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00897 sensor_msgs/JointState joint_state\n\
00898 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00899 ================================================================================\n\
00900 MSG: sensor_msgs/JointState\n\
00901 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00902 #\n\
00903 # The state of each joint (revolute or prismatic) is defined by:\n\
00904 # * the position of the joint (rad or m),\n\
00905 # * the velocity of the joint (rad/s or m/s) and \n\
00906 # * the effort that is applied in the joint (Nm or N).\n\
00907 #\n\
00908 # Each joint is uniquely identified by its name\n\
00909 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00910 # in one message have to be recorded at the same time.\n\
00911 #\n\
00912 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00913 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00914 # effort associated with them, you can leave the effort array empty. \n\
00915 #\n\
00916 # All arrays in this message should have the same size, or be empty.\n\
00917 # This is the only way to uniquely associate the joint name with the correct\n\
00918 # states.\n\
00919 \n\
00920 \n\
00921 Header header\n\
00922 \n\
00923 string[] name\n\
00924 float64[] position\n\
00925 float64[] velocity\n\
00926 float64[] effort\n\
00927 \n\
00928 ================================================================================\n\
00929 MSG: motion_planning_msgs/MultiDOFJointState\n\
00930 #A representation of a multi-dof joint state\n\
00931 time stamp\n\
00932 string[] joint_names\n\
00933 string[] frame_ids\n\
00934 string[] child_frame_ids\n\
00935 geometry_msgs/Pose[] poses\n\
00936 \n\
00937 ================================================================================\n\
00938 MSG: geometry_msgs/Pose\n\
00939 # A representation of pose in free space, composed of postion and orientation. \n\
00940 Point position\n\
00941 Quaternion orientation\n\
00942 \n\
00943 ================================================================================\n\
00944 MSG: geometry_msgs/Point\n\
00945 # This contains the position of a point in free space\n\
00946 float64 x\n\
00947 float64 y\n\
00948 float64 z\n\
00949 \n\
00950 ================================================================================\n\
00951 MSG: geometry_msgs/Quaternion\n\
00952 # This represents an orientation in free space in quaternion form.\n\
00953 \n\
00954 float64 x\n\
00955 float64 y\n\
00956 float64 z\n\
00957 float64 w\n\
00958 \n\
00959 ================================================================================\n\
00960 MSG: motion_planning_msgs/OrderedCollisionOperations\n\
00961 # A set of collision operations that will be performed in the order they are specified\n\
00962 CollisionOperation[] collision_operations\n\
00963 ================================================================================\n\
00964 MSG: motion_planning_msgs/CollisionOperation\n\
00965 # A definition of a collision operation\n\
00966 # E.g. (\"gripper\",COLLISION_SET_ALL,ENABLE) will enable collisions \n\
00967 # between the gripper and all objects in the collision space\n\
00968 \n\
00969 string object1\n\
00970 string object2\n\
00971 string COLLISION_SET_ALL=\"all\"\n\
00972 string COLLISION_SET_OBJECTS=\"objects\"\n\
00973 string COLLISION_SET_ATTACHED_OBJECTS=\"attached\"\n\
00974 \n\
00975 # The penetration distance to which collisions are allowed. This is 0.0 by default.\n\
00976 float64 penetration_distance\n\
00977 \n\
00978 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above\n\
00979 int32 operation\n\
00980 int32 DISABLE=0\n\
00981 int32 ENABLE=1\n\
00982 \n\
00983 ================================================================================\n\
00984 MSG: motion_planning_msgs/AllowedContactSpecification\n\
00985 # The names of the regions\n\
00986 string name\n\
00987 \n\
00988 # The shape of the region in the environment\n\
00989 geometric_shapes_msgs/Shape shape\n\
00990 \n\
00991 # The pose of the space defining the region\n\
00992 geometry_msgs/PoseStamped pose_stamped\n\
00993 \n\
00994 # The set of links that will be allowed to have penetration contact within this region\n\
00995 string[] link_names\n\
00996 \n\
00997 # The maximum penetration depth allowed for every link\n\
00998 float64 penetration_depth\n\
00999 ================================================================================\n\
01000 MSG: geometric_shapes_msgs/Shape\n\
01001 byte SPHERE=0\n\
01002 byte BOX=1\n\
01003 byte CYLINDER=2\n\
01004 byte MESH=3\n\
01005 \n\
01006 byte type\n\
01007 \n\
01008 \n\
01009 #### define sphere, box, cylinder ####\n\
01010 # the origin of each shape is considered at the shape's center\n\
01011 \n\
01012 # for sphere\n\
01013 # radius := dimensions[0]\n\
01014 \n\
01015 # for cylinder\n\
01016 # radius := dimensions[0]\n\
01017 # length := dimensions[1]\n\
01018 # the length is along the Z axis\n\
01019 \n\
01020 # for box\n\
01021 # size_x := dimensions[0]\n\
01022 # size_y := dimensions[1]\n\
01023 # size_z := dimensions[2]\n\
01024 float64[] dimensions\n\
01025 \n\
01026 \n\
01027 #### define mesh ####\n\
01028 \n\
01029 # list of triangles; triangle k is defined by tre vertices located\n\
01030 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
01031 int32[] triangles\n\
01032 geometry_msgs/Point[] vertices\n\
01033 \n\
01034 ================================================================================\n\
01035 MSG: geometry_msgs/PoseStamped\n\
01036 # A Pose with reference coordinate frame and timestamp\n\
01037 Header header\n\
01038 Pose pose\n\
01039 \n\
01040 ================================================================================\n\
01041 MSG: motion_planning_msgs/Constraints\n\
01042 # This message contains a list of motion planning constraints.\n\
01043 \n\
01044 motion_planning_msgs/JointConstraint[] joint_constraints\n\
01045 motion_planning_msgs/PositionConstraint[] position_constraints\n\
01046 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
01047 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
01048 \n\
01049 ================================================================================\n\
01050 MSG: motion_planning_msgs/JointConstraint\n\
01051 # Constrain the position of a joint to be within a certain bound\n\
01052 string joint_name\n\
01053 \n\
01054 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
01055 float64 position\n\
01056 float64 tolerance_above\n\
01057 float64 tolerance_below\n\
01058 \n\
01059 # A weighting factor for this constraint\n\
01060 float64 weight\n\
01061 ================================================================================\n\
01062 MSG: motion_planning_msgs/PositionConstraint\n\
01063 # This message contains the definition of a position constraint.\n\
01064 Header header\n\
01065 \n\
01066 # The robot link this constraint refers to\n\
01067 string link_name\n\
01068 \n\
01069 # The offset (in the link frame) for the target point on the link we are planning for\n\
01070 geometry_msgs/Point target_point_offset\n\
01071 \n\
01072 # The nominal/target position for the point we are planning for\n\
01073 geometry_msgs/Point position\n\
01074 \n\
01075 # The shape of the bounded region that constrains the position of the end-effector\n\
01076 # This region is always centered at the position defined above\n\
01077 geometric_shapes_msgs/Shape constraint_region_shape\n\
01078 \n\
01079 # The orientation of the bounded region that constrains the position of the end-effector. \n\
01080 # This allows the specification of non-axis aligned constraints\n\
01081 geometry_msgs/Quaternion constraint_region_orientation\n\
01082 \n\
01083 # Constraint weighting factor - a weight for this constraint\n\
01084 float64 weight\n\
01085 ================================================================================\n\
01086 MSG: motion_planning_msgs/OrientationConstraint\n\
01087 # This message contains the definition of an orientation constraint.\n\
01088 Header header\n\
01089 \n\
01090 # The robot link this constraint refers to\n\
01091 string link_name\n\
01092 \n\
01093 # The type of the constraint\n\
01094 int32 type\n\
01095 int32 LINK_FRAME=0\n\
01096 int32 HEADER_FRAME=1\n\
01097 \n\
01098 # The desired orientation of the robot link specified as a quaternion\n\
01099 geometry_msgs/Quaternion orientation\n\
01100 \n\
01101 # optional RPY error tolerances specified if \n\
01102 float64 absolute_roll_tolerance\n\
01103 float64 absolute_pitch_tolerance\n\
01104 float64 absolute_yaw_tolerance\n\
01105 \n\
01106 # Constraint weighting factor - a weight for this constraint\n\
01107 float64 weight\n\
01108 \n\
01109 ================================================================================\n\
01110 MSG: motion_planning_msgs/VisibilityConstraint\n\
01111 # This message contains the definition of a visibility constraint.\n\
01112 Header header\n\
01113 \n\
01114 # The point stamped target that needs to be kept within view of the sensor\n\
01115 geometry_msgs/PointStamped target\n\
01116 \n\
01117 # The local pose of the frame in which visibility is to be maintained\n\
01118 # The frame id should represent the robot link to which the sensor is attached\n\
01119 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
01120 geometry_msgs/PoseStamped sensor_pose\n\
01121 \n\
01122 # The deviation (in radians) that will be tolerated\n\
01123 # Constraint error will be measured as the solid angle between the \n\
01124 # X axis of the frame defined above and the vector between the origin \n\
01125 # of the frame defined above and the target location\n\
01126 float64 absolute_tolerance\n\
01127 \n\
01128 \n\
01129 ================================================================================\n\
01130 MSG: geometry_msgs/PointStamped\n\
01131 # This represents a Point with reference coordinate frame and timestamp\n\
01132 Header header\n\
01133 Point point\n\
01134 \n\
01135 ================================================================================\n\
01136 MSG: motion_planning_msgs/LinkPadding\n\
01137 #name for the link\n\
01138 string link_name\n\
01139 \n\
01140 # padding to apply to the link\n\
01141 float64 padding\n\
01142 \n\
01143 ";
01144 }
01145
01146 static const char* value(const ::planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> &) { return value(); }
01147 };
01148
01149 }
01150 }
01151
01152
01153 namespace ros
01154 {
01155 namespace message_traits
01156 {
01157 template<class ContainerAllocator>
01158 struct MD5Sum< ::planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> > {
01159 static const char* value()
01160 {
01161 return "a739823e2969bedb7e3343a4d8c097d4";
01162 }
01163
01164 static const char* value(const ::planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> &) { return value(); }
01165 static const uint64_t static_value1 = 0xa739823e2969bedbULL;
01166 static const uint64_t static_value2 = 0x7e3343a4d8c097d4ULL;
01167 };
01168
01169 template<class ContainerAllocator>
01170 struct DataType< ::planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> > {
01171 static const char* value()
01172 {
01173 return "planning_environment_msgs/GetJointTrajectoryValidityResponse";
01174 }
01175
01176 static const char* value(const ::planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> &) { return value(); }
01177 };
01178
01179 template<class ContainerAllocator>
01180 struct Definition< ::planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> > {
01181 static const char* value()
01182 {
01183 return "\n\
01184 \n\
01185 \n\
01186 \n\
01187 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
01188 \n\
01189 \n\
01190 \n\
01191 \n\
01192 motion_planning_msgs/ArmNavigationErrorCodes[] trajectory_error_codes\n\
01193 \n\
01194 planning_environment_msgs/ContactInformation[] contacts\n\
01195 \n\
01196 \n\
01197 ================================================================================\n\
01198 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
01199 int32 val\n\
01200 \n\
01201 # overall behavior\n\
01202 int32 PLANNING_FAILED=-1\n\
01203 int32 SUCCESS=1\n\
01204 int32 TIMED_OUT=-2\n\
01205 \n\
01206 # start state errors\n\
01207 int32 START_STATE_IN_COLLISION=-3\n\
01208 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
01209 \n\
01210 # goal errors\n\
01211 int32 GOAL_IN_COLLISION=-5\n\
01212 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
01213 \n\
01214 # robot state\n\
01215 int32 INVALID_ROBOT_STATE=-7\n\
01216 int32 INCOMPLETE_ROBOT_STATE=-8\n\
01217 \n\
01218 # planning request errors\n\
01219 int32 INVALID_PLANNER_ID=-9\n\
01220 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
01221 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
01222 int32 INVALID_GROUP_NAME=-12\n\
01223 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
01224 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
01225 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
01226 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
01227 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
01228 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
01229 \n\
01230 # state/trajectory monitor errors\n\
01231 int32 INVALID_TRAJECTORY=-19\n\
01232 int32 INVALID_INDEX=-20\n\
01233 int32 JOINT_LIMITS_VIOLATED=-21\n\
01234 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
01235 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
01236 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
01237 int32 JOINTS_NOT_MOVING=-25\n\
01238 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
01239 \n\
01240 # system errors\n\
01241 int32 FRAME_TRANSFORM_FAILURE=-27\n\
01242 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
01243 int32 ROBOT_STATE_STALE=-29\n\
01244 int32 SENSOR_INFO_STALE=-30\n\
01245 \n\
01246 # kinematics errors\n\
01247 int32 NO_IK_SOLUTION=-31\n\
01248 int32 INVALID_LINK_NAME=-32\n\
01249 int32 IK_LINK_IN_COLLISION=-33\n\
01250 int32 NO_FK_SOLUTION=-34\n\
01251 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
01252 \n\
01253 # general errors\n\
01254 int32 INVALID_TIMEOUT=-36\n\
01255 \n\
01256 \n\
01257 ================================================================================\n\
01258 MSG: planning_environment_msgs/ContactInformation\n\
01259 # Standard ROS header contains information \n\
01260 # about the frame in which this \n\
01261 # contact is specified\n\
01262 Header header\n\
01263 \n\
01264 # Position of the contact point\n\
01265 geometry_msgs/Point position\n\
01266 \n\
01267 # Normal corresponding to the contact point\n\
01268 geometry_msgs/Vector3 normal \n\
01269 \n\
01270 # Depth of contact point\n\
01271 float64 depth\n\
01272 \n\
01273 # Name of the first body that is in contact\n\
01274 # This could be a link or a namespace that represents a body\n\
01275 string contact_body_1\n\
01276 string attached_body_1\n\
01277 uint32 body_type_1\n\
01278 \n\
01279 # Name of the second body that is in contact\n\
01280 # This could be a link or a namespace that represents a body\n\
01281 string contact_body_2\n\
01282 string attached_body_2\n\
01283 uint32 body_type_2\n\
01284 \n\
01285 uint32 ROBOT_LINK=0\n\
01286 uint32 OBJECT=1\n\
01287 uint32 ATTACHED_BODY=2\n\
01288 ================================================================================\n\
01289 MSG: std_msgs/Header\n\
01290 # Standard metadata for higher-level stamped data types.\n\
01291 # This is generally used to communicate timestamped data \n\
01292 # in a particular coordinate frame.\n\
01293 # \n\
01294 # sequence ID: consecutively increasing ID \n\
01295 uint32 seq\n\
01296 #Two-integer timestamp that is expressed as:\n\
01297 # * stamp.secs: seconds (stamp_secs) since epoch\n\
01298 # * stamp.nsecs: nanoseconds since stamp_secs\n\
01299 # time-handling sugar is provided by the client library\n\
01300 time stamp\n\
01301 #Frame this data is associated with\n\
01302 # 0: no frame\n\
01303 # 1: global frame\n\
01304 string frame_id\n\
01305 \n\
01306 ================================================================================\n\
01307 MSG: geometry_msgs/Point\n\
01308 # This contains the position of a point in free space\n\
01309 float64 x\n\
01310 float64 y\n\
01311 float64 z\n\
01312 \n\
01313 ================================================================================\n\
01314 MSG: geometry_msgs/Vector3\n\
01315 # This represents a vector in free space. \n\
01316 \n\
01317 float64 x\n\
01318 float64 y\n\
01319 float64 z\n\
01320 ";
01321 }
01322
01323 static const char* value(const ::planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> &) { return value(); }
01324 };
01325
01326 }
01327 }
01328
01329 namespace ros
01330 {
01331 namespace serialization
01332 {
01333
01334 template<class ContainerAllocator> struct Serializer< ::planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> >
01335 {
01336 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01337 {
01338 stream.next(m.trajectory);
01339 stream.next(m.robot_state);
01340 stream.next(m.check_collisions);
01341 stream.next(m.check_path_constraints);
01342 stream.next(m.check_goal_constraints);
01343 stream.next(m.check_joint_limits);
01344 stream.next(m.check_full_trajectory);
01345 stream.next(m.ordered_collision_operations);
01346 stream.next(m.allowed_contacts);
01347 stream.next(m.path_constraints);
01348 stream.next(m.goal_constraints);
01349 stream.next(m.link_padding);
01350 }
01351
01352 ROS_DECLARE_ALLINONE_SERIALIZER;
01353 };
01354 }
01355 }
01356
01357
01358 namespace ros
01359 {
01360 namespace serialization
01361 {
01362
01363 template<class ContainerAllocator> struct Serializer< ::planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> >
01364 {
01365 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01366 {
01367 stream.next(m.error_code);
01368 stream.next(m.trajectory_error_codes);
01369 stream.next(m.contacts);
01370 }
01371
01372 ROS_DECLARE_ALLINONE_SERIALIZER;
01373 };
01374 }
01375 }
01376
01377 namespace ros
01378 {
01379 namespace service_traits
01380 {
01381 template<>
01382 struct MD5Sum<planning_environment_msgs::GetJointTrajectoryValidity> {
01383 static const char* value()
01384 {
01385 return "5149e4523f6ccd435092fd5fc26e2c33";
01386 }
01387
01388 static const char* value(const planning_environment_msgs::GetJointTrajectoryValidity&) { return value(); }
01389 };
01390
01391 template<>
01392 struct DataType<planning_environment_msgs::GetJointTrajectoryValidity> {
01393 static const char* value()
01394 {
01395 return "planning_environment_msgs/GetJointTrajectoryValidity";
01396 }
01397
01398 static const char* value(const planning_environment_msgs::GetJointTrajectoryValidity&) { return value(); }
01399 };
01400
01401 template<class ContainerAllocator>
01402 struct MD5Sum<planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> > {
01403 static const char* value()
01404 {
01405 return "5149e4523f6ccd435092fd5fc26e2c33";
01406 }
01407
01408 static const char* value(const planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> &) { return value(); }
01409 };
01410
01411 template<class ContainerAllocator>
01412 struct DataType<planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> > {
01413 static const char* value()
01414 {
01415 return "planning_environment_msgs/GetJointTrajectoryValidity";
01416 }
01417
01418 static const char* value(const planning_environment_msgs::GetJointTrajectoryValidityRequest_<ContainerAllocator> &) { return value(); }
01419 };
01420
01421 template<class ContainerAllocator>
01422 struct MD5Sum<planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> > {
01423 static const char* value()
01424 {
01425 return "5149e4523f6ccd435092fd5fc26e2c33";
01426 }
01427
01428 static const char* value(const planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> &) { return value(); }
01429 };
01430
01431 template<class ContainerAllocator>
01432 struct DataType<planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> > {
01433 static const char* value()
01434 {
01435 return "planning_environment_msgs/GetJointTrajectoryValidity";
01436 }
01437
01438 static const char* value(const planning_environment_msgs::GetJointTrajectoryValidityResponse_<ContainerAllocator> &) { return value(); }
01439 };
01440
01441 }
01442 }
01443
01444 #endif // PLANNING_ENVIRONMENT_MSGS_SERVICE_GETJOINTTRAJECTORYVALIDITY_H
01445