Skip to content

Commit 2f882c8

Browse files
committed
Remove file interface
1 parent 1a6ea0f commit 2f882c8

File tree

4 files changed

+369
-6
lines changed

4 files changed

+369
-6
lines changed

evaluation_script/__init__.py

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -162,10 +162,8 @@ def version_to_tuple(version):
162162
from evo.core.trajectory import Plane
163163
from evo.core.metrics import PoseRelation, Unit
164164
# from evo.tools import file_interface
165-
import evo.main_ape as main_ape
166-
import evo.main_rpe as main_rpe
167-
168-
165+
# import evo.main_ape as main_ape
166+
# import evo.main_rpe as main_rpe
169167

170168
# print("✅ evo is installed and available.")
171169
# except subprocess.CalledProcessError as e:

evaluation_script/evo_ape_fork.py

Lines changed: 170 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,170 @@
1+
#!/usr/bin/env python
2+
# -*- coding: UTF8 -*-
3+
# PYTHON_ARGCOMPLETE_OK
4+
"""
5+
Main executable for calculating the absolute pose error (APE) metric.
6+
author: Michael Grupp
7+
8+
This file is part of evo (github.com/MichaelGrupp/evo).
9+
10+
evo is free software: you can redistribute it and/or modify
11+
it under the terms of the GNU General Public License as published by
12+
the Free Software Foundation, either version 3 of the License, or
13+
(at your option) any later version.
14+
15+
evo is distributed in the hope that it will be useful,
16+
but WITHOUT ANY WARRANTY; without even the implied warranty of
17+
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18+
GNU General Public License for more details.
19+
20+
You should have received a copy of the GNU General Public License
21+
along with evo. If not, see <http://www.gnu.org/licenses/>.
22+
"""
23+
24+
import argparse
25+
import logging
26+
import typing
27+
28+
import numpy as np
29+
30+
import evo.common_ape_rpe as common
31+
from evo.core import lie_algebra, sync, metrics
32+
from evo.core.result import Result
33+
from evo.core.trajectory import PosePath3D, PoseTrajectory3D, Plane
34+
from evo.tools import log
35+
from evo.tools.settings import SETTINGS
36+
37+
logger = logging.getLogger(__name__)
38+
39+
SEP = "-" * 80 # separator line
40+
41+
42+
def ape(traj_ref: PosePath3D, traj_est: PosePath3D,
43+
pose_relation: metrics.PoseRelation, align: bool = False,
44+
correct_scale: bool = False, n_to_align: int = -1,
45+
align_origin: bool = False, ref_name: str = "reference",
46+
est_name: str = "estimate",
47+
change_unit: typing.Optional[metrics.Unit] = None,
48+
project_to_plane: typing.Optional[Plane] = None) -> Result:
49+
50+
# Align the trajectories.
51+
only_scale = correct_scale and not align
52+
alignment_transformation = None
53+
if align or correct_scale:
54+
logger.debug(SEP)
55+
alignment_transformation = lie_algebra.sim3(
56+
*traj_est.align(traj_ref, correct_scale, only_scale, n=n_to_align))
57+
if align_origin:
58+
logger.debug(SEP)
59+
alignment_transformation = traj_est.align_origin(traj_ref)
60+
61+
# Projection is done after potential 3D alignment & transformation steps.
62+
if project_to_plane:
63+
logger.debug(SEP)
64+
logger.debug("Projecting trajectories to %s plane.",
65+
project_to_plane.value)
66+
traj_ref.project(project_to_plane)
67+
traj_est.project(project_to_plane)
68+
69+
# Calculate APE.
70+
logger.debug(SEP)
71+
data = (traj_ref, traj_est)
72+
ape_metric = metrics.APE(pose_relation)
73+
ape_metric.process_data(data)
74+
75+
if change_unit:
76+
ape_metric.change_unit(change_unit)
77+
78+
title = str(ape_metric)
79+
if align and not correct_scale:
80+
title += "\n(with SE(3) Umeyama alignment)"
81+
elif align and correct_scale:
82+
title += "\n(with Sim(3) Umeyama alignment)"
83+
elif only_scale:
84+
title += "\n(scale corrected)"
85+
elif not align_origin:
86+
title += "\n(not aligned)"
87+
if (align or correct_scale) and n_to_align != -1:
88+
title += " (aligned poses: {})".format(n_to_align)
89+
if align_origin:
90+
title += "\n(with origin alignment)"
91+
92+
if project_to_plane:
93+
title += f"\n(projected to {project_to_plane.value} plane)"
94+
95+
ape_result = ape_metric.get_result(ref_name, est_name)
96+
ape_result.info["title"] = title
97+
98+
logger.debug(SEP)
99+
logger.info(ape_result.pretty_str())
100+
101+
ape_result.add_trajectory(ref_name, traj_ref)
102+
ape_result.add_trajectory(est_name, traj_est)
103+
if isinstance(traj_est, PoseTrajectory3D):
104+
seconds_from_start = np.array(
105+
[t - traj_est.timestamps[0] for t in traj_est.timestamps])
106+
ape_result.add_np_array("seconds_from_start", seconds_from_start)
107+
ape_result.add_np_array("timestamps", traj_est.timestamps)
108+
ape_result.add_np_array("distances_from_start", traj_ref.distances)
109+
ape_result.add_np_array("distances", traj_est.distances)
110+
111+
if alignment_transformation is not None:
112+
ape_result.add_np_array("alignment_transformation_sim3",
113+
alignment_transformation)
114+
115+
return ape_result
116+
117+
118+
def run(args: argparse.Namespace) -> None:
119+
log.configure_logging(args.verbose, args.silent, args.debug,
120+
local_logfile=args.logfile)
121+
if args.debug:
122+
from pprint import pformat
123+
parser_str = pformat({arg: getattr(args, arg) for arg in vars(args)})
124+
logger.debug("main_parser config:\n{}".format(parser_str))
125+
logger.debug(SEP)
126+
127+
traj_ref, traj_est, ref_name, est_name = common.load_trajectories(args)
128+
pose_relation = common.get_pose_relation(args)
129+
change_unit = metrics.Unit(args.change_unit) if args.change_unit else None
130+
plane = Plane(args.project_to_plane) if args.project_to_plane else None
131+
132+
traj_ref_full = None
133+
if args.plot_full_ref:
134+
import copy
135+
traj_ref_full = copy.deepcopy(traj_ref)
136+
137+
# Downsample or filtering has to be done before synchronization.
138+
# Otherwise filtering might mess up the sync.
139+
common.downsample_or_filter(args, traj_ref, traj_est)
140+
141+
if isinstance(traj_ref, PoseTrajectory3D) and isinstance(
142+
traj_est, PoseTrajectory3D):
143+
logger.debug(SEP)
144+
if args.t_start or args.t_end:
145+
if args.t_start:
146+
logger.info("Using time range start: {}s".format(args.t_start))
147+
if args.t_end:
148+
logger.info("Using time range end: {}s".format(args.t_end))
149+
traj_ref.reduce_to_time_range(args.t_start, args.t_end)
150+
logger.debug("Synchronizing trajectories...")
151+
traj_ref, traj_est = sync.associate_trajectories(
152+
traj_ref, traj_est, args.t_max_diff, args.t_offset,
153+
first_name=ref_name, snd_name=est_name)
154+
155+
result = ape(traj_ref=traj_ref, traj_est=traj_est,
156+
pose_relation=pose_relation, align=args.align,
157+
correct_scale=args.correct_scale, n_to_align=args.n_to_align,
158+
align_origin=args.align_origin, ref_name=ref_name,
159+
est_name=est_name, change_unit=change_unit,
160+
project_to_plane=plane)
161+
162+
if args.plot or args.save_plot or args.serialize_plot:
163+
common.plot_result(args, result, traj_ref,
164+
result.trajectories[est_name],
165+
traj_ref_full=traj_ref_full)
166+
167+
168+
if __name__ == '__main__':
169+
from evo import entry_points
170+
entry_points.ape()

evaluation_script/evo_rpe_fork.py

Lines changed: 193 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,193 @@
1+
#!/usr/bin/env python
2+
# -*- coding: UTF8 -*-
3+
# PYTHON_ARGCOMPLETE_OK
4+
"""
5+
Main executable for calculating the relative pose error (RPE) metric.
6+
author: Michael Grupp
7+
8+
This file is part of evo (github.com/MichaelGrupp/evo).
9+
10+
evo is free software: you can redistribute it and/or modify
11+
it under the terms of the GNU General Public License as published by
12+
the Free Software Foundation, either version 3 of the License, or
13+
(at your option) any later version.
14+
15+
evo is distributed in the hope that it will be useful,
16+
but WITHOUT ANY WARRANTY; without even the implied warranty of
17+
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18+
GNU General Public License for more details.
19+
20+
You should have received a copy of the GNU General Public License
21+
along with evo. If not, see <http://www.gnu.org/licenses/>.
22+
"""
23+
24+
import argparse
25+
import logging
26+
import typing
27+
28+
import numpy as np
29+
30+
import evo.common_ape_rpe as common
31+
from evo.core import lie_algebra, sync, metrics
32+
from evo.core.result import Result
33+
from evo.core.trajectory import PosePath3D, PoseTrajectory3D, Plane
34+
from evo.tools import log
35+
from evo.tools.settings import SETTINGS
36+
37+
logger = logging.getLogger(__name__)
38+
39+
SEP = "-" * 80 # separator line
40+
41+
42+
def rpe(traj_ref: PosePath3D, traj_est: PosePath3D,
43+
pose_relation: metrics.PoseRelation, delta: float,
44+
delta_unit: metrics.Unit, rel_delta_tol: float = 0.1,
45+
all_pairs: bool = False, pairs_from_reference: bool = False,
46+
align: bool = False, correct_scale: bool = False, n_to_align: int = -1,
47+
align_origin: bool = False, ref_name: str = "reference",
48+
est_name: str = "estimate", support_loop: bool = False,
49+
change_unit: typing.Optional[metrics.Unit] = None,
50+
project_to_plane: typing.Optional[Plane] = None) -> Result:
51+
52+
# Align the trajectories.
53+
only_scale = correct_scale and not align
54+
alignment_transformation = None
55+
if align or correct_scale:
56+
logger.debug(SEP)
57+
alignment_transformation = lie_algebra.sim3(
58+
*traj_est.align(traj_ref, correct_scale, only_scale, n=n_to_align))
59+
if align_origin:
60+
logger.debug(SEP)
61+
alignment_transformation = traj_est.align_origin(traj_ref)
62+
63+
# Projection is done after potential 3D alignment & transformation steps.
64+
if project_to_plane:
65+
logger.debug(SEP)
66+
logger.debug("Projecting trajectories to %s plane.",
67+
project_to_plane.value)
68+
traj_ref.project(project_to_plane)
69+
traj_est.project(project_to_plane)
70+
71+
# Calculate RPE.
72+
logger.debug(SEP)
73+
data = (traj_ref, traj_est)
74+
rpe_metric = metrics.RPE(pose_relation, delta, delta_unit, rel_delta_tol,
75+
all_pairs, pairs_from_reference)
76+
rpe_metric.process_data(data)
77+
78+
if change_unit:
79+
rpe_metric.change_unit(change_unit)
80+
81+
title = str(rpe_metric)
82+
if align and not correct_scale:
83+
title += "\n(with SE(3) Umeyama alignment)"
84+
elif align and correct_scale:
85+
title += "\n(with Sim(3) Umeyama alignment)"
86+
elif only_scale:
87+
title += "\n(scale corrected)"
88+
elif not align_origin:
89+
title += "\n(not aligned)"
90+
if (align or correct_scale) and n_to_align != -1:
91+
title += " (aligned poses: {})".format(n_to_align)
92+
if align_origin:
93+
title += "\n(with origin alignment)"
94+
95+
if project_to_plane:
96+
title += f"\n(projected to {project_to_plane.value} plane)"
97+
98+
rpe_result = rpe_metric.get_result(ref_name, est_name)
99+
rpe_result.info["title"] = title
100+
logger.debug(SEP)
101+
logger.info(rpe_result.pretty_str())
102+
103+
# Restrict trajectories to delta ids for further processing steps.
104+
if support_loop:
105+
# Avoid overwriting if called repeatedly e.g. in Jupyter notebook.
106+
import copy
107+
traj_ref = copy.deepcopy(traj_ref)
108+
traj_est = copy.deepcopy(traj_est)
109+
# Note: the pose at index 0 is added for plotting purposes, although it has
110+
# no RPE value assigned to it since it has no previous pose.
111+
# (for each pair (i, j), the 'delta_ids' represent only j)
112+
delta_ids_with_first_pose = [0] + rpe_metric.delta_ids
113+
traj_ref.reduce_to_ids(delta_ids_with_first_pose)
114+
traj_est.reduce_to_ids(delta_ids_with_first_pose)
115+
rpe_result.add_trajectory(ref_name, traj_ref)
116+
rpe_result.add_trajectory(est_name, traj_est)
117+
118+
if isinstance(traj_est, PoseTrajectory3D):
119+
seconds_from_start = np.array(
120+
[t - traj_est.timestamps[0] for t in traj_est.timestamps])
121+
# Save times/distances of each calculated value.
122+
# Note: here the first index needs that was added before needs to be
123+
# ignored again as it's not relevant for the values (see above).
124+
rpe_result.add_np_array("seconds_from_start", seconds_from_start[1:])
125+
rpe_result.add_np_array("timestamps", traj_est.timestamps[1:])
126+
rpe_result.add_np_array("distances_from_start", traj_ref.distances[1:])
127+
rpe_result.add_np_array("distances", traj_est.distances[1:])
128+
129+
if alignment_transformation is not None:
130+
rpe_result.add_np_array("alignment_transformation_sim3",
131+
alignment_transformation)
132+
133+
return rpe_result
134+
135+
136+
def run(args: argparse.Namespace) -> None:
137+
138+
log.configure_logging(args.verbose, args.silent, args.debug,
139+
local_logfile=args.logfile)
140+
if args.debug:
141+
from pprint import pformat
142+
parser_str = pformat({arg: getattr(args, arg) for arg in vars(args)})
143+
logger.debug("main_parser config:\n{}".format(parser_str))
144+
logger.debug(SEP)
145+
146+
traj_ref, traj_est, ref_name, est_name = common.load_trajectories(args)
147+
pose_relation = common.get_pose_relation(args)
148+
delta_unit = common.get_delta_unit(args)
149+
change_unit = metrics.Unit(args.change_unit) if args.change_unit else None
150+
plane = Plane(args.project_to_plane) if args.project_to_plane else None
151+
152+
traj_ref_full = None
153+
if args.plot_full_ref:
154+
import copy
155+
traj_ref_full = copy.deepcopy(traj_ref)
156+
157+
# Downsample or filtering has to be done before synchronization.
158+
# Otherwise filtering might mess up the sync.
159+
common.downsample_or_filter(args, traj_ref, traj_est)
160+
161+
if isinstance(traj_ref, PoseTrajectory3D) and isinstance(
162+
traj_est, PoseTrajectory3D):
163+
logger.debug(SEP)
164+
if args.t_start or args.t_end:
165+
if args.t_start:
166+
logger.info("Using time range start: {}s".format(args.t_start))
167+
if args.t_end:
168+
logger.info("Using time range end: {}s".format(args.t_end))
169+
traj_ref.reduce_to_time_range(args.t_start, args.t_end)
170+
logger.debug("Synchronizing trajectories...")
171+
traj_ref, traj_est = sync.associate_trajectories(
172+
traj_ref, traj_est, args.t_max_diff, args.t_offset,
173+
first_name=ref_name, snd_name=est_name)
174+
175+
result = rpe(traj_ref=traj_ref, traj_est=traj_est,
176+
pose_relation=pose_relation, delta=args.delta,
177+
delta_unit=delta_unit, rel_delta_tol=args.delta_tol,
178+
all_pairs=args.all_pairs,
179+
pairs_from_reference=args.pairs_from_reference,
180+
align=args.align, correct_scale=args.correct_scale,
181+
n_to_align=args.n_to_align, align_origin=args.align_origin,
182+
ref_name=ref_name, est_name=est_name, change_unit=change_unit,
183+
project_to_plane=plane)
184+
185+
if args.plot or args.save_plot or args.serialize_plot:
186+
common.plot_result(args, result, traj_ref,
187+
result.trajectories[est_name],
188+
traj_ref_full=traj_ref_full)
189+
190+
191+
if __name__ == '__main__':
192+
from evo import entry_points
193+
entry_points.rpe()

evaluation_script/evo_script.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,10 @@
1212
from evo.core.trajectory import Plane
1313
from evo.core.metrics import PoseRelation, Unit
1414
# from evo.tools import file_interface
15-
import evo.main_ape as main_ape
16-
import evo.main_rpe as main_rpe
15+
# import evo.main_ape as main_ape
16+
# import evo.main_rpe as main_rpe
17+
from .evo_ape_fork import main_ape
18+
from .evo_rpe_fork import main_rpe
1719
class FileInterfaceException(Exception):
1820
pass
1921

0 commit comments

Comments
 (0)