kinematics_msgs/PositionIKRequest Message

File: kinematics_msgs/PositionIKRequest.msg

# A Position IK request message
# The name of the link for which we are computing IK
string ik_link_name

# The (stamped) pose of the link
geometry_msgs/PoseStamped pose_stamped

# A RobotState consisting of hint/seed positions for the IK computation. 
# These may be used to seed the IK search. 
# The seed state MUST contain state for all joints to be used by the IK solver
# to compute IK. The list of joints that the IK solver deals with can be found using
# the kinematics_msgs/GetKinematicSolverInfo
motion_planning_msgs/RobotState ik_seed_state

# Additional state information can be provided here to specify the starting positions 
# of other joints/links on the robot.
motion_planning_msgs/RobotState robot_state

Expanded Definition

string ik_link_name
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
motion_planning_msgs/RobotState ik_seed_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/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