v01
This commit is contained in:
107
scripts/eval_full/gen_results.py
Executable file
107
scripts/eval_full/gen_results.py
Executable file
@@ -0,0 +1,107 @@
|
||||
#!/usr/bin/env python3
|
||||
#
|
||||
# BSD 3-Clause License
|
||||
#
|
||||
# This file is part of the Basalt project.
|
||||
# https://gitlab.com/VladyslavUsenko/basalt.git
|
||||
#
|
||||
# Copyright (c) 2019-2021, Vladyslav Usenko and Nikolaus Demmel.
|
||||
# All rights reserved.
|
||||
#
|
||||
|
||||
import os
|
||||
import sys
|
||||
import json
|
||||
|
||||
|
||||
datasets = ['Seq.', 'MH_01_easy', 'MH_02_easy', 'MH_03_medium', 'MH_04_difficult',
|
||||
'MH_05_difficult', 'V1_01_easy', 'V1_02_medium',
|
||||
'V1_03_difficult', 'V2_01_easy', 'V2_02_medium']
|
||||
|
||||
|
||||
# Other results.
|
||||
|
||||
|
||||
vio = {
|
||||
'ate' : ['VIO RMS ATE [m]'],
|
||||
'time' : ['VIO Time [s]'],
|
||||
'num_frames' : ['VIO Num. Frames']
|
||||
}
|
||||
|
||||
mapping = {
|
||||
'ate' : ['MAP RMS ATE [m]'],
|
||||
'time' : ['MAP Time [s]'],
|
||||
'num_frames' : ['MAP Num. KFs']
|
||||
}
|
||||
|
||||
pose_graph = {
|
||||
'ate' : ['PG RMS ATE [m]'],
|
||||
'time' : ['PG Time [s]'],
|
||||
'num_frames' : ['PG Num. KFs']
|
||||
}
|
||||
|
||||
pure_ba = {
|
||||
'ate' : ['PG RMS ATE [m]'],
|
||||
'time' : ['PG Time [s]'],
|
||||
'num_frames' : ['PG Num. KFs']
|
||||
}
|
||||
|
||||
out_dir = sys.argv[1]
|
||||
|
||||
def load_data(x, prefix, key):
|
||||
fname = out_dir + '/' + prefix + '_' + key
|
||||
if os.path.isfile(fname):
|
||||
with open(fname, 'r') as f:
|
||||
j = json.load(f)
|
||||
res = round(j['rms_ate'], 3)
|
||||
x['ate'].append(float(res))
|
||||
x['time'].append(round(j['exec_time_ns']*1e-9, 3))
|
||||
x['num_frames'].append(j['num_frames'])
|
||||
else:
|
||||
x['ate'].append(float('Inf'))
|
||||
x['time'].append(float('Inf'))
|
||||
x['num_frames'].append(float('Inf'))
|
||||
|
||||
|
||||
for key in datasets[1:]:
|
||||
load_data(vio, 'vio', key)
|
||||
load_data(mapping, 'mapper', key)
|
||||
load_data(pose_graph, 'mapper_no_weights', key)
|
||||
load_data(pure_ba, 'mapper_no_factors', key)
|
||||
|
||||
|
||||
row_format ="{:>17}" + "{:>13}" * (len(datasets)-1)
|
||||
|
||||
datasets_short = [x[:5] for x in datasets]
|
||||
|
||||
print('\nVisual-Inertial Odometry')
|
||||
print(row_format.format(*datasets_short))
|
||||
|
||||
print(row_format.format(*vio['ate']))
|
||||
#print(row_format.format(*vio['time']))
|
||||
print(row_format.format(*vio['num_frames']))
|
||||
|
||||
print('\nVisual-Inertial Mapping')
|
||||
print(row_format.format(*datasets_short))
|
||||
|
||||
print(row_format.format(*mapping['ate']))
|
||||
#print(row_format.format(*mapping['time']))
|
||||
print(row_format.format(*mapping['num_frames']))
|
||||
|
||||
|
||||
print('\nPose-Graph optimization (Identity weights for all factors)')
|
||||
print(row_format.format(*datasets_short))
|
||||
|
||||
print(row_format.format(*pose_graph['ate']))
|
||||
#print(row_format.format(*pose_graph['time']))
|
||||
print(row_format.format(*pose_graph['num_frames']))
|
||||
|
||||
|
||||
print('\nPure BA optimization (no factors from the recovery used)')
|
||||
print(row_format.format(*datasets_short))
|
||||
|
||||
print(row_format.format(*pure_ba['ate']))
|
||||
#print(row_format.format(*pure_ba['time']))
|
||||
print(row_format.format(*pure_ba['num_frames']))
|
||||
|
||||
|
||||
83
scripts/eval_full/gen_results_kitti.py
Executable file
83
scripts/eval_full/gen_results_kitti.py
Executable file
@@ -0,0 +1,83 @@
|
||||
#!/usr/bin/env python3
|
||||
#
|
||||
# BSD 3-Clause License
|
||||
#
|
||||
# This file is part of the Basalt project.
|
||||
# https://gitlab.com/VladyslavUsenko/basalt.git
|
||||
#
|
||||
# Copyright (c) 2019-2021, Vladyslav Usenko and Nikolaus Demmel.
|
||||
# All rights reserved.
|
||||
#
|
||||
|
||||
import os
|
||||
import sys
|
||||
import json
|
||||
|
||||
|
||||
datasets = ['Seq.', '00', '02', '03','04', '05', '06','07', '08', '09', '10']
|
||||
lengths = [100, 200, 300, 400, 500, 600, 700, 800]
|
||||
|
||||
# Other results.
|
||||
|
||||
|
||||
vo = {
|
||||
'trans_error': {},
|
||||
'rot_error': {}
|
||||
}
|
||||
|
||||
for l in lengths:
|
||||
vo['trans_error'][l] = ['Trans. error [%] ' + str(l) + 'm.']
|
||||
vo['rot_error'][l] = ['Rot. error [deg/m] ' + str(l) + 'm.']
|
||||
|
||||
|
||||
out_dir = sys.argv[1]
|
||||
|
||||
mean_values = {
|
||||
'mean_trans_error' : 0.0,
|
||||
'mean_rot_error' : 0.0,
|
||||
'total_num_meas' : 0.0
|
||||
}
|
||||
|
||||
def load_data(x, prefix, key, mean_values):
|
||||
fname = out_dir + '/' + prefix + '_' + key + '.txt'
|
||||
if os.path.isfile(fname):
|
||||
with open(fname, 'r') as f:
|
||||
j = json.load(f)
|
||||
res = j['results']
|
||||
for v in lengths:
|
||||
num_meas = res[str(v)]['num_meas']
|
||||
trans_error = res[str(v)]['trans_error']
|
||||
rot_error = res[str(v)]['rot_error']
|
||||
x['trans_error'][int(v)].append(round(trans_error, 5))
|
||||
x['rot_error'][int(v)].append(round(rot_error, 5))
|
||||
if num_meas > 0:
|
||||
mean_values['mean_trans_error'] += trans_error*num_meas
|
||||
mean_values['mean_rot_error'] += rot_error*num_meas
|
||||
mean_values['total_num_meas'] += num_meas
|
||||
else:
|
||||
for v in lengths:
|
||||
x['trans_error'][int(v)].append(float('inf'))
|
||||
x['rot_error'][int(v)].append(float('inf'))
|
||||
|
||||
for key in datasets[1:]:
|
||||
load_data(vo, 'rpe', key, mean_values)
|
||||
|
||||
|
||||
row_format ="{:>24}" + "{:>10}" * (len(datasets)-1)
|
||||
|
||||
datasets_short = [x[:5] for x in datasets]
|
||||
|
||||
print('\nVisual Odometry (Stereo)')
|
||||
print(row_format.format(*datasets_short))
|
||||
|
||||
for l in lengths:
|
||||
print(row_format.format(*(vo['trans_error'][l])))
|
||||
|
||||
print()
|
||||
|
||||
for l in lengths:
|
||||
print(row_format.format(*(vo['rot_error'][l])))
|
||||
|
||||
|
||||
print('Mean translation error [%] ', mean_values['mean_trans_error']/mean_values['total_num_meas'])
|
||||
print('Mean rotation error [deg/m] ', mean_values['mean_rot_error']/mean_values['total_num_meas'])
|
||||
62
scripts/eval_full/gen_results_tumvi.py
Executable file
62
scripts/eval_full/gen_results_tumvi.py
Executable file
@@ -0,0 +1,62 @@
|
||||
#!/usr/bin/env python3
|
||||
#
|
||||
# BSD 3-Clause License
|
||||
#
|
||||
# This file is part of the Basalt project.
|
||||
# https://gitlab.com/VladyslavUsenko/basalt.git
|
||||
#
|
||||
# Copyright (c) 2019-2021, Vladyslav Usenko and Nikolaus Demmel.
|
||||
# All rights reserved.
|
||||
#
|
||||
|
||||
import os
|
||||
import sys
|
||||
import json
|
||||
|
||||
|
||||
datasets = ['Seq.', 'dataset-corridor1_512_16', 'dataset-magistrale1_512_16', 'dataset-room1_512_16', 'dataset-slides1_512_16']
|
||||
|
||||
# Other results.
|
||||
|
||||
|
||||
vio = {
|
||||
'ate' : ['VIO RMS ATE [m]'],
|
||||
'time' : ['VIO Time [s]'],
|
||||
'num_frames' : ['VIO Num. Frames']
|
||||
}
|
||||
|
||||
out_dir = sys.argv[1]
|
||||
|
||||
def load_data(x, prefix, key):
|
||||
fname = out_dir + '/' + prefix + '_' + key
|
||||
if os.path.isfile(fname):
|
||||
with open(fname, 'r') as f:
|
||||
j = json.load(f)
|
||||
res = round(j['rms_ate'], 3)
|
||||
x['ate'].append(float(res))
|
||||
x['time'].append(round(j['exec_time_ns']*1e-9, 3))
|
||||
x['num_frames'].append(j['num_frames'])
|
||||
else:
|
||||
x['ate'].append(float('Inf'))
|
||||
x['time'].append(float('Inf'))
|
||||
x['num_frames'].append(float('Inf'))
|
||||
|
||||
|
||||
for key in datasets[1:]:
|
||||
load_data(vio, 'vio', key)
|
||||
|
||||
|
||||
row_format ="{:>17}" + "{:>13}" * (len(datasets)-1)
|
||||
|
||||
datasets_short = [x[8:].split('_')[0] for x in datasets]
|
||||
|
||||
print('\nVisual-Inertial Odometry')
|
||||
print(row_format.format(*datasets_short))
|
||||
|
||||
print(row_format.format(*vio['ate']))
|
||||
#print(row_format.format(*vio['time']))
|
||||
print(row_format.format(*vio['num_frames']))
|
||||
|
||||
|
||||
|
||||
|
||||
44
scripts/eval_full/run_evaluations.sh
Executable file
44
scripts/eval_full/run_evaluations.sh
Executable file
@@ -0,0 +1,44 @@
|
||||
#!/bin/bash
|
||||
##
|
||||
## BSD 3-Clause License
|
||||
##
|
||||
## This file is part of the Basalt project.
|
||||
## https://gitlab.com/VladyslavUsenko/basalt.git
|
||||
##
|
||||
## Copyright (c) 2019-2021, Vladyslav Usenko and Nikolaus Demmel.
|
||||
## All rights reserved.
|
||||
##
|
||||
|
||||
set -e
|
||||
set -x
|
||||
|
||||
DATASET_PATH=/data/euroc
|
||||
|
||||
DATASETS=(MH_01_easy MH_02_easy MH_03_medium MH_04_difficult MH_05_difficult V1_01_easy V1_02_medium V1_03_difficult V2_01_easy V2_02_medium)
|
||||
|
||||
|
||||
folder_name=eval_results
|
||||
mkdir $folder_name
|
||||
|
||||
|
||||
|
||||
for d in ${DATASETS[$CI_NODE_INDEX-1]}; do
|
||||
basalt_vio --dataset-path $DATASET_PATH/$d --cam-calib /usr/etc/basalt/euroc_eucm_calib.json \
|
||||
--dataset-type euroc --show-gui 0 --config-path /usr/etc/basalt/euroc_config.json \
|
||||
--result-path $folder_name/vio_$d --marg-data eval_tmp_marg_data --save-trajectory tum
|
||||
|
||||
mv trajectory.txt $folder_name/traj_vio_$d.txt
|
||||
|
||||
basalt_mapper --show-gui 0 --cam-calib /usr/etc/basalt/euroc_eucm_calib.json --config-path /usr/etc/basalt/euroc_config.json --marg-data eval_tmp_marg_data \
|
||||
--result-path $folder_name/mapper_$d
|
||||
|
||||
basalt_mapper --show-gui 0 --cam-calib /usr/etc/basalt/euroc_eucm_calib.json --config-path /usr/etc/basalt/euroc_config_no_weights.json --marg-data eval_tmp_marg_data \
|
||||
--result-path $folder_name/mapper_no_weights_$d
|
||||
|
||||
basalt_mapper --show-gui 0 --cam-calib /usr/etc/basalt/euroc_eucm_calib.json --config-path /usr/etc/basalt/euroc_config_no_factors.json --marg-data eval_tmp_marg_data \
|
||||
--result-path $folder_name/mapper_no_factors_$d
|
||||
|
||||
rm -rf eval_tmp_marg_data
|
||||
done
|
||||
|
||||
#./gen_results.py $folder_name > euroc_results.txt
|
||||
33
scripts/eval_full/run_evaluations_kitti.sh
Executable file
33
scripts/eval_full/run_evaluations_kitti.sh
Executable file
@@ -0,0 +1,33 @@
|
||||
#!/bin/bash
|
||||
##
|
||||
## BSD 3-Clause License
|
||||
##
|
||||
## This file is part of the Basalt project.
|
||||
## https://gitlab.com/VladyslavUsenko/basalt.git
|
||||
##
|
||||
## Copyright (c) 2019-2021, Vladyslav Usenko and Nikolaus Demmel.
|
||||
## All rights reserved.
|
||||
##
|
||||
|
||||
set -e
|
||||
set -x
|
||||
|
||||
DATASET_PATH=/data/kitti_odom_grey/sequences
|
||||
|
||||
DATASETS=(00 02 03 04 05 06 07 08 09 10)
|
||||
|
||||
|
||||
folder_name=eval_results_kitti
|
||||
mkdir $folder_name
|
||||
|
||||
for d in ${DATASETS[$CI_NODE_INDEX-1]}; do
|
||||
echo $d
|
||||
basalt_vio --dataset-path $DATASET_PATH/$d --cam-calib $DATASET_PATH/$d/basalt_calib.json \
|
||||
--dataset-type kitti --show-gui 0 --config-path /usr/etc/basalt/kitti_config.json --result-path $folder_name/vo_$d --save-trajectory kitti --use-imu 0
|
||||
|
||||
mv trajectory_kitti.txt $folder_name/kitti_$d.txt
|
||||
|
||||
basalt_kitti_eval --traj-path $folder_name/kitti_$d.txt --gt-path $DATASET_PATH/$d/poses.txt --result-path $folder_name/rpe_$d.txt
|
||||
|
||||
done
|
||||
|
||||
39
scripts/eval_full/run_evaluations_tumvi.sh
Executable file
39
scripts/eval_full/run_evaluations_tumvi.sh
Executable file
@@ -0,0 +1,39 @@
|
||||
#!/bin/bash
|
||||
##
|
||||
## BSD 3-Clause License
|
||||
##
|
||||
## This file is part of the Basalt project.
|
||||
## https://gitlab.com/VladyslavUsenko/basalt.git
|
||||
##
|
||||
## Copyright (c) 2019-2021, Vladyslav Usenko and Nikolaus Demmel.
|
||||
## All rights reserved.
|
||||
##
|
||||
|
||||
set -e
|
||||
set -x
|
||||
|
||||
DATASET_PATH=/data/tumvi/512_16/
|
||||
|
||||
DATASETS=(
|
||||
dataset-corridor1_512_16
|
||||
dataset-magistrale1_512_16
|
||||
dataset-room1_512_16
|
||||
dataset-slides1_512_16
|
||||
)
|
||||
|
||||
|
||||
folder_name=eval_results_tumvi
|
||||
mkdir $folder_name
|
||||
|
||||
|
||||
|
||||
for d in ${DATASETS[$CI_NODE_INDEX-1]}; do
|
||||
basalt_vio --dataset-path $DATASET_PATH/$d --cam-calib /usr/etc/basalt/tumvi_512_eucm_calib.json \
|
||||
--dataset-type euroc --show-gui 0 --config-path /usr/etc/basalt/tumvi_512_config.json \
|
||||
--result-path $folder_name/vio_$d --save-trajectory tum
|
||||
|
||||
mv trajectory.txt $folder_name/${d}_basalt_poses.txt
|
||||
|
||||
done
|
||||
|
||||
#./gen_results_tumvi.py $folder_name > euroc_tumvi.txt
|
||||
Reference in New Issue
Block a user