control_msgs/FollowJointTrajectoryAction Message

File: control_msgs/FollowJointTrajectoryAction.msg

# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======

FollowJointTrajectoryActionGoal action_goal
FollowJointTrajectoryActionResult action_result
FollowJointTrajectoryActionFeedback action_feedback

Expanded Definition

FollowJointTrajectoryActionGoal action_goal
    Header header
        uint32 seq
        time stamp
        string frame_id
    actionlib_msgs/GoalID goal_id
        time stamp
        string id
    control_msgs/FollowJointTrajectoryGoal goal
        trajectory_msgs/JointTrajectory 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
        control_msgs/JointTolerance[] path_tolerance
            string name
            float64 position
            float64 velocity
            float64 acceleration
        control_msgs/JointTolerance[] goal_tolerance
            string name
            float64 position
            float64 velocity
            float64 acceleration
        duration goal_time_tolerance
FollowJointTrajectoryActionResult action_result
    Header header
        uint32 seq
        time stamp
        string frame_id
    actionlib_msgs/GoalStatus status
        uint8 PENDING=0
        uint8 ACTIVE=1
        uint8 PREEMPTED=2
        uint8 SUCCEEDED=3
        uint8 ABORTED=4
        uint8 REJECTED=5
        uint8 PREEMPTING=6
        uint8 RECALLING=7
        uint8 RECALLED=8
        uint8 LOST=9
        actionlib_msgs/GoalID goal_id
            time stamp
            string id
        uint8 status
        string text
    control_msgs/FollowJointTrajectoryResult result
        int32 SUCCESSFUL=0
        int32 INVALID_GOAL=-1
        int32 INVALID_JOINTS=-2
        int32 OLD_HEADER_TIMESTAMP=-3
        int32 PATH_TOLERANCE_VIOLATED=-4
        int32 GOAL_TOLERANCE_VIOLATED=-5
        int32 error_code
FollowJointTrajectoryActionFeedback action_feedback
    Header header
        uint32 seq
        time stamp
        string frame_id
    actionlib_msgs/GoalStatus status
        uint8 PENDING=0
        uint8 ACTIVE=1
        uint8 PREEMPTED=2
        uint8 SUCCEEDED=3
        uint8 ABORTED=4
        uint8 REJECTED=5
        uint8 PREEMPTING=6
        uint8 RECALLING=7
        uint8 RECALLED=8
        uint8 LOST=9
        actionlib_msgs/GoalID goal_id
            time stamp
            string id
        uint8 status
        string text
    control_msgs/FollowJointTrajectoryFeedback feedback
        Header header
            uint32 seq
            time stamp
            string frame_id
        string[] joint_names
        trajectory_msgs/JointTrajectoryPoint desired
            float64[] positions
            float64[] velocities
            float64[] accelerations
            duration time_from_start
        trajectory_msgs/JointTrajectoryPoint actual
            float64[] positions
            float64[] velocities
            float64[] accelerations
            duration time_from_start
        trajectory_msgs/JointTrajectoryPoint error
            float64[] positions
            float64[] velocities
            float64[] accelerations
            duration time_from_start