cartographer_sync_markers_gt.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import roslib
3 import rospy
4 import os
5 import tf
6 import numpy
7 import evaluate_ate
8 from visualization_msgs.msg import MarkerArray
9 from geometry_msgs.msg import Point
10 
11 def callback(data):
12  global slamPoses
13  global gtPoses
14  global stamps
15  global listener
16  global lastSize
17  global slamPosesInd
18  global rmse
19  if len(data.markers) > 0 and lastSize != len(data.markers[0].points):
20  t = rospy.Time(data.markers[0].header.stamp.secs, data.markers[0].header.stamp.nsecs)
21  try:
22  listener.waitForTransform(fixedFrame, baseFrame, t, rospy.Duration(0.2))
23  (trans,rot) = listener.lookupTransform(fixedFrame, baseFrame, t)
24  gtPoses.append(Point(trans[0], trans[1], 0))
25  stamps.append(t.to_sec())
26  slamPoses.append(data.markers[0].points[len(data.markers[0].points)-1])
27  slamPosesInd.append(len(data.markers[0].points)-1)
28  first_xyz = numpy.empty([0,3])
29  second_xyz = numpy.empty([0,3])
30  for g in gtPoses:
31  newrow = [g.x,g.y,g.z]
32  first_xyz = numpy.vstack([first_xyz, newrow])
33  for p in slamPoses:
34  newrow = [p.x,p.y,p.z]
35  second_xyz = numpy.vstack([second_xyz, newrow])
36  first_xyz = numpy.matrix(first_xyz).transpose()
37  second_xyz = numpy.matrix(second_xyz).transpose()
38  rot,trans,trans_error = evaluate_ate.align(second_xyz, first_xyz)
39  rmse_v = numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error))
40  rmse.append(rmse_v)
41  print "points= " + str(len(data.markers[0].points)) + " added=" + str(len(slamPoses)) + " rmse=" + str(rmse_v)
43  print str(e)
44  if len(data.markers) > 0 and len(slamPosesInd) > 0:
45  j=0
46  for i in slamPosesInd:
47  slamPoses[j] = data.markers[0].points[i]
48  j+=1
49  if len(data.markers) > 0:
50  lastSize = len(data.markers[0].points)
51 
52 if __name__ == '__main__':
53  rospy.init_node('sync_markers_gt', anonymous=True)
54  listener = tf.TransformListener()
55  fixedFrame = rospy.get_param('~fixed_frame_id', 'world')
56  baseFrame = rospy.get_param('~frame_id', 'base_link_gt')
57  rospy.Subscriber("trajectory_node_list", MarkerArray, callback, queue_size=1)
58  slamPoses = []
59  gtPoses = []
60  stamps = []
61  slamPosesInd = []
62  rmse = []
63  lastSize = 0
64  rospy.spin()
65  fileSlam = open('slam_poses.txt','w')
66  fileGt = open('gt_poses.txt','w')
67  fileRMSE = open('rmse.txt','w')
68  print "slam= " + str(len(slamPoses))
69  print "gt= " + str(len(gtPoses))
70  print "stamps= " + str(len(stamps))
71  for c, g, t, r in zip(slamPoses, gtPoses, stamps, rmse):
72  fileSlam.write('%f %f %f 0 0 0 0 1\n' % (t, c.x, c.y))
73  fileGt.write('%f %f %f 0 0 0 0 1\n' % (t, g.x, g.y))
74  fileRMSE.write('%f %f\n' % (t, r))
75  fileSlam.close()
76  fileGt.close()
77  fileRMSE.close()
def align(model, data)
Definition: evaluate_ate.py:47


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:18