test_sr_ur_unlock_right.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Copyright 2021 Shadow Robot Company Ltd.
3 #
4 # This program is free software: you can redistribute it and/or modify it
5 # under the terms of the GNU General Public License as published by the Free
6 # Software Foundation version 2 of the License.
7 #
8 # This program is distributed in the hope that it will be useful, but WITHOUT
9 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11 # more details.
12 #
13 # You should have received a copy of the GNU General Public License along
14 # with this program. If not, see <http://www.gnu.org/licenses/>.
15 
16 import rospy
17 import rostest
18 from actionlib_msgs.msg import GoalStatusArray
19 from unittest import TestCase
20 from std_msgs.msg import Bool
21 from std_srvs.srv import Trigger
22 from ur_dashboard_msgs.srv import IsProgramRunning
23 from sr_robot_launch.sr_ur_arm_unlock import SrUrUnlock
24 from sr_robot_launch.mock_sr_ur_robot_hw import MockUrRobotHW
25 from ur_dashboard_msgs.msg import SafetyMode, ProgramState, RobotMode
26 from sr_robot_launch.common_sr_ur_unlock_tests import CommonTests
27 import sys
28 
29 
31  """
32  Tests sr_ur_arm_unlock
33  """
34  @classmethod
35  def setUpClass(cls):
36  cls.service_string = {}
37  cls.namespaces = ['/ra_sr_ur_robot_hw']
38  cls.params = ['/headless_mode']
39  for ns in cls.namespaces:
40  for param in cls.params:
41  rospy.set_param(ns + param, True)
42  cls.service_string['right'] = '/ra_sr_ur_robot_hw/dashboard/program_running'
44  cls.mock_dashboard = {}
45  cls.mock_dashboard['right'] = MockUrRobotHW('right')
46 
47  def setUp(self):
48  for key, value in self.mock_dashboard.items():
49  value.reinitialize()
50 
51  def tearDown(self):
52  pass
53 
54  @classmethod
55  def tearDownClass(cls):
56  pass
57 
59  self.arm_setup('right')
60 
61  def test_fault_right(self):
62  self.fault('right')
63 
65  self.e_stop('right', release_estop_before_pedal=True)
66 
68  self.e_stop('right', release_estop_before_pedal=False)
69 
71  self.arm_power_cycle('right')
72 
74  self.arm_mock_dashboard_server('right')
75 
77  self.arm_setup('right')
78 
79 
80 if __name__ == "__main__":
81  PKGNAME = 'sr_robot_launch'
82  NODENAME = 'test_sr_ur_unlock_right'
83  rospy.init_node(NODENAME)
84  rostest.rosrun(PKGNAME, NODENAME, TestSrUrUnlockRight)
def e_stop(self, side, release_estop_before_pedal=True)


sr_robot_launch
Author(s): Kirsty Ellis
autogenerated on Mon Feb 28 2022 23:52:27