motion_planning_msgs/ConvertToJointConstraint Service

File: motion_planning_msgs/ConvertToJointConstraint.srv

string model_id

# Parameters for the state space 
motion_planning_msgs/WorkspaceParameters workspace_parameters

# Starting state updates. If certain joints should be considered
# at positions other than the current ones, these positions should
# be set here
motion_planning_msgs/RobotState start_state

# The joint names, in the same order as the values in the state
string[] joint_names

# A list of hint states, each with the dimension of the requested model.
motion_planning_msgs/RobotState[] init_states

# The input constraints, to be converted to a set of joint constraints
motion_planning_msgs/Constraints constraints

# The maximum amount of time the search is to be run for
float64 allowed_time

---

# The set of joint constraints that correspond to the pose constraint
motion_planning_msgs/JointConstraint[] joint_constraints

Expanded Definition

string model_id
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
string[] joint_names
motion_planning_msgs/RobotState[] init_states
    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 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
float64 allowed_time

motion_planning_msgs/JointConstraint[] joint_constraints
    string joint_name
    float64 position
    float64 tolerance_above
    float64 tolerance_below
    float64 weight