def test_init_wrong_args(self): # no args with self.assertRaises(trajectory.TrajectoryException): trajectory.PosePath3D() # only quaternion with self.assertRaises(trajectory.TrajectoryException): trajectory.PosePath3D( orientations_quat_wxyz=ex_tum_traj.orientations_quat_wxyz) # only xyz with self.assertRaises(trajectory.TrajectoryException): trajectory.PosePath3D(positions_xyz=ex_tum_traj.positions_xyz)
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)
def test_init_correct(self): # only poses_se3 path = helpers.fake_path(10) try: trajectory.PosePath3D(poses_se3=path.poses_se3) except trajectory.TrajectoryException: self.fail("unexpected init failure with only poses_se3") # xyz + quaternion try: trajectory.PosePath3D(path.positions_xyz, path.orientations_quat_wxyz) except trajectory.TrajectoryException: self.fail("unexpected init failure with xyz + quaternion") # all try: trajectory.PosePath3D(path.positions_xyz, path.orientations_quat_wxyz, path.poses_se3) except trajectory.TrajectoryException: self.fail( "unexpected init failure with xyz + quaternion + poses_se3")
def test_init_correct(self): # only poses_se3 try: trajectory.PosePath3D(poses_se3=ex_tum_traj.poses_se3) except trajectory.TrajectoryException: self.fail("unexpected init failure with only poses_se3") # xyz + quaternion try: trajectory.PosePath3D(ex_tum_traj.positions_xyz, ex_tum_traj.orientations_quat_wxyz) except trajectory.TrajectoryException: self.fail("unexpected init failure with xyz + quaternion") # all try: trajectory.PosePath3D(ex_tum_traj.positions_xyz, ex_tum_traj.orientations_quat_wxyz, ex_tum_traj.poses_se3) except trajectory.TrajectoryException: self.fail( "unexpected init failure with xyz + quaternion + poses_se3")
def process_data(self, data: PathPair, align=False, align_origin=False, align_odom=False) -> None: """ Calculate the APE of segments from a batch of SE(3) poses from trajectories :param data: tuple (traj_ref, traj_est) with: traj_ref: reference evo.trajectory.PosePath or derived traj_est: estimated evo.trajectory.PosePath or derived """ if len(data) != 2: raise MetricsException( "please provide data tuple as: (traj_ref, traj_est)") traj_ref, traj_est = data if traj_ref.num_poses != traj_est.num_poses: raise MetricsException( "trajectories must have same number of poses") step_size = 10 i = 0 for first_pose in range(0, traj_ref.num_poses, step_size): print('processing segment ', i) i = i + 1 last_pose = self.last_pose_from_segment_length( traj_ref, first_pose) if (last_pose == -1): break traj_ref_segment = trajectory.PosePath3D( poses_se3=traj_ref.poses_se3[first_pose:last_pose]) traj_est_segment = trajectory.PosePath3D( poses_se3=traj_est.poses_se3[first_pose:last_pose]) # if align or correct_scale: if align: alignment_transformation = lie.sim3(*traj_est_segment.align( traj_ref_segment, False, False, -1)) elif align_origin: print('align origin: ', align_origin) alignment_transformation = traj_est_segment.align_origin( traj_ref_segment) elif align_odom: alignment_transformation = traj_est_segment.align_odom( traj_ref_segment) self.segment_index.append([first_pose, last_pose]) if i == 1: print('starting idx: ', first_pose) print('ending idx: ', last_pose) # print('origin 0 position: ', traj_est_segment.poses_se3[0]) # print('origin 1 position: ', traj_est_segment.poses_se3[1]) # print('ref 0 position: ', traj_ref_segment.poses_se3[0]) # print('results 1 position: ', traj_ref_segment.poses_se3[1]) fig = plt.figure() plot_option = '3D' if plot_option == '2D': ax = fig.add_subplot() #projection="3d" elif plot_option == '3D': ax = fig.add_subplot(projection="3d") x_ref = traj_ref_segment.positions_xyz[:, 0] y_ref = traj_ref_segment.positions_xyz[:, 1] z_ref = traj_ref_segment.positions_xyz[:, 2] front_vector_origin = np.array([1, 0, 0, 1]) f_vecs = np.array([ (np.dot(pose, front_vector_origin) - pose[:, 3]) * 10 for pose in traj_ref_segment.poses_se3 ]) if plot_option == '2D': ax.plot(x_ref, y_ref) #, z_ref) # plt.quiver(x_ref, y_ref, f_vecs[:,0], f_vecs[:,1], color='g')#, arrow_length_ratio=0.05) elif plot_option == '3D': ax.plot(x_ref, y_ref, z_ref) plt.quiver(x_ref, y_ref, z_ref, f_vecs[:, 0], f_vecs[:, 1], f_vecs[:, 2], color='g', arrow_length_ratio=0.05) x_est = traj_est_segment.positions_xyz[:, 0] y_est = traj_est_segment.positions_xyz[:, 1] z_est = traj_est_segment.positions_xyz[:, 2] f_vecs = np.array([ (np.dot(pose, front_vector_origin) - pose[:, 3]) * 10 for pose in traj_est_segment.poses_se3 ]) if plot_option == '2D': ax.plot(x_est, y_est, color='r') # plt.quiver(x_est, y_est, f_vecs[:,0], f_vecs[:,1], color='b') elif plot_option == '3D': ax.plot(x_est, y_est, z_est, color='r') plt.quiver(x_est, y_est, z_est, f_vecs[:, 0], f_vecs[:, 1], f_vecs[:, 2], color='b', arrow_length_ratio=0.05) plt.title('segment_length: ' + str(self.segment_length) + 'm') plt.savefig('first_segment_aligned.png') if self.plot_show: plt.show() if self.pose_relation == PoseRelation.translation_part: segment_E = traj_est_segment.positions_xyz - traj_ref_segment.positions_xyz elif self.pose_relation == PoseRelation.z: segment_E = traj_est_segment.positions_xyz - traj_ref_segment.positions_xyz elif self.pose_relation == PoseRelation.xy: segment_E = traj_est_segment.positions_xyz - traj_ref_segment.positions_xyz else: segment_E = [ self.ape_base(x_t, x_t_star) for x_t, x_t_star in zip( traj_est_segment.poses_se3, traj_ref_segment.poses_se3) ] logger.debug("Compared {} absolute pose pairs.".format(len( self.E))) logger.debug("Calculating APE for {} pose relation...".format( (self.pose_relation.value))) if self.pose_relation == PoseRelation.translation_part: segment_error = np.array( [np.linalg.norm(E_i) for E_i in segment_E]) elif self.pose_relation == PoseRelation.z: segment_error = np.array([E_i[2] for E_i in segment_E]) elif self.pose_relation == PoseRelation.xy: segment_error = np.array( [np.linalg.norm(E_i[0:2]) for E_i in segment_E]) elif self.pose_relation == PoseRelation.rotation_part: segment_error = np.array([ np.linalg.norm(lie.so3_from_se3(E_i) - np.eye(3)) for E_i in segment_E ]) elif self.pose_relation == PoseRelation.full_transformation: segment_error = np.array( [np.linalg.norm(E_i - np.eye(4)) for E_i in segment_E]) elif self.pose_relation == PoseRelation.rotation_angle_rad: segment_error = np.array( [abs(lie.so3_log(E_i[:3, :3])) for E_i in segment_E]) elif self.pose_relation == PoseRelation.rotation_angle_deg: segment_error = np.array([ abs(lie.so3_log(E_i[:3, :3])) * 180 / np.pi for E_i in segment_E ]) else: raise MetricsException("unsupported pose_relation") self.E.append(segment_E) self.seg_error.append(segment_error)