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