motion_planning_msgs/GetMotionPlan Service

File: motion_planning_msgs/GetMotionPlan.srv

# This service contains the definition for a request to the motion
# planner and the output it provides

MotionPlanRequest motion_plan_request

---

# A solution trajectory, if found
motion_planning_msgs/RobotTrajectory trajectory

# The corresponding robot state
motion_planning_msgs/RobotState robot_state

# Planning time
duration planning_time

# Error code - encodes the overall reason for failure
motion_planning_msgs/ArmNavigationErrorCodes error_code

# More detailed error codes (optional) - encode information about each point in the returned trajectory
motion_planning_msgs/ArmNavigationErrorCodes[] trajectory_error_codes

Expanded Definition

MotionPlanRequest motion_plan_request
    motion_planning_msgs/WorkspaceParameters workspace_parameters
        geometric_shapes_msgs/Shape workspace_region_shape
            byte SPHERE=0
            byte BOX=1
            byte CYLINDER=2
            byte MESH=3
            byte type
            float64[] dimensions
            int32[] triangles
            geometry_msgs/Point[] vertices
                float64 x
                float64 y
                float64 z
        geometry_msgs/PoseStamped workspace_region_pose
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/Pose pose
                geometry_msgs/Point position
                    float64 x
                    float64 y
                    float64 z
                geometry_msgs/Quaternion orientation
                    float64 x
                    float64 y
                    float64 z
                    float64 w
    motion_planning_msgs/RobotState start_state
        sensor_msgs/JointState joint_state
            Header header
                uint32 seq
                time stamp
                string frame_id
            string[] name
            float64[] position
            float64[] velocity
            float64[] effort
        motion_planning_msgs/MultiDOFJointState multi_dof_joint_state
            time stamp
            string[] joint_names
            string[] frame_ids
            string[] child_frame_ids
            geometry_msgs/Pose[] poses
                geometry_msgs/Point position
                    float64 x
                    float64 y
                    float64 z
                geometry_msgs/Quaternion orientation
                    float64 x
                    float64 y
                    float64 z
                    float64 w
    motion_planning_msgs/Constraints goal_constraints
        motion_planning_msgs/JointConstraint[] joint_constraints
            string joint_name
            float64 position
            float64 tolerance_above
            float64 tolerance_below
            float64 weight
        motion_planning_msgs/PositionConstraint[] position_constraints
            Header header
                uint32 seq
                time stamp
                string frame_id
            string link_name
            geometry_msgs/Point target_point_offset
                float64 x
                float64 y
                float64 z
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometric_shapes_msgs/Shape constraint_region_shape
                byte SPHERE=0
                byte BOX=1
                byte CYLINDER=2
                byte MESH=3
                byte type
                float64[] dimensions
                int32[] triangles
                geometry_msgs/Point[] vertices
                    float64 x
                    float64 y
                    float64 z
            geometry_msgs/Quaternion constraint_region_orientation
                float64 x
                float64 y
                float64 z
                float64 w
            float64 weight
        motion_planning_msgs/OrientationConstraint[] orientation_constraints
            int32 LINK_FRAME=0
            int32 HEADER_FRAME=1
            Header header
                uint32 seq
                time stamp
                string frame_id
            string link_name
            int32 type
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
            float64 absolute_roll_tolerance
            float64 absolute_pitch_tolerance
            float64 absolute_yaw_tolerance
            float64 weight
        motion_planning_msgs/VisibilityConstraint[] visibility_constraints
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/PointStamped target
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                geometry_msgs/Point point
                    float64 x
                    float64 y
                    float64 z
            geometry_msgs/PoseStamped sensor_pose
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                geometry_msgs/Pose pose
                    geometry_msgs/Point position
                        float64 x
                        float64 y
                        float64 z
                    geometry_msgs/Quaternion orientation
                        float64 x
                        float64 y
                        float64 z
                        float64 w
            float64 absolute_tolerance
    motion_planning_msgs/Constraints path_constraints
        motion_planning_msgs/JointConstraint[] joint_constraints
            string joint_name
            float64 position
            float64 tolerance_above
            float64 tolerance_below
            float64 weight
        motion_planning_msgs/PositionConstraint[] position_constraints
            Header header
                uint32 seq
                time stamp
                string frame_id
            string link_name
            geometry_msgs/Point target_point_offset
                float64 x
                float64 y
                float64 z
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometric_shapes_msgs/Shape constraint_region_shape
                byte SPHERE=0
                byte BOX=1
                byte CYLINDER=2
                byte MESH=3
                byte type
                float64[] dimensions
                int32[] triangles
                geometry_msgs/Point[] vertices
                    float64 x
                    float64 y
                    float64 z
            geometry_msgs/Quaternion constraint_region_orientation
                float64 x
                float64 y
                float64 z
                float64 w
            float64 weight
        motion_planning_msgs/OrientationConstraint[] orientation_constraints
            int32 LINK_FRAME=0
            int32 HEADER_FRAME=1
            Header header
                uint32 seq
                time stamp
                string frame_id
            string link_name
            int32 type
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
            float64 absolute_roll_tolerance
            float64 absolute_pitch_tolerance
            float64 absolute_yaw_tolerance
            float64 weight
        motion_planning_msgs/VisibilityConstraint[] visibility_constraints
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/PointStamped target
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                geometry_msgs/Point point
                    float64 x
                    float64 y
                    float64 z
            geometry_msgs/PoseStamped sensor_pose
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                geometry_msgs/Pose pose
                    geometry_msgs/Point position
                        float64 x
                        float64 y
                        float64 z
                    geometry_msgs/Quaternion orientation
                        float64 x
                        float64 y
                        float64 z
                        float64 w
            float64 absolute_tolerance
    motion_planning_msgs/AllowedContactSpecification[] allowed_contacts
        string name
        geometric_shapes_msgs/Shape shape
            byte SPHERE=0
            byte BOX=1
            byte CYLINDER=2
            byte MESH=3
            byte type
            float64[] dimensions
            int32[] triangles
            geometry_msgs/Point[] vertices
                float64 x
                float64 y
                float64 z
        geometry_msgs/PoseStamped pose_stamped
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/Pose pose
                geometry_msgs/Point position
                    float64 x
                    float64 y
                    float64 z
                geometry_msgs/Quaternion orientation
                    float64 x
                    float64 y
                    float64 z
                    float64 w
        string[] link_names
        float64 penetration_depth
    motion_planning_msgs/OrderedCollisionOperations ordered_collision_operations
        motion_planning_msgs/CollisionOperation[] collision_operations
            string COLLISION_SET_ALL="all"
            string COLLISION_SET_OBJECTS="objects"
            string COLLISION_SET_ATTACHED_OBJECTS="attached"
            int32 DISABLE=0
            int32 ENABLE=1
            string object1
            string object2
            float64 penetration_distance
            int32 operation
    motion_planning_msgs/LinkPadding[] link_padding
        string link_name
        float64 padding
    string planner_id
    string group_name
    int32 num_planning_attempts
    duration allowed_planning_time
    duration expected_path_duration
    duration expected_path_dt

motion_planning_msgs/RobotTrajectory trajectory
    trajectory_msgs/JointTrajectory joint_trajectory
        Header header
            uint32 seq
            time stamp
            string frame_id
        string[] joint_names
        trajectory_msgs/JointTrajectoryPoint[] points
            float64[] positions
            float64[] velocities
            float64[] accelerations
            duration time_from_start
    motion_planning_msgs/MultiDOFJointTrajectory multi_dof_joint_trajectory
        duration stamp
        string[] joint_names
        string[] frame_ids
        string[] child_frame_ids
        motion_planning_msgs/MultiDOFJointTrajectoryPoint[] points
            geometry_msgs/Pose[] poses
                geometry_msgs/Point position
                    float64 x
                    float64 y
                    float64 z
                geometry_msgs/Quaternion orientation
                    float64 x
                    float64 y
                    float64 z
                    float64 w
            duration time_from_start
motion_planning_msgs/RobotState robot_state
    sensor_msgs/JointState joint_state
        Header header
            uint32 seq
            time stamp
            string frame_id
        string[] name
        float64[] position
        float64[] velocity
        float64[] effort
    motion_planning_msgs/MultiDOFJointState multi_dof_joint_state
        time stamp
        string[] joint_names
        string[] frame_ids
        string[] child_frame_ids
        geometry_msgs/Pose[] poses
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
duration planning_time
motion_planning_msgs/ArmNavigationErrorCodes error_code
    int32 PLANNING_FAILED=-1
    int32 SUCCESS=1
    int32 TIMED_OUT=-2
    int32 START_STATE_IN_COLLISION=-3
    int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
    int32 GOAL_IN_COLLISION=-5
    int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
    int32 INVALID_ROBOT_STATE=-7
    int32 INCOMPLETE_ROBOT_STATE=-8
    int32 INVALID_PLANNER_ID=-9
    int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
    int32 INVALID_ALLOWED_PLANNING_TIME=-11
    int32 INVALID_GROUP_NAME=-12
    int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
    int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
    int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
    int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
    int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
    int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
    int32 INVALID_TRAJECTORY=-19
    int32 INVALID_INDEX=-20
    int32 JOINT_LIMITS_VIOLATED=-21
    int32 PATH_CONSTRAINTS_VIOLATED=-22
    int32 COLLISION_CONSTRAINTS_VIOLATED=-23
    int32 GOAL_CONSTRAINTS_VIOLATED=-24
    int32 JOINTS_NOT_MOVING=-25
    int32 TRAJECTORY_CONTROLLER_FAILED=-26
    int32 FRAME_TRANSFORM_FAILURE=-27
    int32 COLLISION_CHECKING_UNAVAILABLE=-28
    int32 ROBOT_STATE_STALE=-29
    int32 SENSOR_INFO_STALE=-30
    int32 NO_IK_SOLUTION=-31
    int32 INVALID_LINK_NAME=-32
    int32 IK_LINK_IN_COLLISION=-33
    int32 NO_FK_SOLUTION=-34
    int32 KINEMATICS_STATE_IN_COLLISION=-35
    int32 INVALID_TIMEOUT=-36
    int32 val
motion_planning_msgs/ArmNavigationErrorCodes[] trajectory_error_codes
    int32 PLANNING_FAILED=-1
    int32 SUCCESS=1
    int32 TIMED_OUT=-2
    int32 START_STATE_IN_COLLISION=-3
    int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
    int32 GOAL_IN_COLLISION=-5
    int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
    int32 INVALID_ROBOT_STATE=-7
    int32 INCOMPLETE_ROBOT_STATE=-8
    int32 INVALID_PLANNER_ID=-9
    int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
    int32 INVALID_ALLOWED_PLANNING_TIME=-11
    int32 INVALID_GROUP_NAME=-12
    int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
    int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
    int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
    int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
    int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
    int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
    int32 INVALID_TRAJECTORY=-19
    int32 INVALID_INDEX=-20
    int32 JOINT_LIMITS_VIOLATED=-21
    int32 PATH_CONSTRAINTS_VIOLATED=-22
    int32 COLLISION_CONSTRAINTS_VIOLATED=-23
    int32 GOAL_CONSTRAINTS_VIOLATED=-24
    int32 JOINTS_NOT_MOVING=-25
    int32 TRAJECTORY_CONTROLLER_FAILED=-26
    int32 FRAME_TRANSFORM_FAILURE=-27
    int32 COLLISION_CHECKING_UNAVAILABLE=-28
    int32 ROBOT_STATE_STALE=-29
    int32 SENSOR_INFO_STALE=-30
    int32 NO_IK_SOLUTION=-31
    int32 INVALID_LINK_NAME=-32
    int32 IK_LINK_IN_COLLISION=-33
    int32 NO_FK_SOLUTION=-34
    int32 KINEMATICS_STATE_IN_COLLISION=-35
    int32 INVALID_TIMEOUT=-36
    int32 val