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