37 from __future__
import print_function
48 from rosgraph_msgs.msg
import Log
51 MSG_PREFIX =
'[test_rosout] '
65 if MSG_PREFIX
in data.msg:
81 log_msg = MSG_PREFIX +
'logging test debug message'
82 rospy.logdebug(log_msg)
85 timeout_time = time.time() + TIMEOUT
91 self.assertIsNotNone(self.
callback_data,
'did not receive expected message')
98 self.assertEqual(
'TestRosout.test_rosout_dbg', self.
callback_data.function)
103 self.assertIsNone(self.
callback_data,
'invalid test fixture')
105 log_msg = MSG_PREFIX +
'logging test info message'
106 rospy.loginfo(log_msg)
109 timeout_time = time.time() + TIMEOUT
115 self.assertIsNotNone(self.
callback_data,
'did not receive expected message')
122 self.assertEqual(
'TestRosout.test_rosout_info', self.
callback_data.function)
127 self.assertIsNone(self.
callback_data,
'invalid test fixture')
129 log_msg = MSG_PREFIX +
'logging test warning message'
130 rospy.logwarn(log_msg)
133 timeout_time = time.time() + TIMEOUT
139 self.assertIsNotNone(self.
callback_data,
'did not receive expected message')
146 self.assertEqual(
'TestRosout.test_rosout_warn', self.
callback_data.function)
151 self.assertIsNone(self.
callback_data,
'invalid test fixture')
153 log_msg = MSG_PREFIX +
'logging test error message'
154 rospy.logerr(log_msg)
157 timeout_time = time.time() + TIMEOUT
163 self.assertIsNotNone(self.
callback_data,
'did not receive expected message')
170 self.assertEqual(
'TestRosout.test_rosout_err', self.
callback_data.function)
175 self.assertIsNone(self.
callback_data,
'invalid test fixture')
177 log_msg = MSG_PREFIX +
'logging test fatal message'
178 rospy.logfatal(log_msg)
181 timeout_time = time.time() + TIMEOUT
187 self.assertIsNotNone(self.
callback_data,
'did not receive expected message')
194 self.assertEqual(
'TestRosout.test_rosout_fatal', self.
callback_data.function)
198 if __name__ ==
'__main__':
199 rospy.init_node(NAME, log_level=rospy.DEBUG)
200 rostest.run(PKG, NAME, TestRosout, sys.argv)