43 import roslib; roslib.load_manifest(PKG)
48 These tests ensure the static transform publisher dies gracefully when 49 provided with an invalid (or non-existent) transform parameter. 51 These tests are started by the static_publisher.launch, which loads 52 parameters into the param server. 54 We check the output to make sure the correct error is occurring, since the 55 return code is always -1 (255). 57 Note that this *could* cause a problem if a valid TF is stored in the param 58 server for one of the names; in this case the subprocess would never return 59 and the test would run forever. 64 cmd =
'rosrun tf2_ros static_transform_publisher' 65 with self.assertRaises(subprocess.CalledProcessError)
as cm:
66 ret = subprocess.check_output(
67 cmd.split(
' '), stderr=subprocess.STDOUT)
68 self.assertEqual(255, cm.exception.returncode)
69 self.assertIn(
'not having the right number of arguments',
74 cmd =
'rosrun tf2_ros static_transform_publisher /test_tf2/tf_null' 75 with self.assertRaises(subprocess.CalledProcessError)
as cm:
76 ret = subprocess.check_output(
77 cmd.split(
' '), stderr=subprocess.STDOUT)
79 self.assertEqual(255, cm.exception.returncode)
80 self.assertIn(
'Could not read TF', cm.exception.output)
84 cmd =
'rosrun tf2_ros static_transform_publisher /test_tf2/tf_invalid' 85 with self.assertRaises(subprocess.CalledProcessError)
as cm:
86 ret = subprocess.check_output(
87 cmd.split(
' '), stderr=subprocess.STDOUT)
89 self.assertEqual(255, cm.exception.returncode)
90 self.assertIn(
'Could not validate XmlRpcC', cm.exception.output)
93 if __name__ ==
'__main__':
94 rospy.init_node(
"test_static_publisher_py")
96 rostest.rosrun(PKG,
'test_static_publisher_py', TestStaticPublisher)
def test_publisher_invalid_param(self)
def test_publisher_nonexistent_param(self)
def test_publisher_no_args(self)