Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 import subprocess
00039 import unittest
00040
00041 import rospy
00042 PKG = 'test_tf2'
00043 import roslib; roslib.load_manifest(PKG)
00044
00045
00046 class TestStaticPublisher(unittest.TestCase):
00047 """
00048 These tests ensure the static transform publisher dies gracefully when
00049 provided with an invalid (or non-existent) transform parameter.
00050
00051 These tests are started by the static_publisher.launch, which loads
00052 parameters into the param server.
00053
00054 We check the output to make sure the correct error is occurring, since the
00055 return code is always -1 (255).
00056
00057 Note that this *could* cause a problem if a valid TF is stored in the param
00058 server for one of the names; in this case the subprocess would never return
00059 and the test would run forever.
00060 """
00061
00062 def test_publisher_no_args(self):
00063
00064 cmd = 'rosrun tf2_ros static_transform_publisher'
00065 with self.assertRaises(subprocess.CalledProcessError) as cm:
00066 ret = subprocess.check_output(
00067 cmd.split(' '), stderr=subprocess.STDOUT)
00068 self.assertEqual(255, cm.exception.returncode)
00069 self.assertIn('not having the right number of arguments',
00070 cm.exception.output)
00071
00072 def test_publisher_nonexistent_param(self):
00073
00074 cmd = 'rosrun tf2_ros static_transform_publisher /test_tf2/tf_null'
00075 with self.assertRaises(subprocess.CalledProcessError) as cm:
00076 ret = subprocess.check_output(
00077 cmd.split(' '), stderr=subprocess.STDOUT)
00078
00079 self.assertEqual(255, cm.exception.returncode)
00080 self.assertIn('Could not read TF', cm.exception.output)
00081
00082 def test_publisher_invalid_param(self):
00083
00084 cmd = 'rosrun tf2_ros static_transform_publisher /test_tf2/tf_invalid'
00085 with self.assertRaises(subprocess.CalledProcessError) as cm:
00086 ret = subprocess.check_output(
00087 cmd.split(' '), stderr=subprocess.STDOUT)
00088
00089 self.assertEqual(255, cm.exception.returncode)
00090 self.assertIn('Could not validate XmlRpcC', cm.exception.output)
00091
00092
00093 if __name__ == '__main__':
00094 rospy.init_node("test_static_publisher_py")
00095 import rostest
00096 rostest.rosrun(PKG, 'test_static_publisher_py', TestStaticPublisher)