cm_msgs_utils_rostest.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (C) 2014, PAL Robotics S.L.
00004 #
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions are met:
00007 # * Redistributions of source code must retain the above copyright notice,
00008 # this list of conditions and the following disclaimer.
00009 # * Redistributions in binary form must reproduce the above copyright
00010 # notice, this list of conditions and the following disclaimer in the
00011 # documentation and/or other materials provided with the distribution.
00012 # * Neither the name of PAL Robotics S.L. nor the names of its
00013 # contributors may be used to endorse or promote products derived from
00014 # this software without specific prior written permission.
00015 #
00016 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00017 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00018 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00019 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00020 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00021 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00022 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00023 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00024 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00025 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00026 # POSSIBILITY OF SUCH DAMAGE.
00027 
00028 import unittest
00029 import rospy
00030 from controller_manager_msgs.utils import *
00031 
00032 valid_cm = [
00033     '/',
00034     '/controller_manager',
00035     '/foo/robot/controller_manager1',
00036     '/foo/robot/controller_manager2'
00037 ]
00038 
00039 invalid_cm = [
00040     'non_existent',
00041     '/incomplete',
00042     '/bad_type'
00043 ]
00044 
00045 
00046 class TestUtils(unittest.TestCase):
00047     def _ready(self):
00048         try:
00049             rospy.wait_for_service("/controller_manager/list_controllers", 2.0)
00050         except ROSException:
00051             return False
00052         return True
00053 
00054     def test_is_controller_manager(self):
00055         self.assertTrue(self._ready())
00056 
00057         for cm in valid_cm:
00058             self.assertTrue(is_controller_manager(cm))
00059         for cm in invalid_cm:
00060             self.assertFalse(is_controller_manager(cm))
00061 
00062     def test_get_controller_managers(self):
00063         self.assertTrue(self._ready())
00064 
00065         # Root namespace
00066         self.assertEqual(valid_cm, get_controller_managers())
00067         self.assertEqual(valid_cm, get_controller_managers('/'))
00068 
00069         # Nested namespace
00070         nested_cm = [valid_cm[2], valid_cm[3]]
00071         self.assertEqual(nested_cm, get_controller_managers('/foo'))
00072         self.assertEqual(nested_cm, get_controller_managers('/foo/robot'))
00073         self.assertEqual(['/controller_manager'],
00074                          get_controller_managers('/controller_manager'))
00075 
00076         # Initial guess: Recommended usage pattern
00077         prev_cm = get_controller_managers()
00078         self.assertEqual(valid_cm,
00079                          get_controller_managers(initial_guess=prev_cm))
00080 
00081         # Initial guess: Partial guess
00082         self.assertEqual(valid_cm,
00083                          get_controller_managers(initial_guess=nested_cm))
00084 
00085         # Misuse of initial guess. Specifying entries that have not gone
00086         # through a full API check can yield incorrect results.
00087         # You have been warned!
00088         wrong_cm = get_controller_managers(initial_guess=invalid_cm)
00089         self.assertNotEqual(valid_cm, wrong_cm)
00090         diff = list(set(wrong_cm) - set(valid_cm))
00091         self.assertEqual(2, len(diff))
00092         self.assertIn('/incomplete', diff)
00093         self.assertIn('/bad_type', diff)
00094 
00095     def test_controller_manager_lister(self):
00096         self.assertTrue(self._ready())
00097 
00098         # Root namespace
00099         list_cm = ControllerManagerLister()
00100         self.assertEqual(valid_cm, list_cm())
00101 
00102         # Nested namespace
00103         list_cm_foo = ControllerManagerLister('/foo')
00104         nested_cm = [valid_cm[2], valid_cm[3]]
00105         self.assertEqual(nested_cm, list_cm_foo())
00106 
00107     def test_controller_lister(self):
00108         self.assertTrue(self._ready())
00109 
00110         # Default namespace
00111         list_controllers = ControllerLister()
00112         controllers = list_controllers()
00113         self.assertEqual(2, len(controllers))
00114         self.assertEqual('foo_controller', controllers[0].name)
00115         self.assertEqual('bar_controller', controllers[1].name)
00116 
00117         # Custom namespace
00118         list_controllers_ns = ControllerLister('/foo')
00119         self.assertEqual(0, len(list_controllers_ns()))
00120 
00121 if __name__ == '__main__':
00122     import rostest
00123     rostest.rosrun('controller_manager_msgs',
00124                    'cm_msgs_utils_rostest',
00125                    TestUtils)


controller_manager_tests
Author(s): Vijay Pradeep
autogenerated on Sat Jun 8 2019 20:09:25