motion_planning_msgs/DisplayPath Message

File: motion_planning_msgs/DisplayPath.msg

# The model id for which this path has been generated
string model_id
# The representation of the path contains position values for all the joints that are moving along the path
JointPath path
# The robot state is used to obtain positions for all/some of the joints of the robot. 
# It is used by the path display node to determine the positions of the joints that are not specified in the joint path message above. 
# If the robot state message contains joint position information for joints that are also mentioned in the joint path message, the positions in the joint path message will overwrite the positions specified in the robot state message. 
RobotState robot_state

Expanded Definition

string model_id
JointPath path
    Header header
        uint32 seq
        time stamp
        string frame_id
    string[] joint_names
    motion_planning_msgs/JointPathPoint[] points
        float64[] positions
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