Skip to content

Commit

Permalink
Move robot starting to dashboard interface
Browse files Browse the repository at this point in the history
  • Loading branch information
RobertWilbrandt committed Oct 19, 2023
1 parent 23d74e4 commit 4e72386
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 27 deletions.
15 changes: 2 additions & 13 deletions ur_robot_driver/test/robot_driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,13 +41,12 @@
from rclpy.node import Node
from sensor_msgs.msg import JointState
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
from ur_dashboard_msgs.msg import RobotMode
from ur_msgs.msg import IOStates

sys.path.append(os.path.dirname(__file__))
from test_common import ( # noqa: E402
ControllerManagerInterface,
ActionInterface,
ControllerManagerInterface,
DashboardInterface,
IoStatusInterface,
generate_driver_test_description,
Expand Down Expand Up @@ -101,17 +100,7 @@ def init_robot(self):
)

def setUp(self):
# Start robot
self.assertTrue(self._dashboard_interface.power_on().success)
self.assertTrue(self._dashboard_interface.brake_release().success)

time.sleep(1)

robot_mode = self._dashboard_interface.get_robot_mode()
self.assertTrue(robot_mode.success)
self.assertEqual(robot_mode.robot_mode.mode, RobotMode.RUNNING)

self.assertTrue(self._dashboard_interface.stop().success)
self._dashboard_interface.start_robot()
time.sleep(1)
self.assertTrue(self._io_status_controller_interface.resend_robot_program().success)

Expand Down
20 changes: 19 additions & 1 deletion ur_robot_driver/test/test_common.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
from launch_testing.actions import ReadyToTest
from rclpy.action import ActionClient
from std_srvs.srv import Trigger
from ur_dashboard_msgs.msg import RobotMode
from ur_dashboard_msgs.srv import (
GetLoadedProgram,
GetProgramState,
Expand Down Expand Up @@ -199,7 +200,24 @@ class DashboardInterface(
"stop": Trigger,
},
):
pass
def start_robot(self):
self._check_call(self.power_on())
self._check_call(self.brake_release())

time.sleep(1)

robot_mode = self.get_robot_mode()
self._check_call(robot_mode)
if robot_mode.robot_mode.mode != RobotMode.RUNNING:
raise Exception(
f"Incorrect robot mode: Expected {RobotMode.RUNNING}, got {robot_mode.robot_mode.mode}"
)

self._check_call(self.stop())

def _check_call(self, result):
if not result.success:
raise Exception("Service call not successful")


class ControllerManagerInterface(
Expand Down
15 changes: 2 additions & 13 deletions ur_robot_driver/test/urscript_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,15 +35,14 @@
import rclpy
import rclpy.node
from std_msgs.msg import String as StringMsg
from ur_dashboard_msgs.msg import RobotMode
from ur_msgs.msg import IOStates

sys.path.append(os.path.dirname(__file__))
from test_common import ( # noqa: E402
ControllerManagerInterface,
DashboardInterface,
IoStatusInterface,
generate_driver_test_description,
ControllerManagerInterface,
)

ROBOT_IP = "192.168.56.101"
Expand Down Expand Up @@ -78,17 +77,7 @@ def init_robot(self):
)

def setUp(self):
# Start robot
self.assertTrue(self._dashboard_interface.power_on().success)
self.assertTrue(self._dashboard_interface.brake_release().success)

time.sleep(1)

robot_mode = self._dashboard_interface.get_robot_mode()
self.assertTrue(robot_mode.success)
self.assertEqual(robot_mode.robot_mode.mode, RobotMode.RUNNING)

self.assertTrue(self._dashboard_interface.stop().success)
self._dashboard_interface.start_robot()
time.sleep(1)
self.assertTrue(self._io_status_controller_interface.resend_robot_program().success)

Expand Down

0 comments on commit 4e72386

Please sign in to comment.