test_nlj_dummy_interfaces.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 # -*- coding: utf-8 -*-
00003 
00004 from __future__ import print_function, division
00005 
00006 import unittest
00007 
00008 import rospy
00009 import roslib.message
00010 
00011 from nlj_dummy.msg import Dummy
00012 
00013 from lama_interfaces.interface_factory import interface_factory
00014 from nlj_dummy.srv import GetDummyDescriptorRequest
00015 
00016 
00017 class RosTestCase(unittest.TestCase):
00018     def assertMsgEqual(self, msg0, msg1):
00019         """Fail if two ROS messages are not equal"""
00020         self.assertIsInstance(msg0, roslib.message.Message,
00021                               msg='Argument 1 is not a Message')
00022         self.assertIsInstance(msg1, roslib.message.Message,
00023                               msg='Argument 2 is not a Message')
00024         slots0 = msg0.__slots__
00025         slots1 = msg1.__slots__
00026         self.assertEquals(slots0, slots1,
00027                           msg=('Messages do not have the same arguments\n' +
00028                                'Msg1 args: {}\n'.format(slots0) +
00029                                'Msg2 args: {}\n'.format(slots1)))
00030         for slot in slots0:
00031             value0 = getattr(msg0, slot)
00032             value1 = getattr(msg1, slot)
00033             if isinstance(value0, roslib.message.Message):
00034                 self.assertMsgEqual(value0, value1)
00035             elif isinstance(value0, (list, tuple)):
00036                 self.assertAlmostEquals(list(value0), list(value1), places=6,
00037                                         msg='Argument {} differ: {} != {}'.
00038                                         format(slot, value0, value1))
00039             else:
00040                 self.assertAlmostEqual(value0, value1, places=6,
00041                                        msg='Argument {} differ: {} != {}'.
00042                                        format(slot, value0, value1))
00043 
00044 
00045 class TestDbMessagePassing(RosTestCase):
00046     """test setting and getting dummy descriptors"""
00047     def __init__(self, *args, **kwargs):
00048         rospy.init_node('test_lama_interfaces_nlj_dummy', anonymous=True)
00049         super(TestDbMessagePassing, self).__init__(*args, **kwargs)
00050 
00051     def test_dummy(self):
00052         """Test passing and getting a Dummy message"""
00053         interface_name = 'dummy_descriptor'
00054         getter_service = 'nlj_dummy/GetDummyDescriptor'
00055         setter_service = 'nlj_dummy/SetDummyDescriptor'
00056 
00057         # Set up node as well as getter and setter services.
00058         iface = interface_factory(interface_name,
00059                                   getter_service,
00060                                   setter_service)
00061         get_srv = rospy.ServiceProxy(iface.getter_service_name,
00062                                      iface.getter_service_class)
00063         set_srv = rospy.ServiceProxy(iface.setter_service_name,
00064                                      iface.setter_service_class)
00065 
00066         dummy0 = Dummy()
00067         dummy0.value = 354
00068         dummy1 = Dummy()
00069         dummy1.value = 5649
00070 
00071         id_from_setter0 = set_srv(dummy0)
00072         # id_from_setter cannot be passed to get_srv because of
00073         # type incompatibility, "transform" it to a Get...Request()
00074         id_to_getter0 = GetDummyDescriptorRequest()
00075         id_to_getter0.id = id_from_setter0.id
00076         response0 = get_srv(id_to_getter0)
00077 
00078         id_from_setter1 = set_srv(dummy1)
00079         # id_from_setter cannot be passed to get_srv because of
00080         # type incompatibility, "transform" it to a Get...Request()
00081         id_to_getter1 = GetDummyDescriptorRequest()
00082         id_to_getter1.id = id_from_setter1.id
00083         response1 = get_srv(id_to_getter1)
00084 
00085         self.assertIsNot(dummy0, response0.descriptor)
00086         self.assertIsNot(dummy0.value, response0.descriptor.value)
00087         self.assertIsNot(dummy1, response1.descriptor)
00088         self.assertEqual(dummy0.value, response0.descriptor.value)
00089         self.assertEqual(dummy1.value, response1.descriptor.value)
00090 
00091 if __name__ == '__main__':
00092     import rostest
00093     rostest.rosrun('nlj_dummy',
00094                    'test_db_message_passing',
00095                    TestDbMessagePassing)


nlj_dummy
Author(s): Gaël Ecorchard , Karel Košnar
autogenerated on Thu Jun 6 2019 22:02:12