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