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
25 from ur_dashboard_msgs.msg
import SafetyMode, ProgramState, RobotMode
32 Tests sr_ur_arm_unlock 41 rospy.set_param(ns + param,
True)
42 cls.
service_string[
'right'] =
'/ra_sr_ur_robot_hw/dashboard/program_running' 59 self.arm_setup(
'right')
65 self.
e_stop(
'right', release_estop_before_pedal=
True)
68 self.
e_stop(
'right', release_estop_before_pedal=
False)
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 arm_power_cycle(self, side)
def test_e_stop_right_2(self)
def test_arm_mock_dashboard_server_right(self)
def test_e_stop_right_1(self)
def arm_setup(self, side)
def test_arm_startup_right_again(self)
def test_fault_right(self)
def arm_mock_dashboard_server(self, side)
def test_arm_power_cycle_right(self)
def e_stop(self, side, release_estop_before_pedal=True)
def test_arm_startup_right(self)