Skip to content

Formats

Michael Grupp edited this page Jun 14, 2024 · 31 revisions

Trajectories

Executables that load trajectories support different formats. You can specify the format you want to use with the mode switch (2nd argument), for example: evo_traj tum ... or evo_traj kitti .... This document provides information about these file formats.

Tip: if you don't know which format you should use for your SLAM algorithm, use the TUM format. It's simple, but can be converted to any other format later and doesn't require ROS.


bag & bag2 - ROS1/ROS2 bagfile

Currently, bagfiles with topics that contain geometry_msgs/PoseStamped, geometry_msgs/TransformStamped, geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/PointStamped and nav_msgs/Odometry messages are supported. evo only reads the trajectory, thus covariance or twist aren't used.

Example usage for ROS 1 bags:

evo_traj bag my_data.bag /odom /pose

Example usage for ROS 2 bags:

evo_traj bag2 my_data /odom /pose

New since v1.9: TF topics are now also supported. You can load the trajectory of a TF transform in the command line apps with specifier <topic>:<parent_frame>.<child_frame>. For example:

evo_traj bag my_data.bag /tf:map.base_link /tf:odom.base_link

loads the trajectories of the transform chains "map to base_link" and "odom to base_link" from the topic /tf. Note that only tf2 is supported as the old tf is deprecated.

Note on ROS dependencies:

  • Loading pose-like topics from ROS1 or ROS2 bags with evo works on any platform without the need for a ROS installation.
  • Loading a TF trajectory requires either a ROS 1 or 2 distro, since this uses a TF buffer.
  • The TF loading feature is cross-compatible without the need to convert bagfiles between ROS versions:
    • evo_traj bag my_data.bag /tf:map.base_link works with ROS 1 & 2
    • evo_traj bag2 my_data /tf:map.base_link also works with ROS 1 & 2

More infos:

or run: rosmsg show geometry_msgs/PoseStamped (ROS2: ros2 interface show).


euroc - EuRoC MAV dataset format (also used in TUM VI dataset)

Every sequence of the EuRoC MAV dataset has .csv files with various ground truth information. For us, only the first columns with the ground truth's trajectory are important (timestamps, positions and orientations).

You can find these files in the sequence folder: <sequence>/mav0/state_groundtruth_estimate0/data.csv

This format only makes sense for these ground truth files because they have additional data (which we don't need). If you use the EuRoC dataset, you usually need to save the trajectory in another format like the TUM format (e.g. ORB-SLAM does it like that).

In euroc mode, evo's metrics require you to give the reference in the EuRoC format and the estimated trajectory in the TUM format.

More infos: http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets#the_euroc_mav_dataset

WARNING be careful with the EuRoC dataset coordinate frames (ground truth, IMU, camera...), because they have different axis conventions.


kitti - KITTI dataset pose format

This is actually not a real trajectory format because it has no timestamps - it only contains the poses in a text file. This means that you have to be careful when you want to compare two files in this format with a metric because the number of poses must be exactly the same.

Every row of the file contains the first 3 rows of a 4x4 homogeneous pose matrix (SE(3) matrix) flattened into one line, with each value separated by a space. For example, this pose matrix:

a b c d
e f g h
i j k l
0 0 0 1

will appear in the file as the row:

a b c d e f g h i j k l

More infos: http://www.cvlibs.net/datasets/kitti/eval_odometry.php


tum - TUM RGB-D dataset trajectory format

Every row has 8 entries containing timestamp (in seconds), position and orientation (as quaternion) with each value separated by a space:

timestamp x y z q_x q_y q_z q_w

More infos: https://vision.in.tum.de/data/datasets/rgbd-dataset/file_formats

NOTE: the TUM visual inertial dataset provides groundtruth data in a similar format like the EuRoC MAV dataset. It is not using the TUM RGB-D trajectory format for the groundtruth. With evo 1.13.4 or later you can use the euroc mode also for this dataset.


Saving / Exporting to other formats

In general, you can export trajectories to other formats with evo_traj using the --save_as_<other_format> options.

The following combinations are possible:

--save_as_bag --save_as_kitti --save_as_tum --save_as_bag2
bag yes yes yes yes
euroc yes yes yes yes
kitti no (no timestamps) yes no (no timestamps)* no (no timestamps)
tum yes yes yes yes
bag2 yes yes yes yes

*... but you can use this script together with the timestamp files of the KITTI dataset

exported ROS bag files will contain geometry_msgs/PoseStamped messages

Example:

# export a EuRoC groundtruth file to a TUM trajectory
evo_traj euroc data.csv --save_as_tum
# (will be saved as data.tum)

# export TUM trajectories to KITTI format
evo_traj tum traj_1.txt traj_2.txt traj_3.txt --save_as_kitti
# (will be saved as *.kitti)

# export TUM trajectories to ROS bagfile
evo_traj tum traj_1.txt traj_2.txt traj_3.txt --save_as_bag
# (will be saved as <timestamp>.bag with topics traj_1, traj_2 and traj_3)

# and so on...

There is no --save_as_euroc option because the EuRoC format only makes sense for the ground truth of the EuRoC dataset.

Note: Prior to version 1.0.5, there was a bug with the quaternions if TUM files were exported. Make sure your version is at least v1.0.5 with evo pkg --version or upgrade.


Result zip files for evo_res

These files generated by a metric with the --save_results option contain the data that is needed to compare different results with evo_res. They are just .zip files that contain a few .json files and .npy files for storing larger numpy arrays.

If you want, you can also store a backup of the trajectories that were used to generate the result in the .zip file. To do this automatically whenever you use --save_results, change the settings:

evo_config set save_traj_in_zip true

Note that this will increase the size of the files.