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