8 from nav_msgs.msg
import Odometry
9 from geometry_msgs.msg
import Point
19 if rospy.get_time() - lastTime < 1:
21 lastTime = rospy.get_time()
23 t = rospy.Time(data.header.stamp.secs, data.header.stamp.nsecs)
25 listener.waitForTransform(fixedFrame, baseFrame, t, rospy.Duration(0.2))
26 (trans,rot) = listener.lookupTransform(fixedFrame, baseFrame, t)
27 gtPoses.append(Point(trans[0], trans[1], 0))
28 stamps.append(t.to_sec())
29 slamPoses.append(data.pose.pose.position)
30 first_xyz = numpy.empty([0,3])
31 second_xyz = numpy.empty([0,3])
33 newrow = [g.x,g.y,g.z]
34 first_xyz = numpy.vstack([first_xyz, newrow])
36 newrow = [p.x,p.y,p.z]
37 second_xyz = numpy.vstack([second_xyz, newrow])
38 first_xyz = numpy.matrix(first_xyz).transpose()
39 second_xyz = numpy.matrix(second_xyz).transpose()
41 rmse_v = numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error))
43 print " added=" + str(len(slamPoses)) +
" rmse=" + str(rmse_v)
47 if __name__ ==
'__main__':
48 rospy.init_node(
'sync_odom_gt', anonymous=
True)
50 fixedFrame = rospy.get_param(
'~fixed_frame_id',
'world')
51 baseFrame = rospy.get_param(
'~frame_id',
'base_link_gt')
52 rospy.Subscriber(
"icp_odom", Odometry, callback, queue_size=1)
57 lastTime = rospy.get_time()
59 fileSlam = open(
'slam_poses.txt',
'w')
60 fileGt = open(
'gt_poses.txt',
'w')
61 fileRMSE = open(
'rmse.txt',
'w')
62 print "slam= " + str(len(slamPoses))
63 print "gt= " + str(len(gtPoses))
64 print "stamps= " + str(len(stamps))
65 for c, g, t, r
in zip(slamPoses, gtPoses, stamps, rmse):
66 fileSlam.write(
'%f %f %f 0 0 0 0 1\n' % (t, c.x, c.y))
67 fileGt.write(
'%f %f %f 0 0 0 0 1\n' % (t, g.x, g.y))
68 fileRMSE.write(
'%f %f\n' % (t, r))