test
test_relay_stealth.py
Go to the documentation of this file.
1
#!/usr/bin/env python
2
# -*- coding: utf-8 -*-
3
4
import
rospy
5
import
unittest
6
from
std_msgs.msg
import
String
7
8
9
class
TestRelayStealth
(unittest.TestCase):
10
def
out_callback
(self, msg):
11
self.
out_msg_count
+= 1
12
13
def
monitor_callback
(self, msg):
14
self.
monitor_msg_count
+= 1
15
16
def
test_stealth_relay
(self):
17
self.
out_msg_count
= 0
18
self.
monitor_msg_count
= 0
19
sub_out = rospy.Subscriber(
"/relay_stealth/output"
, String,
20
self.
out_callback
, queue_size=1)
21
for
i
in
range(5):
22
if
sub_out.get_num_connections() == 0:
23
rospy.sleep(1)
24
self.assertTrue(sub_out.get_num_connections() > 0)
25
26
rospy.sleep(5)
27
self.assertEqual(self.
out_msg_count
, 0)
28
29
sub_monitor = rospy.Subscriber(
"/original_topic/relay"
, String,
30
self.
monitor_callback
, queue_size=1)
31
rospy.sleep(5)
32
self.assertGreater(self.
monitor_msg_count
, 0)
33
self.assertGreater(self.
out_msg_count
, 0)
34
35
cnt = self.
out_msg_count
36
sub_monitor.unregister()
37
38
rospy.sleep(3)
39
self.assertLess(abs(cnt - self.
out_msg_count
), 30)
40
41
42
if
__name__ ==
'__main__'
:
43
import
rostest
44
rospy.init_node(
"test_relay_stealth"
)
45
rostest.rosrun(
"topic_tools"
,
"test_relay_stealth"
, TestRelayStealth)
msg
test_relay_stealth.TestRelayStealth.monitor_msg_count
monitor_msg_count
Definition:
test_relay_stealth.py:18
test_relay_stealth.TestRelayStealth.monitor_callback
def monitor_callback(self, msg)
Definition:
test_relay_stealth.py:13
test_relay_stealth.TestRelayStealth
Definition:
test_relay_stealth.py:9
test_relay_stealth.TestRelayStealth.out_msg_count
out_msg_count
Definition:
test_relay_stealth.py:17
test_relay_stealth.TestRelayStealth.out_callback
def out_callback(self, msg)
Definition:
test_relay_stealth.py:10
test_relay_stealth.TestRelayStealth.test_stealth_relay
def test_stealth_relay(self)
Definition:
test_relay_stealth.py:16
topic_tools
Author(s): Morgan Quigley, Brian Gerkey, Dirk Thomas
, Jacob Perron
autogenerated on Sat Sep 14 2024 03:00:05