3 @file check_camera_transforms_publish_tf.py 12 is_log_contains_keyword, LOGFILE, shell_cmd_timeout
14 PKG =
"realsense_camera" 15 NAME =
"test_camera_transforms_publish_tf" 20 @class CheckCameraTransformsPublishTf: check whether message exist 21 or not based on disable/enable publish tf 25 @fn test_camera_transforms_publish_tf 29 rospy.init_node(NAME, anonymous=
True, log_level=rospy.DEBUG)
31 messages = expected_message.split(
',')
33 cmd =
"rm ~/.ros/test_rostopic.log >/dev/null 2>&1" 35 cmd =
"rostopic echo /tf_static > ~/.ros/test_rostopic.log" 37 for message
in messages:
39 indicator = indicator + 1
40 rospy.loginfo(
"***transforms publish info***: " + str(indicator))
42 self.assertEqual(
'true', expected)
44 self.assertEqual(
'false', expected)
46 self.assertTrue(
False)
48 if __name__ ==
'__main__':
50 expected_message = param_dict[
'expected_messages']
51 expected = param_dict[
'expected']
52 publish_info = param_dict[
'info'].replace(
'*',
' ')
53 rostest.rosrun(PKG, NAME, CheckCameraTransformsPublishTf, sys.argv)
def shell_cmd_timeout(cmd, timeout=0)
def is_log_contains_keyword(log_file, keyword)
def get_camera_params_and_values(args)