status_indicator_unit_test.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Copyright (c) 2020 Pilz GmbH & Co. KG
3 #
4 # This program is free software: you can redistribute it and/or modify
5 # it under the terms of the GNU Lesser General Public License as published by
6 # the Free Software Foundation, either version 3 of the License, or
7 # (at your option) any later version.
8 #
9 # This program is distributed in the hope that it will be useful,
10 # but WITHOUT ANY WARRANTY; without even the implied warranty of
11 # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 # GNU Lesser General Public License for more details.
13 #
14 # You should have received a copy of the GNU Lesser General Public License
15 # along with this program. If not, see <http://www.gnu.org/licenses/>.
16 
17 import unittest
18 
19 import rospy
20 from mock import ANY, MagicMock, Mock, call, patch
21 from prbt_hardware_support.msg import OperationModes
22 from python_qt_binding.QtCore import QObject
23 from qt_gui.plugin import Plugin
24 from std_msgs.msg import Bool, Float64
25 
27 
28 
29 class MockContext(QObject):
30  def __init__(self):
31  super(MockContext, self).__init__()
32 
33  def serial_number(self):
34  return 0
35 
36  def add_widget(arg1, arg2):
37  pass
38 
39 
40 def extract_subscriber_mock_callback(mock, topic_name):
41  return [cb[1][2] for cb in mock.mock_calls if cb[1][0] == topic_name][0]
42 
43 
44 @patch('rospy.Subscriber')
45 @patch('pilz_status_indicator_rqt.status_indicator.PilzStatusIndicatorWidget')
46 class TestStatusIndicator(unittest.TestCase):
47  """
48  Testing the status indicator plugin to correctly interface with ROS.
49  """
50 
51  def test_init(self, _, SubscriberMock):
52  """Initialized Plugin and test if initialization methods are called
53  correctly."""
55  psi._widget.set_ROS_status.assert_called_once_with(False)
56  psi._widget.set_HW_status.assert_called_once_with(False)
57  psi._widget.set_operation_mode.assert_called_once_with(
58  OperationModes.UNKNOWN)
59  psi._widget.set_speed.assert_called_once_with(0.5)
60  SubscriberMock.assert_has_calls([
61  call(TOPIC_STATE_ROS, Bool, ANY),
62  call(TOPIC_STATE_HW, Bool, ANY),
63  call(TOPIC_OPERATION_MODE, OperationModes, ANY),
64  call(TOPIC_SPEED_OVERRIDE, Float64, ANY),
65  ])
66 
67  def test_status_prbt(self, _, SubscriberMock):
68  """Test if updates to the HW status are correctly passed from ROS to
69  the widget."""
71  psi._widget.reset_mock()
72 
73  diagnostic_prbt_callback = extract_subscriber_mock_callback(
74  SubscriberMock, TOPIC_STATE_HW)
75 
76  diagnostic_prbt_callback(Bool(False))
77  psi._widget.set_HW_status.assert_called_with(False)
78 
79  diagnostic_prbt_callback(Bool(True))
80  psi._widget.set_HW_status.assert_called_with(True)
81 
82  def test_status_ros(self, _, SubscriberMock):
83  """Test if updates to the ROS status are correctly passed from ROS to
84  the widget."""
86  psi._widget.reset_mock()
87 
88  diagnostic_ros_callback = extract_subscriber_mock_callback(
89  SubscriberMock, TOPIC_STATE_ROS)
90 
91  diagnostic_ros_callback(Bool(True))
92  psi._widget.set_ROS_status.assert_called_with(True)
93 
94  diagnostic_ros_callback(Bool(False))
95  psi._widget.set_ROS_status.assert_called_with(False)
96 
97  def test_operation_mode(self, _, SubscriberMock):
98  """Test if updates to the operation mode are correctly passed from ROS
99  to the widget."""
101  psi._widget.reset_mock()
102 
103  diagnostic_operation_mode_callback = extract_subscriber_mock_callback(
104  SubscriberMock, TOPIC_OPERATION_MODE)
105 
106  operation_mode_msg = OperationModes()
107 
108  operation_mode_msg.value = OperationModes.UNKNOWN
109  diagnostic_operation_mode_callback(operation_mode_msg)
110  psi._widget.set_operation_mode.assert_called_with(
111  OperationModes.UNKNOWN)
112 
113  operation_mode_msg.value = OperationModes.T1
114  diagnostic_operation_mode_callback(operation_mode_msg)
115  psi._widget.set_operation_mode.assert_called_with(OperationModes.T1)
116 
117  operation_mode_msg.value = OperationModes.T2
118  diagnostic_operation_mode_callback(operation_mode_msg)
119  psi._widget.set_operation_mode.assert_called_with(OperationModes.T2)
120 
121  operation_mode_msg.value = OperationModes.AUTO
122  diagnostic_operation_mode_callback(operation_mode_msg)
123  psi._widget.set_operation_mode.assert_called_with(OperationModes.AUTO)
124 
125  def test_set_speed(self, _, SubscriberMock):
126  """Test if updates to the speed override are correctly passed from ROS
127  to the widget."""
129  psi._widget.reset_mock()
130 
131  speed_callback = extract_subscriber_mock_callback(
132  SubscriberMock, TOPIC_SPEED_OVERRIDE)
133 
134  speed_msg = Float64()
135 
136  speed_msg.data = 0
137  speed_callback(speed_msg)
138  psi._widget.set_speed.assert_called_with(0)
139 
140  speed_msg.data = 0.5
141  speed_callback(speed_msg)
142  psi._widget.set_speed.assert_called_with(0.5)
143 
144  speed_msg.data = 1.0
145  speed_callback(speed_msg)
146  psi._widget.set_speed.assert_called_with(1.0)
147 
148 
149 if __name__ == '__main__':
150  import rosunit
151  rosunit.unitrun('pilz_status_indicator_rqt',
152  'test_status_indicator', TestStatusIndicator)
def extract_subscriber_mock_callback(mock, topic_name)


pilz_status_indicator_rqt
Author(s):
autogenerated on Tue Feb 2 2021 03:50:27