11 PKG =
'rosbridge_library'
12 NAME =
'test_message_handlers'
24 handler = subscribe.MessageHandler(
None, self.dummy_cb)
25 self.help_test_default(handler)
28 handler = subscribe.ThrottleMessageHandler(subscribe.MessageHandler(
None, self.
dummy_cb))
32 handler = subscribe.QueueMessageHandler(subscribe.MessageHandler(
None, self.
dummy_cb))
37 received = {
"msgs": []}
40 received[
"msgs"].append(msg)
42 handler = subscribe.QueueMessageHandler(subscribe.MessageHandler(
None, cb))
44 self.assertTrue(handler.is_alive())
48 self.assertFalse(handler.is_alive())
51 received = {
"msgs": []}
54 received[
"msgs"].append(msg)
58 handler = subscribe.MessageHandler(
None, cb)
60 handler = handler.set_throttle_rate(10000)
61 handler = handler.set_queue_length(10)
62 self.assertIsInstance(handler, subscribe.QueueMessageHandler)
65 handler.handle_message(
"hello")
73 handler.handle_message(x)
75 handler = handler.set_throttle_rate(0)
80 self.assertEqual([
"hello"] + list(range(990, 1000)), received[
"msgs"])
88 received = {
"msgs": []}
91 received[
"msgs"].append(msg)
95 msgs = list(range(queue_length * 5))
97 handler = subscribe.MessageHandler(
None, cb)
99 handler = handler.set_queue_length(queue_length)
100 self.assertIsInstance(handler, subscribe.QueueMessageHandler)
109 handler.handle_message(x)
115 time.sleep(queue_length + 3)
118 self.assertEqual([msgs[0]] + msgs[-queue_length:], received[
"msgs"])
126 handler = subscribe.MessageHandler(
None, self.
dummy_cb)
133 handler = handler.set_queue_length(0)
134 handler = handler.set_throttle_rate(0)
135 self.assertIsInstance(handler, subscribe.MessageHandler)
137 msg =
"test_default_message_handler"
138 received = {
"msg":
None}
141 received[
"msg"] = msg
144 self.assertTrue(handler.time_remaining() == 0)
146 handler.handle_message(msg)
149 self.assertEqual(received[
"msg"], msg)
150 self.assertLessEqual(t1, handler.last_publish)
151 self.assertLessEqual(handler.last_publish, t2)
152 self.assertEqual(handler.time_remaining(), 0)
154 received = {
"msgs": []}
156 received[
"msgs"].append(msg)
158 xs = list(range(10000))
160 handler.handle_message(x)
162 self.assertEqual(received[
"msgs"], xs)
166 handler = handler.set_queue_length(0)
167 handler = handler.set_throttle_rate(throttle_rate)
168 self.assertIsInstance(handler, subscribe.ThrottleMessageHandler)
170 msg =
"test_throttle_message_handler"
173 received = {
"msg":
None}
176 received[
"msg"] = msg
181 time.sleep(2.0 * handler.throttle_rate)
182 handler.handle_message(msg)
183 self.assertEqual(received[
"msg"], msg)
186 time.sleep(2.0 * handler.throttle_rate)
188 received = {
"msgs": []}
190 received[
"msgs"].append(msg)
194 time_padding = handler.throttle_rate / 4.0
195 for i
in range(1, 10):
200 time.sleep(2.0 * time_padding)
201 fin = time.time() + throttle_rate / 1000.0 - time_padding
202 while time.time() < fin:
203 handler.handle_message(x)
205 self.assertEqual(len(received[
"msgs"]), i)
209 handler = handler.set_queue_length(queue_length)
210 self.assertIsInstance(handler, subscribe.QueueMessageHandler)
212 received = {
"msgs": []}
215 received[
"msgs"].append(msg)
219 msgs = list(range(queue_length))
221 handler.handle_message(x)
225 self.assertEqual(msgs, received[
"msgs"])
229 handler = handler.set_throttle_rate(throttle_rate)
230 handler = handler.set_queue_length(queue_length)
231 self.assertIsInstance(handler, subscribe.QueueMessageHandler)
233 received = {
"msg":
None}
236 received[
"msg"] = msg
240 throttle_rate_sec = throttle_rate / 1000.0
243 time.sleep(throttle_rate_sec)
244 for x
in range(queue_length):
245 handler.handle_message(x)
247 time.sleep(throttle_rate_sec / 2.0)
251 self.assertEqual(x, received[
"msg"])
252 time.sleep(throttle_rate_sec)
262 handler = subscribe.MessageHandler(
None, self.
dummy_cb)
263 next_handler = handler.transition()
264 self.assertEqual(handler, next_handler)
267 handler = subscribe.MessageHandler(
None, self.
dummy_cb)
268 next_handler = handler.set_throttle_rate(100)
269 self.assertIsInstance(next_handler, subscribe.ThrottleMessageHandler)
270 handler = next_handler
272 next_handler = handler.transition()
273 self.assertEqual(handler, next_handler)
275 next_handler = handler.set_throttle_rate(0)
276 self.assertIsInstance(next_handler, subscribe.MessageHandler)
279 handler = subscribe.MessageHandler(
None, self.
dummy_cb)
280 next_handler = handler.set_queue_length(100)
281 self.assertIsInstance(next_handler, subscribe.QueueMessageHandler)
282 handler = next_handler
283 next_handler = handler.transition()
284 self.assertEqual(handler, next_handler)
285 next_handler = handler.set_queue_length(0)
286 self.assertIsInstance(next_handler, subscribe.MessageHandler)
289 handler = subscribe.MessageHandler(
None, self.
dummy_cb)
290 next_handler = handler.set_queue_length(100).set_throttle_rate(100)
291 self.assertIsInstance(next_handler, subscribe.QueueMessageHandler)
292 next_handler.finish()
293 next_handler = handler.set_throttle_rate(100).set_queue_length(100)
294 self.assertIsInstance(next_handler, subscribe.QueueMessageHandler)
295 next_handler.finish()
296 handler = next_handler
297 next_handler = handler.transition()
298 self.assertEqual(handler, next_handler)
300 next_handler = handler.set_throttle_rate(0)
301 self.assertIsInstance(next_handler, subscribe.QueueMessageHandler)
302 next_handler = handler.set_queue_length(0)
303 self.assertIsInstance(next_handler, subscribe.MessageHandler)
307 handler = subscribe.MessageHandler(
None,
None)
311 handler = subscribe.MessageHandler(
None,
None)
315 handler = subscribe.MessageHandler(
None,
None)
320 handler = subscribe.MessageHandler(
None,
None)
326 handler = subscribe.MessageHandler(
None,
None)
332 handler = subscribe.MessageHandler(
None,
None)
338 handler = subscribe.MessageHandler(
None,
None)
344 handler = subscribe.MessageHandler(
None,
None)
350 handler = subscribe.MessageHandler(
None,
None)
357 handler = subscribe.MessageHandler(
None,
None)
362 handler = subscribe.MessageHandler(
None,
None)
367 handler = subscribe.MessageHandler(
None,
None)
380 if __name__ ==
'__main__':
381 rosunit.unitrun(PKG, NAME, TestMessageHandlers)