motion_planning_msgs/RobotTrajectory Message

File: motion_planning_msgs/RobotTrajectory.msg

trajectory_msgs/JointTrajectory joint_trajectory
motion_planning_msgs/MultiDOFJointTrajectory multi_dof_joint_trajectory

Expanded Definition

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