38 This script computes the absolute trajectory error from the ground truth 39 trajectory and the estimated trajectory. 48 """Align two trajectories using the method of Horn (closed-form). 51 model -- first trajectory (3xn) 52 data -- second trajectory (3xn) 55 rot -- rotation matrix (3x3) 56 trans -- translation vector (3x1) 57 trans_error -- translational error per point (1xn) 60 numpy.set_printoptions(precision=3,suppress=
True)
61 model_zerocentered = model - model.mean(1)
62 data_zerocentered = data - data.mean(1)
64 W = numpy.zeros( (3,3) )
65 for column
in range(model.shape[1]):
66 W += numpy.outer(model_zerocentered[:,column],data_zerocentered[:,column])
67 U,d,Vh = numpy.linalg.linalg.svd(W.transpose())
68 S = numpy.matrix(numpy.identity( 3 ))
69 if(numpy.linalg.det(U) * numpy.linalg.det(Vh)<0):
72 trans = data.mean(1) - rot * model.mean(1)
74 model_aligned = rot * model + trans
75 alignment_error = model_aligned - data
77 trans_error = numpy.sqrt(numpy.sum(numpy.multiply(alignment_error,alignment_error),0)).A[0]
79 return rot,trans,trans_error
83 Plot a trajectory using matplotlib. 87 stamps -- time stamps (1xn) 88 traj -- trajectory (3xn) 95 interval = numpy.median([s-t
for s,t
in zip(stamps[1:],stamps[:-1])])
99 for i
in range(len(stamps)):
100 if stamps[i]-last < 2*interval:
104 ax.plot(x,y,style,color=color,label=label)
110 ax.plot(x,y,style,color=color,label=label)
113 if __name__==
"__main__":
115 parser = argparse.ArgumentParser(description=
''' 116 This script computes the absolute trajectory error from the ground truth trajectory and the estimated trajectory. 118 parser.add_argument(
'first_file', help=
'ground truth trajectory (format: timestamp tx ty tz qx qy qz qw)')
119 parser.add_argument(
'second_file', help=
'estimated trajectory (format: timestamp tx ty tz qx qy qz qw)')
120 parser.add_argument(
'--offset', help=
'time offset added to the timestamps of the second file (default: 0.0)',default=0.0)
121 parser.add_argument(
'--scale', help=
'scaling factor for the second trajectory (default: 1.0)',default=1.0)
122 parser.add_argument(
'--max_difference', help=
'maximally allowed time difference for matching entries (default: 0.02)',default=0.02)
123 parser.add_argument(
'--save', help=
'save aligned second trajectory to disk (format: stamp2 x2 y2 z2)')
124 parser.add_argument(
'--save_associations', help=
'save associated first and aligned second trajectory to disk (format: stamp1 x1 y1 z1 stamp2 x2 y2 z2)')
125 parser.add_argument(
'--plot', help=
'plot the first and the aligned second trajectory to an image (format: png)')
126 parser.add_argument(
'--verbose', help=
'print all evaluation data (otherwise, only the RMSE absolute translational error in meters after alignment will be printed)', action=
'store_true')
127 args = parser.parse_args()
134 sys.exit(
"Couldn't find matching timestamp pairs between groundtruth and estimated trajectory! Did you choose the correct sequence?")
137 first_xyz = numpy.matrix([[float(value)
for value
in first_list[a][0:3]]
for a,b
in matches]).transpose()
138 second_xyz = numpy.matrix([[float(value)*float(args.scale)
for value
in second_list[b][0:3]]
for a,b
in matches]).transpose()
139 rot,trans,trans_error =
align(second_xyz,first_xyz)
141 second_xyz_aligned = rot * second_xyz + trans
143 first_stamps = first_list.keys()
145 first_xyz_full = numpy.matrix([[float(value)
for value
in first_list[b][0:3]]
for b
in first_stamps]).transpose()
147 second_stamps = second_list.keys()
149 second_xyz_full = numpy.matrix([[float(value)*float(args.scale)
for value
in second_list[b][0:3]]
for b
in second_stamps]).transpose()
150 second_xyz_full_aligned = rot * second_xyz_full + trans
153 print "compared_pose_pairs %d pairs"%(len(trans_error))
155 print "absolute_translational_error.rmse %f m"%numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error))
156 print "absolute_translational_error.mean %f m"%numpy.mean(trans_error)
157 print "absolute_translational_error.median %f m"%numpy.median(trans_error)
158 print "absolute_translational_error.std %f m"%numpy.std(trans_error)
159 print "absolute_translational_error.min %f m"%numpy.min(trans_error)
160 print "absolute_translational_error.max %f m"%numpy.max(trans_error)
162 print "%f"%numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error))
164 if args.save_associations:
165 file = open(args.save_associations,
"w")
166 file.write(
"\n".join([
"%f %f %f %f %f %f %f %f"%(a,x1,y1,z1,b,x2,y2,z2)
for (a,b),(x1,y1,z1),(x2,y2,z2)
in zip(matches,first_xyz.transpose().A,second_xyz_aligned.transpose().A)]))
170 file = open(args.save,
"w")
171 file.write(
"\n".join([
"%f "%stamp+
" ".join([
"%f"%d
for d
in line])
for stamp,line
in zip(second_stamps,second_xyz_full_aligned.transpose().A)]))
176 matplotlib.use(
'Agg')
177 import matplotlib.pyplot
as plt
178 import matplotlib.pylab
as pylab
179 from matplotlib.patches
import Ellipse
181 ax = fig.add_subplot(111)
182 plot_traj(ax,first_stamps,first_xyz_full.transpose().A,
'-',
"black",
"ground truth")
183 plot_traj(ax,second_stamps,second_xyz_full_aligned.transpose().A,
'-',
"blue",
"estimated")
192 ax.set_xlabel(
'x [m]')
193 ax.set_ylabel(
'y [m]')
194 plt.savefig(args.plot,dpi=300, format=
'pdf')
def plot_traj(ax, stamps, traj, style, color, label)
def read_file_list(filename)
def associate(first_list, second_list, offset, max_difference)