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