Secure your code as it's written. Use Snyk Code to scan source code in minutes - no build needed - and fix issues immediately.
def test_init_wrong_args(self):
path = helpers.fake_path(10)
# no args
with self.assertRaises(trajectory.TrajectoryException):
trajectory.PosePath3D()
# only quaternion
with self.assertRaises(trajectory.TrajectoryException):
trajectory.PosePath3D(
orientations_quat_wxyz=path.orientations_quat_wxyz)
# only xyz
with self.assertRaises(trajectory.TrajectoryException):
trajectory.PosePath3D(positions_xyz=path.positions_xyz)
import numpy as np
import matplotlib.pyplot as plt
logger = logging.getLogger("evo")
log.configure_logging(verbose=True)
traj_ref = file_interface.read_kitti_poses_file("../test/data/KITTI_00_gt.txt")
traj_est = file_interface.read_kitti_poses_file(
"../test/data/KITTI_00_ORB.txt")
# add artificial Sim(3) transformation
traj_est.transform(lie.se3(np.eye(3), [0, 0, 0]))
traj_est.scale(0.5)
logger.info("\nUmeyama alignment without scaling")
traj_est_aligned = trajectory.align_trajectory(traj_est, traj_ref)
logger.info("\nUmeyama alignment with scaling")
traj_est_aligned_scaled = trajectory.align_trajectory(traj_est, traj_ref,
correct_scale=True)
logger.info("\nUmeyama alignment with scaling only")
traj_est_aligned_only_scaled = trajectory.align_trajectory(
traj_est, traj_ref, correct_only_scale=True)
fig = plt.figure(figsize=(8, 8))
plot_mode = plot.PlotMode.xz
ax = plot.prepare_axis(fig, plot_mode, subplot_arg=221)
plot.traj(ax, plot_mode, traj_ref, '--', 'gray')
plot.traj(ax, plot_mode, traj_est, '-', 'blue')
fig.axes.append(ax)
logger = logging.getLogger("evo")
log.configure_logging(verbose=True)
traj_ref = file_interface.read_kitti_poses_file("../test/data/KITTI_00_gt.txt")
traj_est = file_interface.read_kitti_poses_file(
"../test/data/KITTI_00_ORB.txt")
# add artificial Sim(3) transformation
traj_est.transform(lie.se3(np.eye(3), [0, 0, 0]))
traj_est.scale(0.5)
logger.info("\nUmeyama alignment without scaling")
traj_est_aligned = trajectory.align_trajectory(traj_est, traj_ref)
logger.info("\nUmeyama alignment with scaling")
traj_est_aligned_scaled = trajectory.align_trajectory(traj_est, traj_ref,
correct_scale=True)
logger.info("\nUmeyama alignment with scaling only")
traj_est_aligned_only_scaled = trajectory.align_trajectory(
traj_est, traj_ref, correct_only_scale=True)
fig = plt.figure(figsize=(8, 8))
plot_mode = plot.PlotMode.xz
ax = plot.prepare_axis(fig, plot_mode, subplot_arg=221)
plot.traj(ax, plot_mode, traj_ref, '--', 'gray')
plot.traj(ax, plot_mode, traj_est, '-', 'blue')
fig.axes.append(ax)
plt.title('not aligned')
ax = plot.prepare_axis(fig, plot_mode, subplot_arg=222)
rpe_result.info["title"] = title
logger.debug(SEP)
logger.info(rpe_result.pretty_str())
# Restrict trajectories to delta ids for further processing steps.
if support_loop:
# Avoid overwriting if called repeatedly e.g. in Jupyter notebook.
import copy
traj_ref = copy.deepcopy(traj_ref)
traj_est = copy.deepcopy(traj_est)
traj_ref.reduce_to_ids(rpe_metric.delta_ids)
traj_est.reduce_to_ids(rpe_metric.delta_ids)
rpe_result.add_trajectory(ref_name, traj_ref)
rpe_result.add_trajectory(est_name, traj_est)
if isinstance(traj_est, trajectory.PoseTrajectory3D) and not all_pairs:
seconds_from_start = [
t - traj_est.timestamps[0] for t in traj_est.timestamps
]
rpe_result.add_np_array("seconds_from_start", seconds_from_start)
rpe_result.add_np_array("timestamps", traj_est.timestamps)
return rpe_result
"""
plot a path/trajectory based on xyz coordinates into an axis
:param axarr: an axis array (for x, y & z)
e.g. from 'fig, axarr = plt.subplots(3)'
:param traj: trajectory.PosePath3D or trajectory.PoseTrajectory3D object
:param style: matplotlib line style
:param color: matplotlib color
:param label: label (for legend)
:param alpha: alpha value for transparency
:param start_timestamp: optional start time of the reference
(for x-axis alignment)
"""
if len(axarr) != 3:
raise PlotException("expected an axis array with 3 subplots - got " +
str(len(axarr)))
if isinstance(traj, trajectory.PoseTrajectory3D):
if start_timestamp:
x = traj.timestamps - start_timestamp
else:
x = traj.timestamps
xlabel = "$t$ (s)"
else:
x = range(0, len(traj.positions_xyz))
xlabel = "index"
ylabels = ["$x$ (m)", "$y$ (m)", "$z$ (m)"]
for i in range(0, 3):
axarr[i].plot(x, traj.positions_xyz[:, i], style, color=color,
label=label, alpha=alpha)
axarr[i].set_ylabel(ylabels[i])
axarr[2].set_xlabel(xlabel)
if label:
axarr[0].legend(frameon=True)
if args.debug:
import pprint
logger.debug("main_parser config:\n" + pprint.pformat(
{arg: getattr(args, arg)
for arg in vars(args)}) + "\n")
logger.debug(SEP)
trajectories, ref_traj = load_trajectories(args)
if args.merge:
if args.subcommand == "kitti":
die("Can't merge KITTI files.")
if len(trajectories) == 0:
die("No trajectories to merge (excluding --ref).")
trajectories = {
"merged_trajectory": trajectory.merge(trajectories.values())
}
if args.transform_left or args.transform_right:
tf_type = "left" if args.transform_left else "right"
tf_path = args.transform_left \
if args.transform_left else args.transform_right
transform = file_interface.load_transform_json(tf_path)
logger.debug(SEP)
if not lie.is_se3(transform):
logger.warning("Not a valid SE(3) transformation!")
if args.invert_transform:
transform = lie.se3_inverse(transform)
logger.debug("Applying a {}-multiplicative transformation:\n{}".format(
tf_type, transform))
for traj in trajectories.values():
traj.transform(transform, right_mul=args.transform_right,
def rpe(traj_ref, traj_est, pose_relation, delta, delta_unit,
rel_delta_tol=0.1, all_pairs=False, align=False, correct_scale=False,
align_origin=False, ref_name="reference", est_name="estimate",
support_loop=False):
from evo.core import metrics
from evo.core import trajectory
# Align the trajectories.
only_scale = correct_scale and not align
if align or correct_scale:
logger.debug(SEP)
traj_est = trajectory.align_trajectory(traj_est, traj_ref,
correct_scale, only_scale)
elif align_origin:
logger.debug(SEP)
traj_est = trajectory.align_trajectory_origin(traj_est, traj_ref)
# Calculate RPE.
logger.debug(SEP)
data = (traj_ref, traj_est)
rpe_metric = metrics.RPE(pose_relation, delta, delta_unit, rel_delta_tol,
all_pairs)
rpe_metric.process_data(data)
title = str(rpe_metric)
if align and not correct_scale:
title += "\n(with SE(3) Umeyama alignment)"
elif align and correct_scale:
def trajectory_stats_to_df(traj, name=None):
if not isinstance(traj, trajectory.PosePath3D):
raise TypeError("trajectory.PosePath3D or derived required")
data_dict = {k: v for k, v in traj.get_infos().items() if np.isscalar(v)}
data_dict.update(traj.get_statistics())
index = [name] if name else [0]
return pd.DataFrame(data=data_dict, index=index)