test_roslib_gentools.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2008, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of Willow Garage, Inc. nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 
00034 from __future__ import print_function
00035 
00036 import os
00037 import string 
00038 import sys 
00039 import unittest
00040         
00041 import roslib.names
00042 import roslib.packages
00043 
00044 TEST_CTX = 'rosgraph_msgs'
00045 
00046 import roslib
00047 PKG='test_roslib_comm'
00048 
00049 class TestGentools(unittest.TestCase):
00050 
00051     def setUp(self):
00052         pass
00053         
00054     def _load_md5_tests(self, dir):
00055         test_dir = os.path.join(roslib.packages.get_pkg_dir(PKG), 'test', 'md5tests', dir)
00056         tests = {}
00057         for f in os.listdir(test_dir):
00058             path = os.path.join(test_dir, f)
00059             if not f.endswith('.txt'):
00060                 continue
00061             name = f[:-4]
00062             while name and name[-1].isdigit():
00063                 name = name[:-1]
00064             self.assert_(name)
00065             if name in tests:
00066                 tests[name].append(path)
00067             else:
00068                 tests[name] = [path]
00069         return tests
00070     
00071     def _compute_md5(self, f):
00072         from roslib.gentools import compute_md5, get_dependencies
00073         from roslib.msgs import load_from_string
00074 
00075         text = open(f, 'r').read()
00076         spec = load_from_string(text, package_context=TEST_CTX) 
00077         get_deps_dict = get_dependencies(spec, TEST_CTX, compute_files=False)
00078         return compute_md5(get_deps_dict)
00079         
00080     def _compute_md5_text(self, f):
00081         from roslib.gentools import compute_md5_text, get_dependencies
00082         from roslib.msgs import load_from_string
00083 
00084         text = open(f, 'r').read()
00085         spec = load_from_string(text, package_context=TEST_CTX)
00086         get_deps_dict = get_dependencies(spec, TEST_CTX, compute_files=False)
00087         return compute_md5_text(get_deps_dict, spec)
00088 
00089     def test_compute_md5_text(self):
00090         from std_msgs.msg import Header
00091         Header_md5 = Header._md5sum
00092         rg_msg_dir = os.path.join(roslib.packages.get_pkg_dir(TEST_CTX), 'msg')
00093         clock_msg = os.path.join(rg_msg_dir, 'Clock.msg')
00094         # a bit gory, but go ahead and regression test these important messages
00095         self.assertEquals("time clock", self._compute_md5_text(clock_msg))
00096         log_msg = os.path.join(rg_msg_dir, 'Log.msg')
00097         self.assertEquals("byte DEBUG=1\nbyte INFO=2\nbyte WARN=4\nbyte ERROR=8\nbyte FATAL=16\n%s header\nbyte level\nstring name\nstring msg\nstring file\nstring function\nuint32 line\nstring[] topics"%Header_md5, self._compute_md5_text(log_msg))
00098 
00099         tests = self._load_md5_tests('md5text')
00100         # text file #1 is the reference
00101         for k, files in tests.items():
00102             print("running tests", k)
00103             ref_file = [f for f in files if f.endswith('%s1.txt'%k)]
00104             if not ref_file:
00105                 self.fail("failed to load %s"%k)
00106             ref_file = ref_file[0]
00107             ref_text = open(ref_file, 'r').read().strip()
00108             print("KEY", k)
00109             files = [f for f in files if not f.endswith('%s1.txt'%k)]
00110             for f in files[1:]:
00111                 f_text = self._compute_md5_text(f)
00112                 self.assertEquals(ref_text, f_text, "failed on %s\n%s\n%s: \n[%s]\nvs.\n[%s]\n"%(k, ref_file, f, ref_text, f_text))
00113         
00114     def test_md5_equals(self):
00115         tests = self._load_md5_tests('same')
00116         for k, files in tests.items():
00117             print("running tests", k)
00118             md5sum = self._compute_md5(files[0])
00119             for f in files[1:]:
00120                 self.assertEquals(md5sum, self._compute_md5(f), "failed on %s: \n[%s]\nvs.\n[%s]\n"%(k, self._compute_md5_text(files[0]), self._compute_md5_text(f)))
00121     
00122     def test_md5_not_equals(self):
00123         tests = self._load_md5_tests('different')
00124         for k, files in tests.items():
00125             print("running tests", k)
00126             md5s = set()
00127             md6md5sum = self._compute_md5(files[0])
00128             for f in files:
00129                 md5s.add(self._compute_md5(f))
00130             # each md5 should be unique
00131             self.assertEquals(len(md5s), len(files))


test_roslib_comm
Author(s): Jeremy Leibs, Ken Conley
autogenerated on Thu Jun 6 2019 21:09:59