-
Notifications
You must be signed in to change notification settings - Fork 758
Metrics
These built-in command line apps let you evaluate estimated trajectories against a reference (ground truth):
evo_ape
evo_rpe
Conceptually, the command syntax is as follows:
command format reference-trajectory estimated-trajectory [options]
where format
indicates one of the supported trajectory formats - see here for more infos on the different formats.
In case of a ROS bagfile, the syntax is slightly different:
command bag bagfile-path reference-topic estimated-topic [options]
TF topics are also supported, see here.
For more details on the command line interfaces, use the --help
flag - e.g. evo_rpe euroc --help
.
A good start to get a feeling for the concepts behind the apps is the interactive Jupyter notebook metrics_tutorial.ipynb
that you can find here.
Very simple Bash-script demos for the command line apps that show examples for different use cases are also provided in the repository, see here.
You can use Umeyama alignment as a pre-processing step:
-
--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
Scale or Sim(3) alignment is usually required for monocular SLAM, where you usually have random scale. SE(3) alignment is useful for the absolute pose error (evo_ape
) if you want to measure the shape similarity of trajectories as best as possible. The alignment_demo.py script shows the different types of alignment with an example trajectory (as shown in the evo_traj
documentation).
New since v1.5.0:
A simple origin alignment that can be useful for drift/loop closure evaluation is available with --align_origin
. This is not based on the Umeyama algorithm.
3D trajectories can be projected to 2D before errors are calculated. This works the same as in evo_traj via --project_to_plane {xy, xz, yz}
, see the section there for details.
Data can be downsampled and motion-filtered. This works the same as in evo_traj, see the section there for details.
Absolute pose error, often used as absolute trajectory error. Corresponding poses are directly compared between estimate and reference given a pose relation. Then, statistics for the whole trajectory are calculated. This is useful to test the global consistency of a trajectory.
Example:
evo_ape tum reference.txt estimate.txt --align
Append --help
to the command to see all available options.
Instead of a direct comparison of absolute poses, the relative pose error compares motions ("pose deltas"). This metric gives insights about the local accuracy, i.e. the drift. For example, the translational or rotational drift per meter can be evaluated:
evo_rpe tum reference.txt estimate.txt --pose_relation angle_deg --delta 1 --delta_unit m
Relative pose pairs are consecutive unless --all_pairs
is specified. Then, overlapping relative pose pairs are used.
Append --help
to the command to see all available options.