|
| 1 | +#!/usr/bin/env python3 |
| 2 | +# Copyright 2024, Universal Robots |
| 3 | +# |
| 4 | +# Redistribution and use in source and binary forms, with or without |
| 5 | +# modification, are permitted provided that the following conditions are met: |
| 6 | +# |
| 7 | +# * Redistributions of source code must retain the above copyright |
| 8 | +# notice, this list of conditions and the following disclaimer. |
| 9 | +# |
| 10 | +# * Redistributions in binary form must reproduce the above copyright |
| 11 | +# notice, this list of conditions and the following disclaimer in the |
| 12 | +# documentation and/or other materials provided with the distribution. |
| 13 | +# |
| 14 | +# * Neither the name of the {copyright_holder} nor the names of its |
| 15 | +# contributors may be used to endorse or promote products derived from |
| 16 | +# this software without specific prior written permission. |
| 17 | +# |
| 18 | +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
| 19 | +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
| 20 | +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
| 21 | +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE |
| 22 | +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR |
| 23 | +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF |
| 24 | +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS |
| 25 | +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN |
| 26 | +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) |
| 27 | +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
| 28 | +# POSSIBILITY OF SUCH DAMAGE. |
| 29 | + |
| 30 | +import rclpy |
| 31 | +from builtin_interfaces.msg import Duration |
| 32 | +from control_msgs.action import JointTrajectory |
| 33 | + |
| 34 | +from rclpy.action import ActionClient |
| 35 | +from rclpy.node import Node |
| 36 | +from trajectory_msgs.msg import JointTrajectory as JTmsg, JointTrajectoryPoint |
| 37 | +from ur_msgs.srv import SetIO |
| 38 | +from controller_manager_msgs.srv import ( |
| 39 | + UnloadController, |
| 40 | + LoadController, |
| 41 | + ConfigureController, |
| 42 | + SwitchController, |
| 43 | + ListControllers, |
| 44 | +) |
| 45 | +import time |
| 46 | + |
| 47 | +TIMEOUT_WAIT_SERVICE = 10 |
| 48 | +TIMEOUT_WAIT_SERVICE_INITIAL = 60 |
| 49 | +TIMEOUT_WAIT_ACTION = 10 |
| 50 | + |
| 51 | +ROBOT_JOINTS = [ |
| 52 | + "shoulder_pan_joint", |
| 53 | + "shoulder_lift_joint", |
| 54 | + "elbow_joint", |
| 55 | + "wrist_1_joint", |
| 56 | + "wrist_2_joint", |
| 57 | + "wrist_3_joint", |
| 58 | +] |
| 59 | + |
| 60 | + |
| 61 | +# Helper functions |
| 62 | +def waitForService(node, srv_name, srv_type, timeout=TIMEOUT_WAIT_SERVICE): |
| 63 | + client = node.create_client(srv_type, srv_name) |
| 64 | + if client.wait_for_service(timeout) is False: |
| 65 | + raise Exception(f"Could not reach service '{srv_name}' within timeout of {timeout}") |
| 66 | + |
| 67 | + node.get_logger().info(f"Successfully connected to service '{srv_name}'") |
| 68 | + return client |
| 69 | + |
| 70 | + |
| 71 | +def waitForAction(node, action_name, action_type, timeout=TIMEOUT_WAIT_ACTION): |
| 72 | + client = ActionClient(node, action_type, action_name) |
| 73 | + if client.wait_for_server(timeout) is False: |
| 74 | + raise Exception( |
| 75 | + f"Could not reach action server '{action_name}' within timeout of {timeout}" |
| 76 | + ) |
| 77 | + |
| 78 | + node.get_logger().info(f"Successfully connected to action '{action_name}'") |
| 79 | + return client |
| 80 | + |
| 81 | + |
| 82 | +class Robot: |
| 83 | + def __init__(self, node): |
| 84 | + self.node = node |
| 85 | + self.init_robot() |
| 86 | + |
| 87 | + def init_robot(self): |
| 88 | + service_interfaces = { |
| 89 | + "/io_and_status_controller/set_io": SetIO, |
| 90 | + "/controller_manager/load_controller": LoadController, |
| 91 | + "/controller_manager/unload_controller": UnloadController, |
| 92 | + "/controller_manager/configure_controller": ConfigureController, |
| 93 | + "/controller_manager/switch_controller": SwitchController, |
| 94 | + "/controller_manager/list_controllers": ListControllers, |
| 95 | + } |
| 96 | + self.service_clients = { |
| 97 | + srv_name: waitForService(self.node, srv_name, srv_type) |
| 98 | + for (srv_name, srv_type) in service_interfaces.items() |
| 99 | + } |
| 100 | + self.jtc_action_client = waitForAction( |
| 101 | + self.node, |
| 102 | + "/passthrough_trajectory_controller/forward_joint_trajectory", |
| 103 | + JointTrajectory, |
| 104 | + ) |
| 105 | + time.sleep(2) |
| 106 | + |
| 107 | + def set_io(self, pin, value): |
| 108 | + """Test to set an IO.""" |
| 109 | + set_io_req = SetIO.Request() |
| 110 | + set_io_req.fun = 1 |
| 111 | + set_io_req.pin = pin |
| 112 | + set_io_req.state = value |
| 113 | + |
| 114 | + self.call_service("/io_and_status_controller/set_io", set_io_req) |
| 115 | + |
| 116 | + def send_trajectory(self, waypts, time_vec): |
| 117 | + """Send robot trajectory.""" |
| 118 | + if len(waypts) != len(time_vec): |
| 119 | + raise Exception("waypoints vector and time vec should be same length") |
| 120 | + |
| 121 | + # Construct test trajectory |
| 122 | + joint_trajectory = JTmsg() |
| 123 | + joint_trajectory.joint_names = ROBOT_JOINTS |
| 124 | + for i in range(len(waypts)): |
| 125 | + point = JointTrajectoryPoint() |
| 126 | + point.positions = waypts[i] |
| 127 | + point.time_from_start = time_vec[i] |
| 128 | + joint_trajectory.points.append(point) |
| 129 | + |
| 130 | + # Sending trajectory goal |
| 131 | + goal_response = self.call_action( |
| 132 | + self.jtc_action_client, JointTrajectory.Goal(trajectory=joint_trajectory) |
| 133 | + ) |
| 134 | + if goal_response.accepted is False: |
| 135 | + raise Exception("trajectory was not accepted") |
| 136 | + |
| 137 | + # Verify execution |
| 138 | + result = self.get_result(self.jtc_action_client, goal_response) |
| 139 | + return result |
| 140 | + |
| 141 | + def call_service(self, srv_name, request): |
| 142 | + future = self.service_clients[srv_name].call_async(request) |
| 143 | + rclpy.spin_until_future_complete(self.node, future) |
| 144 | + if future.result() is not None: |
| 145 | + return future.result() |
| 146 | + else: |
| 147 | + raise Exception(f"Exception while calling service: {future.exception()}") |
| 148 | + |
| 149 | + def call_action(self, ac_client, g): |
| 150 | + future = ac_client.send_goal_async(g) |
| 151 | + rclpy.spin_until_future_complete(self.node, future) |
| 152 | + |
| 153 | + if future.result() is not None: |
| 154 | + return future.result() |
| 155 | + else: |
| 156 | + raise Exception(f"Exception while calling action: {future.exception()}") |
| 157 | + |
| 158 | + def get_result(self, ac_client, goal_response): |
| 159 | + future_res = ac_client._get_result_async(goal_response) |
| 160 | + rclpy.spin_until_future_complete(self.node, future_res) |
| 161 | + if future_res.result() is not None: |
| 162 | + return future_res.result().result |
| 163 | + else: |
| 164 | + raise Exception(f"Exception while calling action: {future_res.exception()}") |
| 165 | + |
| 166 | + def load_passthrough_controller(self): |
| 167 | + list_request = ListControllers.Request() |
| 168 | + list_response = robot.call_service("/controller_manager/list_controllers", list_request) |
| 169 | + names = [] |
| 170 | + # Find loaded controllers |
| 171 | + for controller in list_response.controller: |
| 172 | + names.append(controller.name) |
| 173 | + # Check whether the passthrough controller is already loaded |
| 174 | + try: |
| 175 | + names.index("passthrough_trajectory_controller") |
| 176 | + except ValueError: |
| 177 | + print("Loading controller") |
| 178 | + load_request = LoadController.Request() |
| 179 | + load_request.name = "passthrough_trajectory_controller" |
| 180 | + self.call_service("/controller_manager/load_controller", load_request) |
| 181 | + configure_request = ConfigureController.Request() |
| 182 | + configure_request.name = "passthrough_trajectory_controller" |
| 183 | + self.call_service("/controller_manager/configure_controller", configure_request) |
| 184 | + list_request = ListControllers.Request() |
| 185 | + list_response = robot.call_service("/controller_manager/list_controllers", list_request) |
| 186 | + names.clear() |
| 187 | + # Update the list of controller names. |
| 188 | + for controller in list_response.controller: |
| 189 | + names.append(controller.name) |
| 190 | + id = names.index("passthrough_trajectory_controller") |
| 191 | + switch_request = SwitchController.Request() |
| 192 | + # Check if passthrough controller is inactive, and activate it if it is. |
| 193 | + if list_response.controller[id].state == "inactive": |
| 194 | + switch_request.activate_controllers = ["passthrough_trajectory_controller"] |
| 195 | + # Check that the scaled joint trajectory controller is loaded and active, deactivate if it is. |
| 196 | + try: |
| 197 | + id = names.index("scaled_joint_trajectory_controller") |
| 198 | + if list_response.controller[id].state == "active": |
| 199 | + switch_request.deactivate_controllers = ["scaled_joint_trajectory_controller"] |
| 200 | + except ValueError: |
| 201 | + switch_request.deactivate_controllers = [] |
| 202 | + finally: |
| 203 | + switch_request.strictness = 1 # Best effort switching, will not terminate program if controller is already running |
| 204 | + switch_request.activate_asap = False |
| 205 | + switch_request.timeout = Duration(sec=2, nanosec=0) |
| 206 | + self.call_service("/controller_manager/switch_controller", switch_request) |
| 207 | + # Try unloading the scaled joint trajectory controller |
| 208 | + try: |
| 209 | + names.index("scaled_joint_trajectory_controller") |
| 210 | + unload_request = UnloadController.Request() |
| 211 | + unload_request.name = "scaled_joint_trajectory_controller" |
| 212 | + self.call_service("/controller_manager/unload_controller", unload_request) |
| 213 | + except ValueError: |
| 214 | + print("scaled_joint_trajectory_controller not loaded, skipping unload") |
| 215 | + # Connect to the passthrough controller action |
| 216 | + finally: |
| 217 | + self.jtc_action_client = waitForAction( |
| 218 | + self.node, |
| 219 | + "/passthrough_trajectory_controller/forward_joint_trajectory", |
| 220 | + JointTrajectory, |
| 221 | + ) |
| 222 | + time.sleep(2) |
| 223 | + |
| 224 | + def switch_controller(self, active, inactive): |
| 225 | + switch_request = SwitchController.Request() |
| 226 | + # Check if passthrough controller is inactive, and activate it if it is. |
| 227 | + switch_request.activate_controllers = [active] |
| 228 | + # Check that the scaled joint trajectory controller is loaded and active, deactivate if it is. |
| 229 | + switch_request.deactivate_controllers = [inactive] |
| 230 | + switch_request.strictness = ( |
| 231 | + 1 # Best effort switching, will not terminate program if controller is already running |
| 232 | + ) |
| 233 | + switch_request.activate_asap = False |
| 234 | + switch_request.timeout = Duration(sec=2, nanosec=0) |
| 235 | + self.call_service("/controller_manager/switch_controller", switch_request) |
| 236 | + |
| 237 | + |
| 238 | +if __name__ == "__main__": |
| 239 | + rclpy.init() |
| 240 | + node = Node("robot_driver_test") |
| 241 | + robot = Robot(node) |
| 242 | + |
| 243 | + # The following list are arbitrary joint positions, change according to your own needs |
| 244 | + waypts = [ |
| 245 | + [-1, -2.5998, -1.004, -2.676, -0.992, -1.5406], |
| 246 | + [-0.1, -2.6998, -1.104, -2.676, -0.992, -1.5406], |
| 247 | + [-1, -2.5998, -1.004, -2.676, -0.992, -1.5406], |
| 248 | + ] |
| 249 | + time_vec = [Duration(sec=4, nanosec=0), Duration(sec=8, nanosec=0), Duration(sec=12, nanosec=0)] |
| 250 | + |
| 251 | + # Execute trajectory on robot, make sure that the robot is booted and the control script is running |
| 252 | + robot.send_trajectory(waypts, time_vec) |
0 commit comments