test_map.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2008, Willow Garage, Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of the Willow Garage nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 #
34 
35 
36 import PIL.Image
37 import unittest
38 import subprocess
39 import sys
40 
41 import roslib
42 import os
43 roslib.load_manifest('gmapping')
44 import rostest
45 
46 class TestGmapping(unittest.TestCase):
47 
48  # Test that 2 map files are approximately the same
49  def cmp_maps(self, f0, f1):
50  im0 = PIL.Image.open(f0+'.pgm')
51  im1 = PIL.Image.open(f1+'.pgm')
52 
53  size = 100,100
54  im0.thumbnail(size,PIL.Image.ANTIALIAS)
55  im1.thumbnail(size,PIL.Image.ANTIALIAS)
56 
57  # get raw data for comparison
58  im0d = im0.getdata()
59  im1d = im1.getdata()
60 
61  # assert len(i0)==len(i1)
62  self.assertTrue(len(im0d) == len(im1d))
63 
64  #compare pixel by pixel for thumbnails
65  error_count = 0
66  error_total = 0
67  pixel_tol = 0
68  total_error_tol = 0.1
69  for i in range(len(im0d)):
70  (p0) = im0d[i]
71  (p1) = im1d[i]
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)
78 
80  if sys.argv > 1:
81  target_time = float(sys.argv[1])
82 
83  import time
84  import rospy
85  rospy.init_node('test', anonymous=True)
86  while(rospy.rostime.get_time() == 0.0):
87  print 'Waiting for initial time publication'
88  time.sleep(0.1)
89  start_time = rospy.rostime.get_time()
90 
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))
93  time.sleep(0.1)
94 
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')
97 
98  cmd = ['rosrun', 'map_server', 'map_saver', 'map:=dynamic_map', '-f', f1]
99  self.assertTrue(subprocess.call(cmd) == 0)
100 
101  self.cmp_maps(f0,f1)
102 
103 if __name__ == '__main__':
104  rostest.run('gmapping', 'gmapping_slam', TestGmapping, sys.argv)
def test_basic_localization_stage(self)
Definition: test_map.py:79
def cmp_maps(self, f0, f1)
Definition: test_map.py:49


gmapping
Author(s): Brian Gerkey
autogenerated on Mon Jun 10 2019 15:08:12