Skip to content

evo_traj

Michael Grupp edited this page May 17, 2018 · 26 revisions

evo_traj is the main tool to do house-keeping stuff with multiple trajectories, such as:

  • displaying some infos
  • plotting
  • verifying that the data is valid
  • exporting to other formats
  • applying transformations

etc.

Basics

evo_traj can open as many trajectories as you want. In case of a text based trajectory format (tum, euroc, kitti - see also the formats chapter) you give the trajectory files as arguments, for example:

evo_traj tum traj_1.txt traj_2.txt traj_3.txt

(here, you could also use glob notation on a UNIX-like system: evo_traj tum traj_*)

In case of a ROS bagfile, you give the .bag file path followed by the names of the geometry_msgs/PoseStamped topics you want to use:

evo_traj bag ROS_example.bag groundtruth ORB-SLAM S-PTAM

You can also use the --all_topics option to load all trajectories inside the bagfile.

A reference trajectory can be marked with --ref:

evo_traj bag ROS_example.bag ORB-SLAM S-PTAM --ref groundtruth

You have to give the --ref argument if you want to use the alignment features with evo_traj (-a / --align, -s / --correct_scale or --n_to_align).

Check trajectory data

By default, evo_traj prints out only a few important infos about the trajectories that you feed into it in this format:

name:	groundtruth
infos:	12765 poses, 304.207m path length, 889.019s duration

In verbose mode (-v/--verbose) the output changes to this format:

name:   groundtruth
infos
        duration (s)    889.01894474
        nr. of poses    12765
        path length (m) 304.206897009
        pos_end (m)     [ -3.32159757  -4.64051651  32.7839329 ]
        pos_start (m)   [-0.00489994 -0.01775981 -0.01375532]
        t_end (s)       1502793459.3
        t_start (s)     1502792570.28

You can get the most detailed output with the --full_check flag. This performs some math and logic checks - e.g. if the quaternions have unit norm or if the timestamps are ascending. Some speed values are shown as well (except for kitti where we don't have timestamps).

name:   groundtruth
infos
        duration (s)    889.01894474
        nr. of poses    12765
        path length (m) 304.206897009
        pos_end (m)     [ -3.32159757  -4.64051651  32.7839329 ]
        pos_start (m)   [-0.00489994 -0.01775981 -0.01375532]
        t_end (s)       1502793459.3
        t_start (s)     1502792570.28
checks
        SE(3) conform   yes
        array shapes    ok
        nr. of stamps   ok
        quaternions     ok
        timestamps      ok
stats
        v_avg (km/h)    1.411572
        v_avg (m/s)     0.392103
        v_max (km/h)    3.038775
        v_max (m/s)     0.844104
        v_min (km/h)    0.001567
        v_min (m/s)     0.000435

Tip: On UNIX-like systems, pipe the output to less to get a more comfortable view when loading multiple trajectories. If you don't want any output except warnings and errors, use --silent.

Plotting

Append -p or --plot to your command to plot the trajectories. You can specify the view with --plot_mode - e.g. --plot_mode xz for a 2D view at the x and z axes or --plot_mode xyz for a 3D view. In any case, there's also a second tab in the plot window with the x, y and z values plotted individually and a third one with roll, pitch and yaw angles (xyz-convention).

Exporting

See here.

Alignment and transformation

If you give a reference trajectory with --ref, you can align the other trajectories to the reference with Umeyama's method:

  • --align or -a = SE(3) Umeyama alignment (rotation, translation)
  • --align --correct_scale or -as = Sim(3) Umeyama alignment (rotation, translation, scale)
  • --correct_scale or -s = scale alignment

You can also align only the first n poses of the trajectories with --n_to_align, for example --n_to_align 100.

You can also transform the poses of the trajectories with a custom 3D transformation. For this, you need a .json file with the translation vector and the rotation quaternion in this format:

{
  "x": 0.0,
  "y": 0.0,
  "z": 0.0,
  "qx": 0.0,
  "qy": 0.0,
  "qz": 0.0,
  "qw": 1.0
}

To apply such a transformation from the global frame, use --transform_left <json file>. To transform each pose from its own local frame, use --transform_right <json file> (this changes the shape of the trajectory if it includes a translation!).

Clone this wiki locally