ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
3

The meaning of velocities, accelerations and time_from_start in JointTrajectoryPoint.msg

asked 2012-12-16 16:19:54 -0500

Albert K gravatar image

updated 2014-01-28 17:14:36 -0500

ngrennan gravatar image

I've followed this tutorial

When I tried to fill in the action goal of the type JointTrajectoryActionGoal, I didn't know what value shoud goal.goal.trajectory.points[i].velocities[i] and goal.goal.trajectory.points[i].time_from_start be, which belonged to trajectory_msgs/JointTrajectoryPoint.msg

I've tried several value and felt that time_from_start seemed to be related to the total execution time, but still got no idea about velocities, which tended to make the trajectory weird.

I would like to know what's the meaning behind these parameters and how to set it up properly. Thanks~

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
7

answered 2012-12-17 22:32:33 -0500

updated 2012-12-17 22:34:15 -0500

Yes, the semantics of the joint trajectory messages is a little under-specified. Some pointers:

  • time_from_start is relative to trajectory.header.stamp; each trajectory point's time_from_start must be greater than the last
  • the velocities specify the joint velocities you would like the joints to have at that trajectory point
  • the velocities should be all 0 for the first and last trajectory point
  • you shouldn't execute such a "hand-crafted" trajectory directly on the robot; instead, run it through a properly set-up trajectory_filter pipeline first to make sure it's physically possible to reach the desired joint trajectories at the given time points

I think an example would be nice, so this is a trajectory generated and executed on the Katana robot arm. (Actually, this is the new FollowJointTrajectoryAction and not the old JointTrajectoryAction format, but they are almost identical).

I just noticed while writing this answer that this trajectory might not be an ideal example. The accelerations are all 0, which doesn't make sense; they should either be empty (saying that there are no desired accelerations, and the controller is free to choose) or be filled to sensible values. Seems to be a bug in my trajectory filtering pipeline. Anyway, here you go:

header: 
  seq: 0
  stamp: 
    secs: 1355824277
    nsecs: 243513013
  frame_id: ''
goal_id: 
  stamp: 
    secs: 1355824277
    nsecs: 243517830
  id: /kurtana_move_arm-1-1355824277.243517830
goal: 
  trajectory: 
    header: 
      seq: 0
      stamp: 
        secs: 1355824277
        nsecs: 443477691
      frame_id: ''
    joint_names: ['katana_motor1_pan_joint', 'katana_motor2_lift_joint', 'katana_motor3_lift_joint', 'katana_motor4_lift_joint', 'katana_motor5_wrist_roll_joint']
    points: 
      - 
        positions: [-2.9641690268167444, 2.13549384276445, -2.1556486321117725, -1.9719493470579683, -2.9318804356548496]
        velocities: [0.0, 0.0, 0.0, 0.0, 0.0]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 0
          nsecs: 0
      - 
        positions: [-2.9251733424342388, 2.13549384276445, -2.1556486321117725, -1.9719493470579683, -2.8933095299198217]
        velocities: [0.29930315443351097, 0.0, 0.0, -6.139114030773157e-19, 0.2960428554763487]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 0
          nsecs: 228646348
      - 
        positions: [-2.8849641701621285, 2.13549384276445, -2.1556486321117725, -1.9719493470579683, -2.853538354776994]
        velocities: [0.44598050148009644, 0.0, 0.0, 1.823853811086392e-18, 0.4411224512312072]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 0
          nsecs: 339639817
      - 
        positions: [-2.52736640929761, 2.13549384276445, -2.1556486321117725, -1.9719493470579683, -2.4998358940105807]
        velocities: [1.0028722191625212, 0.0, 0.0, -1.6240875412254114e-17, 0.9919479666049925]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 0
          nsecs: 800369305
      - 
        positions: [-2.2959492044755803, 2.13549384276445, -2.1556486321117725, -1.9719493470579683, -2.2709395088336946]
        velocities: [1.0910884747158898, 0.0, 0.0, 4.7121007739083667e-17, 1.0792032855236304]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 1
          nsecs: 20369305
      - 
        positions: [-2.1094083544721736, 2.13549384276445, -2.1556486321117725, -1.9719493470579683, -2.0864306418873473]
        velocities: [1.0870331216234024, 0.0, 0.0, -1.5451562371091847e-16, 1.0751921072527668]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 1
          nsecs: 190369305
      - 
        positions: [-1.9654064488044534, 2.13549384276445, -2.1556486321117725, -1.9719493470579683, -1.9439973440205225]
        velocities: [1.0735605072416647, 0.0, 0.0, 5.153091454187644e-16, 1.0618662495956706]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0 ...
(more)
edit flag offensive delete link more

Comments

2

Trajectory endpoints don't need to have zero vel/acc. This is especially so for the first point: if it has time_from_start>0, a spline will be traced from the current state (can also have nonzero vel/acc) in time_from_start sec. We use this a lot for online trajectory substitution.

Adolfo Rodriguez T gravatar image Adolfo Rodriguez T  ( 2012-12-18 20:27:55 -0500 )edit

Thank you very much~ I have two questions. Is time from start equals to the execution time? Can I deduce that accelerations term equals to the acceleration at that trajectory point?

Albert K gravatar image Albert K  ( 2012-12-18 20:29:46 -0500 )edit

Actually, I've tried trajectory filter and get problems : http://answers.ros.org/question/50611/trajectory-filter-response-with-nothing/

Albert K gravatar image Albert K  ( 2012-12-18 20:30:49 -0500 )edit

Why is that some of the time_from_start are the same as (not greater than) the last points in the example?

Albert K gravatar image Albert K  ( 2012-12-18 20:33:52 -0500 )edit
1

Trajectories with unspecified accelerations use cubic spline interpolation, hence have no acceleration continuity. Trajectories specifying accelerations use quintic splines and guarantee acceleration continuity. Setting them to zero at waypoints is a perfectly valid choice (and used in practice).

Adolfo Rodriguez T gravatar image Adolfo Rodriguez T  ( 2012-12-18 20:38:06 -0500 )edit
1

Total desired trajectory duration is the time_from_start of the last trajectory point. In the posted example all waypoint times are monotonically increasing, as expected. Note that durations consist of two fields: secs and nsecs, and although the secs field may be equal for two points, nsec is not.

Adolfo Rodriguez T gravatar image Adolfo Rodriguez T  ( 2012-12-18 20:44:07 -0500 )edit

Thanks for your helpful comments, Adolfo! I forgot about trajectory substitution and acceleration continuity; the Katana arm is more limited than the PR2's arms, so it cannot do either of them.

Martin Günther gravatar image Martin Günther  ( 2012-12-18 21:53:25 -0500 )edit

Hi, I am using FollowJointTrajectoryGoal to define trajectories for the UR5. Would you recommend FollowJointTrajectoryAction for it as well? I am using the ros-industrial/universal_robot package.

varunagrawal gravatar image varunagrawal  ( 2016-02-01 19:29:25 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2012-12-16 16:19:54 -0500

Seen: 6,914 times

Last updated: Dec 17 '12