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

Revision history [back]

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.0]
        time_from_start: 
          secs: 1
          nsecs: 324259613
      - 
        positions: [-1.7266965336015323, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -1.7078876877058584]
        velocities: [1.0955434012456187, 0.0, 0.0, 5.577067357268163e-16, 1.0836096846920393]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 1
          nsecs: 544259614
      - 
        positions: [-1.5618053834346186, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -1.5447926911610177]
        velocities: [1.1002506664107818, 0.0, 0.0, -1.6280551286439496e-16, 1.0882656737798182]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 1
          nsecs: 694259614
      - 
        positions: [-1.352801108899281, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -1.3380650929928186]
        velocities: [1.0995760502885568, 0.0, 0.0, 3.1423072274376064e-17, 1.087598406227786]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 1
          nsecs: 884388906
      - 
        positions: [-1.2428109699673853, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -1.229273072857686]
        velocities: [1.099721341194797, 0.0, 0.0, -1.0271726233852743e-17, 1.0877421144851813]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 1
          nsecs: 984388907
      - 
        positions: [-1.0668126798340363, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -1.0551919260396805]
        velocities: [1.101621901250425, 0.0, 0.0, 3.1360609511064693e-18, 1.0896219718055542]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 2
          nsecs: 144388907
      - 
        positions: [-0.8186363391284005, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -0.8097189616694035]
        velocities: [1.0917942273591639, 0.0, 0.0, -6.310525555784859e-19, 1.079901350427656]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 2
          nsecs: 370054003
      - 
        positions: [-0.6872969356042933, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -0.6798102337462729]
        velocities: [1.1073704870325298, 0.0, 0.0, 2.6560761706557022e-19, 1.0953079384406423]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 2
          nsecs: 490054004
      - 
        positions: [-0.10077700694030943, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -0.09967924647315002]
        velocities: [0.6703568712225323, 0.0, 0.0, -4.289222110264426e-20, 0.663054696902626]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 3
          nsecs: 76996454
      - 
        positions: [-0.00012129289047690934, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -0.00011997165119668348]
        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: 3
          nsecs: 356996686
  path_tolerance: []
  goal_tolerance: []
  goal_time_tolerance: 
    secs: 0
    nsecs: 0

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 Katana robot arm. 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.0]
        time_from_start: 
          secs: 1
          nsecs: 324259613
      - 
        positions: [-1.7266965336015323, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -1.7078876877058584]
        velocities: [1.0955434012456187, 0.0, 0.0, 5.577067357268163e-16, 1.0836096846920393]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 1
          nsecs: 544259614
      - 
        positions: [-1.5618053834346186, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -1.5447926911610177]
        velocities: [1.1002506664107818, 0.0, 0.0, -1.6280551286439496e-16, 1.0882656737798182]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 1
          nsecs: 694259614
      - 
        positions: [-1.352801108899281, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -1.3380650929928186]
        velocities: [1.0995760502885568, 0.0, 0.0, 3.1423072274376064e-17, 1.087598406227786]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 1
          nsecs: 884388906
      - 
        positions: [-1.2428109699673853, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -1.229273072857686]
        velocities: [1.099721341194797, 0.0, 0.0, -1.0271726233852743e-17, 1.0877421144851813]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 1
          nsecs: 984388907
      - 
        positions: [-1.0668126798340363, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -1.0551919260396805]
        velocities: [1.101621901250425, 0.0, 0.0, 3.1360609511064693e-18, 1.0896219718055542]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 2
          nsecs: 144388907
      - 
        positions: [-0.8186363391284005, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -0.8097189616694035]
        velocities: [1.0917942273591639, 0.0, 0.0, -6.310525555784859e-19, 1.079901350427656]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 2
          nsecs: 370054003
      - 
        positions: [-0.6872969356042933, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -0.6798102337462729]
        velocities: [1.1073704870325298, 0.0, 0.0, 2.6560761706557022e-19, 1.0953079384406423]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 2
          nsecs: 490054004
      - 
        positions: [-0.10077700694030943, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -0.09967924647315002]
        velocities: [0.6703568712225323, 0.0, 0.0, -4.289222110264426e-20, 0.663054696902626]
        accelerations: [0.0, 0.0, 0.0, 0.0, 0.0]
        time_from_start: 
          secs: 3
          nsecs: 76996454
      - 
        positions: [-0.00012129289047690934, 2.13549384276445, -2.1556486321117725, -1.971949347057968, -0.00011997165119668348]
        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: 3
          nsecs: 356996686
  path_tolerance: []
  goal_tolerance: []
  goal_time_tolerance: 
    secs: 0
    nsecs: 0