8 from visualization_msgs.msg
import MarkerArray
9 from geometry_msgs.msg
import Point
21 for m
in data.markers:
23 point_markers.append(m)
25 if len(point_markers) > 0
and lastSize != len(point_markers):
26 t = rospy.Time(point_markers[0].header.stamp.secs, point_markers[0].header.stamp.nsecs)
28 listener.waitForTransform(fixedFrame, baseFrame, t, rospy.Duration(0.2))
29 (trans,rot) = listener.lookupTransform(fixedFrame, baseFrame, t)
30 gtPoses.append(Point(trans[0], trans[1], 0))
31 stamps.append(t.to_sec())
32 slamPoses.append(point_markers[len(point_markers)-1].pose.position)
33 slamPosesInd.append(len(point_markers)-1)
34 first_xyz = numpy.empty([0,3])
35 second_xyz = numpy.empty([0,3])
37 newrow = [g.x,g.y,g.z]
38 first_xyz = numpy.vstack([first_xyz, newrow])
40 newrow = [p.x,p.y,p.z]
41 second_xyz = numpy.vstack([second_xyz, newrow])
42 first_xyz = numpy.matrix(first_xyz).transpose()
43 second_xyz = numpy.matrix(second_xyz).transpose()
45 rmse_v = numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error))
47 print "points= " + str(len(point_markers)) +
" added=" + str(len(slamPoses)) +
" rmse=" + str(rmse_v)
50 if len(data.markers) > 0
and len(slamPosesInd) > 0:
52 for i
in slamPosesInd:
53 slamPoses[j] = point_markers[i].pose.position
55 if len(data.markers) > 0:
56 lastSize = len(point_markers)
58 if __name__ ==
'__main__':
59 rospy.init_node(
'sync_markers_gt', anonymous=
True)
61 fixedFrame = rospy.get_param(
'~fixed_frame_id',
'world')
62 baseFrame = rospy.get_param(
'~frame_id',
'base_link_gt')
63 rospy.Subscriber(
"visualization_marker_array", MarkerArray, callback, queue_size=1)
71 fileSlam = open(
'slam_poses.txt',
'w')
72 fileGt = open(
'gt_poses.txt',
'w')
73 fileRMSE = open(
'rmse.txt',
'w')
74 print "slam= " + str(len(slamPoses))
75 print "gt= " + str(len(gtPoses))
76 print "stamps= " + str(len(stamps))
77 for c, g, t, r
in zip(slamPoses, gtPoses, stamps, rmse):
78 fileSlam.write(
'%f %f %f 0 0 0 0 1\n' % (t, c.x, c.y))
79 fileGt.write(
'%f %f %f 0 0 0 0 1\n' % (t, g.x, g.y))
80 fileRMSE.write(
'%f %f\n' % (t, r))