00001
00002 #ifndef MOVE_ARM_MSGS_MESSAGE_MOVEARMACTIONGOAL_H
00003 #define MOVE_ARM_MSGS_MESSAGE_MOVEARMACTIONGOAL_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "std_msgs/Header.h"
00014 #include "actionlib_msgs/GoalID.h"
00015 #include "move_arm_msgs/MoveArmGoal.h"
00016
00017 namespace move_arm_msgs
00018 {
00019 template <class ContainerAllocator>
00020 struct MoveArmActionGoal_ : public ros::Message
00021 {
00022 typedef MoveArmActionGoal_<ContainerAllocator> Type;
00023
00024 MoveArmActionGoal_()
00025 : header()
00026 , goal_id()
00027 , goal()
00028 {
00029 }
00030
00031 MoveArmActionGoal_(const ContainerAllocator& _alloc)
00032 : header(_alloc)
00033 , goal_id(_alloc)
00034 , goal(_alloc)
00035 {
00036 }
00037
00038 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00039 ::std_msgs::Header_<ContainerAllocator> header;
00040
00041 typedef ::actionlib_msgs::GoalID_<ContainerAllocator> _goal_id_type;
00042 ::actionlib_msgs::GoalID_<ContainerAllocator> goal_id;
00043
00044 typedef ::move_arm_msgs::MoveArmGoal_<ContainerAllocator> _goal_type;
00045 ::move_arm_msgs::MoveArmGoal_<ContainerAllocator> goal;
00046
00047
00048 private:
00049 static const char* __s_getDataType_() { return "move_arm_msgs/MoveArmActionGoal"; }
00050 public:
00051 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00052
00053 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00054
00055 private:
00056 static const char* __s_getMD5Sum_() { return "9b271f91d996a9442a767677d36e2eb3"; }
00057 public:
00058 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00059
00060 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00061
00062 private:
00063 static const char* __s_getMessageDefinition_() { return "\n\
00064 Header header\n\
00065 actionlib_msgs/GoalID goal_id\n\
00066 MoveArmGoal goal\n\
00067 \n\
00068 ================================================================================\n\
00069 MSG: std_msgs/Header\n\
00070 # Standard metadata for higher-level stamped data types.\n\
00071 # This is generally used to communicate timestamped data \n\
00072 # in a particular coordinate frame.\n\
00073 # \n\
00074 # sequence ID: consecutively increasing ID \n\
00075 uint32 seq\n\
00076 #Two-integer timestamp that is expressed as:\n\
00077 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00078 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00079 # time-handling sugar is provided by the client library\n\
00080 time stamp\n\
00081 #Frame this data is associated with\n\
00082 # 0: no frame\n\
00083 # 1: global frame\n\
00084 string frame_id\n\
00085 \n\
00086 ================================================================================\n\
00087 MSG: actionlib_msgs/GoalID\n\
00088 # The stamp should store the time at which this goal was requested.\n\
00089 # It is used by an action server when it tries to preempt all\n\
00090 # goals that were requested before a certain time\n\
00091 time stamp\n\
00092 \n\
00093 # The id provides a way to associate feedback and\n\
00094 # result message with specific goal requests. The id\n\
00095 # specified must be unique.\n\
00096 string id\n\
00097 \n\
00098 \n\
00099 ================================================================================\n\
00100 MSG: move_arm_msgs/MoveArmGoal\n\
00101 # Service name to call for getting a motion plan\n\
00102 # Move arm will call a service on this service name \n\
00103 # using the MotionPlanRequest specified here\n\
00104 string planner_service_name\n\
00105 \n\
00106 # A motion planning request\n\
00107 motion_planning_msgs/MotionPlanRequest motion_plan_request\n\
00108 \n\
00109 # OPTIONAL flag\n\
00110 # Setting this flag to true will allow move_arm to accept plans that do not go all the way to the goal\n\
00111 bool accept_partial_plans\n\
00112 \n\
00113 # OPTIONAL flag\n\
00114 # Setting this flag to true will allow move_arm to accept invalid goals\n\
00115 # This is useful if you are using a planner like CHOMP along with a noisy rapidly changing collision map\n\
00116 # and you would like to plan to a goal near an object.\n\
00117 bool accept_invalid_goals\n\
00118 \n\
00119 # OPTIONAL flag\n\
00120 # Setting this flag to true will disable the call to IK for a pose goal\n\
00121 bool disable_ik\n\
00122 \n\
00123 # OPTIONAL flag\n\
00124 # Setting this flag to true will disable collision monitoring during execution of a trajectory\n\
00125 bool disable_collision_monitoring\n\
00126 ================================================================================\n\
00127 MSG: motion_planning_msgs/MotionPlanRequest\n\
00128 # This service contains the definition for a request to the motion\n\
00129 # planner and the output it provides\n\
00130 \n\
00131 # Parameters for the workspace that the planner should work inside\n\
00132 motion_planning_msgs/WorkspaceParameters workspace_parameters\n\
00133 \n\
00134 # Starting state updates. If certain joints should be considered\n\
00135 # at positions other than the current ones, these positions should\n\
00136 # be set here\n\
00137 motion_planning_msgs/RobotState start_state\n\
00138 \n\
00139 # The goal state for the model to plan for. The goal is achieved\n\
00140 # if all constraints are satisfied\n\
00141 motion_planning_msgs/Constraints goal_constraints\n\
00142 \n\
00143 # No state at any point along the path in the produced motion plan will violate these constraints\n\
00144 motion_planning_msgs/Constraints path_constraints\n\
00145 \n\
00146 # A specification for regions where contact is \n\
00147 # allowed up to a certain depth\n\
00148 # Any collision within this set of regions with a link \n\
00149 # specified in the message will be allowed if\n\
00150 # it is less than the penetration depth specified in the message\n\
00151 AllowedContactSpecification[] allowed_contacts\n\
00152 \n\
00153 # A set of ordered collision operations, \n\
00154 # these are applied to all links, objects, \n\
00155 # namespaces in the collision space\n\
00156 OrderedCollisionOperations ordered_collision_operations\n\
00157 \n\
00158 # Specifies a set of links and paddings to change from the default\n\
00159 # specified in the yaml file\n\
00160 motion_planning_msgs/LinkPadding[] link_padding\n\
00161 \n\
00162 # The name of the motion planner to use. If no name is specified,\n\
00163 # a default motion planner will be used\n\
00164 string planner_id\n\
00165 \n\
00166 # The name of the group of joints on which this planner is operating\n\
00167 string group_name\n\
00168 \n\
00169 # The number of times this plan is to be computed. Shortest solution\n\
00170 # will be reported.\n\
00171 int32 num_planning_attempts\n\
00172 \n\
00173 # The maximum amount of time the motion planner is allowed to plan for\n\
00174 duration allowed_planning_time\n\
00175 \n\
00176 # 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\
00177 duration expected_path_duration\n\
00178 duration expected_path_dt\n\
00179 \n\
00180 ================================================================================\n\
00181 MSG: motion_planning_msgs/WorkspaceParameters\n\
00182 # This message contains a set of parameters useful in\n\
00183 # setting up the workspace for planning\n\
00184 geometric_shapes_msgs/Shape workspace_region_shape\n\
00185 geometry_msgs/PoseStamped workspace_region_pose\n\
00186 \n\
00187 \n\
00188 ================================================================================\n\
00189 MSG: geometric_shapes_msgs/Shape\n\
00190 byte SPHERE=0\n\
00191 byte BOX=1\n\
00192 byte CYLINDER=2\n\
00193 byte MESH=3\n\
00194 \n\
00195 byte type\n\
00196 \n\
00197 \n\
00198 #### define sphere, box, cylinder ####\n\
00199 # the origin of each shape is considered at the shape's center\n\
00200 \n\
00201 # for sphere\n\
00202 # radius := dimensions[0]\n\
00203 \n\
00204 # for cylinder\n\
00205 # radius := dimensions[0]\n\
00206 # length := dimensions[1]\n\
00207 # the length is along the Z axis\n\
00208 \n\
00209 # for box\n\
00210 # size_x := dimensions[0]\n\
00211 # size_y := dimensions[1]\n\
00212 # size_z := dimensions[2]\n\
00213 float64[] dimensions\n\
00214 \n\
00215 \n\
00216 #### define mesh ####\n\
00217 \n\
00218 # list of triangles; triangle k is defined by tre vertices located\n\
00219 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00220 int32[] triangles\n\
00221 geometry_msgs/Point[] vertices\n\
00222 \n\
00223 ================================================================================\n\
00224 MSG: geometry_msgs/Point\n\
00225 # This contains the position of a point in free space\n\
00226 float64 x\n\
00227 float64 y\n\
00228 float64 z\n\
00229 \n\
00230 ================================================================================\n\
00231 MSG: geometry_msgs/PoseStamped\n\
00232 # A Pose with reference coordinate frame and timestamp\n\
00233 Header header\n\
00234 Pose pose\n\
00235 \n\
00236 ================================================================================\n\
00237 MSG: geometry_msgs/Pose\n\
00238 # A representation of pose in free space, composed of postion and orientation. \n\
00239 Point position\n\
00240 Quaternion orientation\n\
00241 \n\
00242 ================================================================================\n\
00243 MSG: geometry_msgs/Quaternion\n\
00244 # This represents an orientation in free space in quaternion form.\n\
00245 \n\
00246 float64 x\n\
00247 float64 y\n\
00248 float64 z\n\
00249 float64 w\n\
00250 \n\
00251 ================================================================================\n\
00252 MSG: motion_planning_msgs/RobotState\n\
00253 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00254 sensor_msgs/JointState joint_state\n\
00255 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00256 ================================================================================\n\
00257 MSG: sensor_msgs/JointState\n\
00258 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00259 #\n\
00260 # The state of each joint (revolute or prismatic) is defined by:\n\
00261 # * the position of the joint (rad or m),\n\
00262 # * the velocity of the joint (rad/s or m/s) and \n\
00263 # * the effort that is applied in the joint (Nm or N).\n\
00264 #\n\
00265 # Each joint is uniquely identified by its name\n\
00266 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00267 # in one message have to be recorded at the same time.\n\
00268 #\n\
00269 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00270 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00271 # effort associated with them, you can leave the effort array empty. \n\
00272 #\n\
00273 # All arrays in this message should have the same size, or be empty.\n\
00274 # This is the only way to uniquely associate the joint name with the correct\n\
00275 # states.\n\
00276 \n\
00277 \n\
00278 Header header\n\
00279 \n\
00280 string[] name\n\
00281 float64[] position\n\
00282 float64[] velocity\n\
00283 float64[] effort\n\
00284 \n\
00285 ================================================================================\n\
00286 MSG: motion_planning_msgs/MultiDOFJointState\n\
00287 #A representation of a multi-dof joint state\n\
00288 time stamp\n\
00289 string[] joint_names\n\
00290 string[] frame_ids\n\
00291 string[] child_frame_ids\n\
00292 geometry_msgs/Pose[] poses\n\
00293 \n\
00294 ================================================================================\n\
00295 MSG: motion_planning_msgs/Constraints\n\
00296 # This message contains a list of motion planning constraints.\n\
00297 \n\
00298 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00299 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00300 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00301 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00302 \n\
00303 ================================================================================\n\
00304 MSG: motion_planning_msgs/JointConstraint\n\
00305 # Constrain the position of a joint to be within a certain bound\n\
00306 string joint_name\n\
00307 \n\
00308 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00309 float64 position\n\
00310 float64 tolerance_above\n\
00311 float64 tolerance_below\n\
00312 \n\
00313 # A weighting factor for this constraint\n\
00314 float64 weight\n\
00315 ================================================================================\n\
00316 MSG: motion_planning_msgs/PositionConstraint\n\
00317 # This message contains the definition of a position constraint.\n\
00318 Header header\n\
00319 \n\
00320 # The robot link this constraint refers to\n\
00321 string link_name\n\
00322 \n\
00323 # The offset (in the link frame) for the target point on the link we are planning for\n\
00324 geometry_msgs/Point target_point_offset\n\
00325 \n\
00326 # The nominal/target position for the point we are planning for\n\
00327 geometry_msgs/Point position\n\
00328 \n\
00329 # The shape of the bounded region that constrains the position of the end-effector\n\
00330 # This region is always centered at the position defined above\n\
00331 geometric_shapes_msgs/Shape constraint_region_shape\n\
00332 \n\
00333 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00334 # This allows the specification of non-axis aligned constraints\n\
00335 geometry_msgs/Quaternion constraint_region_orientation\n\
00336 \n\
00337 # Constraint weighting factor - a weight for this constraint\n\
00338 float64 weight\n\
00339 ================================================================================\n\
00340 MSG: motion_planning_msgs/OrientationConstraint\n\
00341 # This message contains the definition of an orientation constraint.\n\
00342 Header header\n\
00343 \n\
00344 # The robot link this constraint refers to\n\
00345 string link_name\n\
00346 \n\
00347 # The type of the constraint\n\
00348 int32 type\n\
00349 int32 LINK_FRAME=0\n\
00350 int32 HEADER_FRAME=1\n\
00351 \n\
00352 # The desired orientation of the robot link specified as a quaternion\n\
00353 geometry_msgs/Quaternion orientation\n\
00354 \n\
00355 # optional RPY error tolerances specified if \n\
00356 float64 absolute_roll_tolerance\n\
00357 float64 absolute_pitch_tolerance\n\
00358 float64 absolute_yaw_tolerance\n\
00359 \n\
00360 # Constraint weighting factor - a weight for this constraint\n\
00361 float64 weight\n\
00362 \n\
00363 ================================================================================\n\
00364 MSG: motion_planning_msgs/VisibilityConstraint\n\
00365 # This message contains the definition of a visibility constraint.\n\
00366 Header header\n\
00367 \n\
00368 # The point stamped target that needs to be kept within view of the sensor\n\
00369 geometry_msgs/PointStamped target\n\
00370 \n\
00371 # The local pose of the frame in which visibility is to be maintained\n\
00372 # The frame id should represent the robot link to which the sensor is attached\n\
00373 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00374 geometry_msgs/PoseStamped sensor_pose\n\
00375 \n\
00376 # The deviation (in radians) that will be tolerated\n\
00377 # Constraint error will be measured as the solid angle between the \n\
00378 # X axis of the frame defined above and the vector between the origin \n\
00379 # of the frame defined above and the target location\n\
00380 float64 absolute_tolerance\n\
00381 \n\
00382 \n\
00383 ================================================================================\n\
00384 MSG: geometry_msgs/PointStamped\n\
00385 # This represents a Point with reference coordinate frame and timestamp\n\
00386 Header header\n\
00387 Point point\n\
00388 \n\
00389 ================================================================================\n\
00390 MSG: motion_planning_msgs/AllowedContactSpecification\n\
00391 # The names of the regions\n\
00392 string name\n\
00393 \n\
00394 # The shape of the region in the environment\n\
00395 geometric_shapes_msgs/Shape shape\n\
00396 \n\
00397 # The pose of the space defining the region\n\
00398 geometry_msgs/PoseStamped pose_stamped\n\
00399 \n\
00400 # The set of links that will be allowed to have penetration contact within this region\n\
00401 string[] link_names\n\
00402 \n\
00403 # The maximum penetration depth allowed for every link\n\
00404 float64 penetration_depth\n\
00405 ================================================================================\n\
00406 MSG: motion_planning_msgs/OrderedCollisionOperations\n\
00407 # A set of collision operations that will be performed in the order they are specified\n\
00408 CollisionOperation[] collision_operations\n\
00409 ================================================================================\n\
00410 MSG: motion_planning_msgs/CollisionOperation\n\
00411 # A definition of a collision operation\n\
00412 # E.g. (\"gripper\",COLLISION_SET_ALL,ENABLE) will enable collisions \n\
00413 # between the gripper and all objects in the collision space\n\
00414 \n\
00415 string object1\n\
00416 string object2\n\
00417 string COLLISION_SET_ALL=\"all\"\n\
00418 string COLLISION_SET_OBJECTS=\"objects\"\n\
00419 string COLLISION_SET_ATTACHED_OBJECTS=\"attached\"\n\
00420 \n\
00421 # The penetration distance to which collisions are allowed. This is 0.0 by default.\n\
00422 float64 penetration_distance\n\
00423 \n\
00424 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above\n\
00425 int32 operation\n\
00426 int32 DISABLE=0\n\
00427 int32 ENABLE=1\n\
00428 \n\
00429 ================================================================================\n\
00430 MSG: motion_planning_msgs/LinkPadding\n\
00431 #name for the link\n\
00432 string link_name\n\
00433 \n\
00434 # padding to apply to the link\n\
00435 float64 padding\n\
00436 \n\
00437 "; }
00438 public:
00439 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00440
00441 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00442
00443 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00444 {
00445 ros::serialization::OStream stream(write_ptr, 1000000000);
00446 ros::serialization::serialize(stream, header);
00447 ros::serialization::serialize(stream, goal_id);
00448 ros::serialization::serialize(stream, goal);
00449 return stream.getData();
00450 }
00451
00452 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00453 {
00454 ros::serialization::IStream stream(read_ptr, 1000000000);
00455 ros::serialization::deserialize(stream, header);
00456 ros::serialization::deserialize(stream, goal_id);
00457 ros::serialization::deserialize(stream, goal);
00458 return stream.getData();
00459 }
00460
00461 ROS_DEPRECATED virtual uint32_t serializationLength() const
00462 {
00463 uint32_t size = 0;
00464 size += ros::serialization::serializationLength(header);
00465 size += ros::serialization::serializationLength(goal_id);
00466 size += ros::serialization::serializationLength(goal);
00467 return size;
00468 }
00469
00470 typedef boost::shared_ptr< ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> > Ptr;
00471 typedef boost::shared_ptr< ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> const> ConstPtr;
00472 };
00473 typedef ::move_arm_msgs::MoveArmActionGoal_<std::allocator<void> > MoveArmActionGoal;
00474
00475 typedef boost::shared_ptr< ::move_arm_msgs::MoveArmActionGoal> MoveArmActionGoalPtr;
00476 typedef boost::shared_ptr< ::move_arm_msgs::MoveArmActionGoal const> MoveArmActionGoalConstPtr;
00477
00478
00479 template<typename ContainerAllocator>
00480 std::ostream& operator<<(std::ostream& s, const ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> & v)
00481 {
00482 ros::message_operations::Printer< ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> >::stream(s, "", v);
00483 return s;}
00484
00485 }
00486
00487 namespace ros
00488 {
00489 namespace message_traits
00490 {
00491 template<class ContainerAllocator>
00492 struct MD5Sum< ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> > {
00493 static const char* value()
00494 {
00495 return "9b271f91d996a9442a767677d36e2eb3";
00496 }
00497
00498 static const char* value(const ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> &) { return value(); }
00499 static const uint64_t static_value1 = 0x9b271f91d996a944ULL;
00500 static const uint64_t static_value2 = 0x2a767677d36e2eb3ULL;
00501 };
00502
00503 template<class ContainerAllocator>
00504 struct DataType< ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> > {
00505 static const char* value()
00506 {
00507 return "move_arm_msgs/MoveArmActionGoal";
00508 }
00509
00510 static const char* value(const ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> &) { return value(); }
00511 };
00512
00513 template<class ContainerAllocator>
00514 struct Definition< ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> > {
00515 static const char* value()
00516 {
00517 return "\n\
00518 Header header\n\
00519 actionlib_msgs/GoalID goal_id\n\
00520 MoveArmGoal goal\n\
00521 \n\
00522 ================================================================================\n\
00523 MSG: std_msgs/Header\n\
00524 # Standard metadata for higher-level stamped data types.\n\
00525 # This is generally used to communicate timestamped data \n\
00526 # in a particular coordinate frame.\n\
00527 # \n\
00528 # sequence ID: consecutively increasing ID \n\
00529 uint32 seq\n\
00530 #Two-integer timestamp that is expressed as:\n\
00531 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00532 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00533 # time-handling sugar is provided by the client library\n\
00534 time stamp\n\
00535 #Frame this data is associated with\n\
00536 # 0: no frame\n\
00537 # 1: global frame\n\
00538 string frame_id\n\
00539 \n\
00540 ================================================================================\n\
00541 MSG: actionlib_msgs/GoalID\n\
00542 # The stamp should store the time at which this goal was requested.\n\
00543 # It is used by an action server when it tries to preempt all\n\
00544 # goals that were requested before a certain time\n\
00545 time stamp\n\
00546 \n\
00547 # The id provides a way to associate feedback and\n\
00548 # result message with specific goal requests. The id\n\
00549 # specified must be unique.\n\
00550 string id\n\
00551 \n\
00552 \n\
00553 ================================================================================\n\
00554 MSG: move_arm_msgs/MoveArmGoal\n\
00555 # Service name to call for getting a motion plan\n\
00556 # Move arm will call a service on this service name \n\
00557 # using the MotionPlanRequest specified here\n\
00558 string planner_service_name\n\
00559 \n\
00560 # A motion planning request\n\
00561 motion_planning_msgs/MotionPlanRequest motion_plan_request\n\
00562 \n\
00563 # OPTIONAL flag\n\
00564 # Setting this flag to true will allow move_arm to accept plans that do not go all the way to the goal\n\
00565 bool accept_partial_plans\n\
00566 \n\
00567 # OPTIONAL flag\n\
00568 # Setting this flag to true will allow move_arm to accept invalid goals\n\
00569 # This is useful if you are using a planner like CHOMP along with a noisy rapidly changing collision map\n\
00570 # and you would like to plan to a goal near an object.\n\
00571 bool accept_invalid_goals\n\
00572 \n\
00573 # OPTIONAL flag\n\
00574 # Setting this flag to true will disable the call to IK for a pose goal\n\
00575 bool disable_ik\n\
00576 \n\
00577 # OPTIONAL flag\n\
00578 # Setting this flag to true will disable collision monitoring during execution of a trajectory\n\
00579 bool disable_collision_monitoring\n\
00580 ================================================================================\n\
00581 MSG: motion_planning_msgs/MotionPlanRequest\n\
00582 # This service contains the definition for a request to the motion\n\
00583 # planner and the output it provides\n\
00584 \n\
00585 # Parameters for the workspace that the planner should work inside\n\
00586 motion_planning_msgs/WorkspaceParameters workspace_parameters\n\
00587 \n\
00588 # Starting state updates. If certain joints should be considered\n\
00589 # at positions other than the current ones, these positions should\n\
00590 # be set here\n\
00591 motion_planning_msgs/RobotState start_state\n\
00592 \n\
00593 # The goal state for the model to plan for. The goal is achieved\n\
00594 # if all constraints are satisfied\n\
00595 motion_planning_msgs/Constraints goal_constraints\n\
00596 \n\
00597 # No state at any point along the path in the produced motion plan will violate these constraints\n\
00598 motion_planning_msgs/Constraints path_constraints\n\
00599 \n\
00600 # A specification for regions where contact is \n\
00601 # allowed up to a certain depth\n\
00602 # Any collision within this set of regions with a link \n\
00603 # specified in the message will be allowed if\n\
00604 # it is less than the penetration depth specified in the message\n\
00605 AllowedContactSpecification[] allowed_contacts\n\
00606 \n\
00607 # A set of ordered collision operations, \n\
00608 # these are applied to all links, objects, \n\
00609 # namespaces in the collision space\n\
00610 OrderedCollisionOperations ordered_collision_operations\n\
00611 \n\
00612 # Specifies a set of links and paddings to change from the default\n\
00613 # specified in the yaml file\n\
00614 motion_planning_msgs/LinkPadding[] link_padding\n\
00615 \n\
00616 # The name of the motion planner to use. If no name is specified,\n\
00617 # a default motion planner will be used\n\
00618 string planner_id\n\
00619 \n\
00620 # The name of the group of joints on which this planner is operating\n\
00621 string group_name\n\
00622 \n\
00623 # The number of times this plan is to be computed. Shortest solution\n\
00624 # will be reported.\n\
00625 int32 num_planning_attempts\n\
00626 \n\
00627 # The maximum amount of time the motion planner is allowed to plan for\n\
00628 duration allowed_planning_time\n\
00629 \n\
00630 # 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\
00631 duration expected_path_duration\n\
00632 duration expected_path_dt\n\
00633 \n\
00634 ================================================================================\n\
00635 MSG: motion_planning_msgs/WorkspaceParameters\n\
00636 # This message contains a set of parameters useful in\n\
00637 # setting up the workspace for planning\n\
00638 geometric_shapes_msgs/Shape workspace_region_shape\n\
00639 geometry_msgs/PoseStamped workspace_region_pose\n\
00640 \n\
00641 \n\
00642 ================================================================================\n\
00643 MSG: geometric_shapes_msgs/Shape\n\
00644 byte SPHERE=0\n\
00645 byte BOX=1\n\
00646 byte CYLINDER=2\n\
00647 byte MESH=3\n\
00648 \n\
00649 byte type\n\
00650 \n\
00651 \n\
00652 #### define sphere, box, cylinder ####\n\
00653 # the origin of each shape is considered at the shape's center\n\
00654 \n\
00655 # for sphere\n\
00656 # radius := dimensions[0]\n\
00657 \n\
00658 # for cylinder\n\
00659 # radius := dimensions[0]\n\
00660 # length := dimensions[1]\n\
00661 # the length is along the Z axis\n\
00662 \n\
00663 # for box\n\
00664 # size_x := dimensions[0]\n\
00665 # size_y := dimensions[1]\n\
00666 # size_z := dimensions[2]\n\
00667 float64[] dimensions\n\
00668 \n\
00669 \n\
00670 #### define mesh ####\n\
00671 \n\
00672 # list of triangles; triangle k is defined by tre vertices located\n\
00673 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00674 int32[] triangles\n\
00675 geometry_msgs/Point[] vertices\n\
00676 \n\
00677 ================================================================================\n\
00678 MSG: geometry_msgs/Point\n\
00679 # This contains the position of a point in free space\n\
00680 float64 x\n\
00681 float64 y\n\
00682 float64 z\n\
00683 \n\
00684 ================================================================================\n\
00685 MSG: geometry_msgs/PoseStamped\n\
00686 # A Pose with reference coordinate frame and timestamp\n\
00687 Header header\n\
00688 Pose pose\n\
00689 \n\
00690 ================================================================================\n\
00691 MSG: geometry_msgs/Pose\n\
00692 # A representation of pose in free space, composed of postion and orientation. \n\
00693 Point position\n\
00694 Quaternion orientation\n\
00695 \n\
00696 ================================================================================\n\
00697 MSG: geometry_msgs/Quaternion\n\
00698 # This represents an orientation in free space in quaternion form.\n\
00699 \n\
00700 float64 x\n\
00701 float64 y\n\
00702 float64 z\n\
00703 float64 w\n\
00704 \n\
00705 ================================================================================\n\
00706 MSG: motion_planning_msgs/RobotState\n\
00707 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00708 sensor_msgs/JointState joint_state\n\
00709 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00710 ================================================================================\n\
00711 MSG: sensor_msgs/JointState\n\
00712 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00713 #\n\
00714 # The state of each joint (revolute or prismatic) is defined by:\n\
00715 # * the position of the joint (rad or m),\n\
00716 # * the velocity of the joint (rad/s or m/s) and \n\
00717 # * the effort that is applied in the joint (Nm or N).\n\
00718 #\n\
00719 # Each joint is uniquely identified by its name\n\
00720 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00721 # in one message have to be recorded at the same time.\n\
00722 #\n\
00723 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00724 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00725 # effort associated with them, you can leave the effort array empty. \n\
00726 #\n\
00727 # All arrays in this message should have the same size, or be empty.\n\
00728 # This is the only way to uniquely associate the joint name with the correct\n\
00729 # states.\n\
00730 \n\
00731 \n\
00732 Header header\n\
00733 \n\
00734 string[] name\n\
00735 float64[] position\n\
00736 float64[] velocity\n\
00737 float64[] effort\n\
00738 \n\
00739 ================================================================================\n\
00740 MSG: motion_planning_msgs/MultiDOFJointState\n\
00741 #A representation of a multi-dof joint state\n\
00742 time stamp\n\
00743 string[] joint_names\n\
00744 string[] frame_ids\n\
00745 string[] child_frame_ids\n\
00746 geometry_msgs/Pose[] poses\n\
00747 \n\
00748 ================================================================================\n\
00749 MSG: motion_planning_msgs/Constraints\n\
00750 # This message contains a list of motion planning constraints.\n\
00751 \n\
00752 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00753 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00754 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00755 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00756 \n\
00757 ================================================================================\n\
00758 MSG: motion_planning_msgs/JointConstraint\n\
00759 # Constrain the position of a joint to be within a certain bound\n\
00760 string joint_name\n\
00761 \n\
00762 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00763 float64 position\n\
00764 float64 tolerance_above\n\
00765 float64 tolerance_below\n\
00766 \n\
00767 # A weighting factor for this constraint\n\
00768 float64 weight\n\
00769 ================================================================================\n\
00770 MSG: motion_planning_msgs/PositionConstraint\n\
00771 # This message contains the definition of a position constraint.\n\
00772 Header header\n\
00773 \n\
00774 # The robot link this constraint refers to\n\
00775 string link_name\n\
00776 \n\
00777 # The offset (in the link frame) for the target point on the link we are planning for\n\
00778 geometry_msgs/Point target_point_offset\n\
00779 \n\
00780 # The nominal/target position for the point we are planning for\n\
00781 geometry_msgs/Point position\n\
00782 \n\
00783 # The shape of the bounded region that constrains the position of the end-effector\n\
00784 # This region is always centered at the position defined above\n\
00785 geometric_shapes_msgs/Shape constraint_region_shape\n\
00786 \n\
00787 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00788 # This allows the specification of non-axis aligned constraints\n\
00789 geometry_msgs/Quaternion constraint_region_orientation\n\
00790 \n\
00791 # Constraint weighting factor - a weight for this constraint\n\
00792 float64 weight\n\
00793 ================================================================================\n\
00794 MSG: motion_planning_msgs/OrientationConstraint\n\
00795 # This message contains the definition of an orientation constraint.\n\
00796 Header header\n\
00797 \n\
00798 # The robot link this constraint refers to\n\
00799 string link_name\n\
00800 \n\
00801 # The type of the constraint\n\
00802 int32 type\n\
00803 int32 LINK_FRAME=0\n\
00804 int32 HEADER_FRAME=1\n\
00805 \n\
00806 # The desired orientation of the robot link specified as a quaternion\n\
00807 geometry_msgs/Quaternion orientation\n\
00808 \n\
00809 # optional RPY error tolerances specified if \n\
00810 float64 absolute_roll_tolerance\n\
00811 float64 absolute_pitch_tolerance\n\
00812 float64 absolute_yaw_tolerance\n\
00813 \n\
00814 # Constraint weighting factor - a weight for this constraint\n\
00815 float64 weight\n\
00816 \n\
00817 ================================================================================\n\
00818 MSG: motion_planning_msgs/VisibilityConstraint\n\
00819 # This message contains the definition of a visibility constraint.\n\
00820 Header header\n\
00821 \n\
00822 # The point stamped target that needs to be kept within view of the sensor\n\
00823 geometry_msgs/PointStamped target\n\
00824 \n\
00825 # The local pose of the frame in which visibility is to be maintained\n\
00826 # The frame id should represent the robot link to which the sensor is attached\n\
00827 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00828 geometry_msgs/PoseStamped sensor_pose\n\
00829 \n\
00830 # The deviation (in radians) that will be tolerated\n\
00831 # Constraint error will be measured as the solid angle between the \n\
00832 # X axis of the frame defined above and the vector between the origin \n\
00833 # of the frame defined above and the target location\n\
00834 float64 absolute_tolerance\n\
00835 \n\
00836 \n\
00837 ================================================================================\n\
00838 MSG: geometry_msgs/PointStamped\n\
00839 # This represents a Point with reference coordinate frame and timestamp\n\
00840 Header header\n\
00841 Point point\n\
00842 \n\
00843 ================================================================================\n\
00844 MSG: motion_planning_msgs/AllowedContactSpecification\n\
00845 # The names of the regions\n\
00846 string name\n\
00847 \n\
00848 # The shape of the region in the environment\n\
00849 geometric_shapes_msgs/Shape shape\n\
00850 \n\
00851 # The pose of the space defining the region\n\
00852 geometry_msgs/PoseStamped pose_stamped\n\
00853 \n\
00854 # The set of links that will be allowed to have penetration contact within this region\n\
00855 string[] link_names\n\
00856 \n\
00857 # The maximum penetration depth allowed for every link\n\
00858 float64 penetration_depth\n\
00859 ================================================================================\n\
00860 MSG: motion_planning_msgs/OrderedCollisionOperations\n\
00861 # A set of collision operations that will be performed in the order they are specified\n\
00862 CollisionOperation[] collision_operations\n\
00863 ================================================================================\n\
00864 MSG: motion_planning_msgs/CollisionOperation\n\
00865 # A definition of a collision operation\n\
00866 # E.g. (\"gripper\",COLLISION_SET_ALL,ENABLE) will enable collisions \n\
00867 # between the gripper and all objects in the collision space\n\
00868 \n\
00869 string object1\n\
00870 string object2\n\
00871 string COLLISION_SET_ALL=\"all\"\n\
00872 string COLLISION_SET_OBJECTS=\"objects\"\n\
00873 string COLLISION_SET_ATTACHED_OBJECTS=\"attached\"\n\
00874 \n\
00875 # The penetration distance to which collisions are allowed. This is 0.0 by default.\n\
00876 float64 penetration_distance\n\
00877 \n\
00878 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above\n\
00879 int32 operation\n\
00880 int32 DISABLE=0\n\
00881 int32 ENABLE=1\n\
00882 \n\
00883 ================================================================================\n\
00884 MSG: motion_planning_msgs/LinkPadding\n\
00885 #name for the link\n\
00886 string link_name\n\
00887 \n\
00888 # padding to apply to the link\n\
00889 float64 padding\n\
00890 \n\
00891 ";
00892 }
00893
00894 static const char* value(const ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> &) { return value(); }
00895 };
00896
00897 template<class ContainerAllocator> struct HasHeader< ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> > : public TrueType {};
00898 template<class ContainerAllocator> struct HasHeader< const ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> > : public TrueType {};
00899 }
00900 }
00901
00902 namespace ros
00903 {
00904 namespace serialization
00905 {
00906
00907 template<class ContainerAllocator> struct Serializer< ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> >
00908 {
00909 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00910 {
00911 stream.next(m.header);
00912 stream.next(m.goal_id);
00913 stream.next(m.goal);
00914 }
00915
00916 ROS_DECLARE_ALLINONE_SERIALIZER;
00917 };
00918 }
00919 }
00920
00921 namespace ros
00922 {
00923 namespace message_operations
00924 {
00925
00926 template<class ContainerAllocator>
00927 struct Printer< ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> >
00928 {
00929 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::move_arm_msgs::MoveArmActionGoal_<ContainerAllocator> & v)
00930 {
00931 s << indent << "header: ";
00932 s << std::endl;
00933 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00934 s << indent << "goal_id: ";
00935 s << std::endl;
00936 Printer< ::actionlib_msgs::GoalID_<ContainerAllocator> >::stream(s, indent + " ", v.goal_id);
00937 s << indent << "goal: ";
00938 s << std::endl;
00939 Printer< ::move_arm_msgs::MoveArmGoal_<ContainerAllocator> >::stream(s, indent + " ", v.goal);
00940 }
00941 };
00942
00943
00944 }
00945 }
00946
00947 #endif // MOVE_ARM_MSGS_MESSAGE_MOVEARMACTIONGOAL_H
00948