43 roslib.load_manifest(
'gmapping')
50 im0 = PIL.Image.open(f0+
'.pgm')
51 im1 = PIL.Image.open(f1+
'.pgm')
54 im0.thumbnail(size,PIL.Image.ANTIALIAS)
55 im1.thumbnail(size,PIL.Image.ANTIALIAS)
62 self.assertTrue(len(im0d) == len(im1d))
69 for i
in range(len(im0d)):
72 if abs(p0-p1) > pixel_tol:
73 error_count = error_count + 1
74 error_total = error_total + abs(p0-p1)
75 error_avg = float(error_total)/float(len(im0d))
76 print '%d / %d = %.6f (%.6f)'%(error_total,len(im0d),error_avg,total_error_tol)
77 self.assertTrue(error_avg <= total_error_tol)
81 target_time = float(sys.argv[1])
85 rospy.init_node(
'test', anonymous=
True)
86 while(rospy.rostime.get_time() == 0.0):
87 print 'Waiting for initial time publication' 89 start_time = rospy.rostime.get_time()
91 while (rospy.rostime.get_time() - start_time) < target_time:
92 print 'Waiting for end time %.6f (current: %.6f)'%(target_time,(rospy.rostime.get_time() - start_time))
95 f0 = os.path.join(roslib.packages.get_pkg_dir(
'gmapping'),
'test',
'basic_localization_stage_groundtruth')
96 f1 = os.path.join(roslib.packages.get_pkg_dir(
'gmapping'),
'test',
'basic_localization_stage_generated')
98 cmd = [
'rosrun',
'map_server',
'map_saver',
'map:=dynamic_map',
'-f', f1]
99 self.assertTrue(subprocess.call(cmd) == 0)
103 if __name__ ==
'__main__':
104 rostest.run(
'gmapping',
'gmapping_slam', TestGmapping, sys.argv)
def test_basic_localization_stage(self)
def cmp_maps(self, f0, f1)