Skip to content

Commit c862bc0

Browse files
Use the library's coroutines in the ROS2 driver
This is now as thin as we want it. Also drop receiving the module's state periodically in the driver. The library does that now.
1 parent 56116a0 commit c862bc0

File tree

4 files changed

+11
-52
lines changed

4 files changed

+11
-52
lines changed

schunk_gripper_driver/launch/driver.launch.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222

2323
port = DeclareLaunchArgument(
2424
"port",
25-
default_value="/dev/ur-ttylink/ttyTool",
25+
default_value="/dev/ttyUSB0",
2626
description="The gripper's serial port",
2727
)
2828
device_id = DeclareLaunchArgument(

schunk_gripper_driver/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111
<depend>launch</depend>
1212
<depend>launch_ros</depend>
1313
<depend>schunk_gripper_library</depend>
14+
<depend>std_srvs</depend>
1415

1516
<test_depend>launch_pytest</test_depend>
1617
<test_depend>ament_copyright</test_depend>

schunk_gripper_driver/schunk_gripper_driver/driver.py

+3-47
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
from rclpy.lifecycle import TransitionCallbackReturn
2323
from schunk_gripper_library.driver import Driver as GripperDriver
2424
from std_srvs.srv import Trigger
25-
import time
25+
import asyncio
2626

2727

2828
class Driver(Node):
@@ -87,62 +87,18 @@ def on_shutdown(self, state: State) -> TransitionCallbackReturn:
8787
return TransitionCallbackReturn.SUCCESS
8888

8989
def status_update(self):
90-
self.gripper.receive_plc_input()
9190
self.get_logger().info(f"---> Status update: {self.gripper.get_plc_input()}")
9291

9392
# Service callbacks
9493
def _acknowledge_cb(self, request: Trigger.Request, response: Trigger.Response):
9594
self.get_logger().info("---> Acknowledge")
96-
# Reset
97-
self.gripper.clear_plc_output()
98-
self.gripper.set_control_bit(bit=0, value=True)
99-
self.gripper.send_plc_output()
100-
time.sleep(0.5)
101-
# Acknowledge
102-
self.gripper.set_control_bit(bit=2, value=True)
103-
for bit in self.gripper.valid_control_bits:
104-
self.get_logger().info(
105-
f"---> Control bit {bit}: {self.gripper.get_control_bit(bit=bit)}"
106-
)
107-
cmd_before = self.gripper.get_status_bit(bit=5)
108-
self.gripper.send_plc_output()
109-
time.sleep(0.5)
110-
self.gripper.receive_plc_input()
111-
cmd_after = self.gripper.get_status_bit(bit=5)
112-
self.get_logger().info(f"---> PLC input: {self.gripper.get_plc_input()}")
113-
for bit in self.gripper.valid_status_bits:
114-
self.get_logger().info(
115-
f"---> Status bit {bit}: {self.gripper.get_status_bit(bit=bit)}"
116-
)
117-
118-
response.success = self.gripper.get_status_bit(bit=0) == 1 and (
119-
cmd_after != cmd_before
120-
)
95+
response.success = asyncio.run(self.gripper.acknowledge())
12196
response.message = self.gripper.get_status_diagnostics()
12297
return response
12398

12499
def _fast_stop_cb(self, request: Trigger.Request, response: Trigger.Response):
125100
self.get_logger().info("---> Fast stop")
126-
self.gripper.clear_plc_output()
127-
self.gripper.set_control_bit(bit=0, value=False)
128-
for bit in self.gripper.valid_control_bits:
129-
self.get_logger().info(
130-
f"---> Control bit {bit}: {self.gripper.get_control_bit(bit=bit)}"
131-
)
132-
cmd_before = self.gripper.get_status_bit(bit=5)
133-
self.gripper.send_plc_output()
134-
time.sleep(0.5)
135-
self.gripper.receive_plc_input()
136-
cmd_after = self.gripper.get_status_bit(bit=5)
137-
self.get_logger().info(f"---> PLC input: {self.gripper.get_plc_input()}")
138-
for bit in self.gripper.valid_status_bits:
139-
self.get_logger().info(
140-
f"---> Status bit {bit}: {self.gripper.get_status_bit(bit=bit)}"
141-
)
142-
143-
response.success = self.gripper.get_status_bit(bit=4) == 1 and (
144-
cmd_after != cmd_before
145-
)
101+
response.success = asyncio.run(self.gripper.fast_stop())
146102
response.message = self.gripper.get_status_diagnostics()
147103
return response
148104

schunk_gripper_driver/test/test_services.py

+6-4
Original file line numberDiff line numberDiff line change
@@ -49,11 +49,13 @@ def test_driver_implements_acknowledge(lifecycle_interface):
4949
client.wait_for_service(timeout_sec=2)
5050
future = client.call_async(Trigger.Request())
5151
rclpy.spin_until_future_complete(node, future)
52+
lifecycle_interface.change_state(Transition.TRANSITION_CLEANUP)
5253

5354
assert future.result().success
54-
expected_msg = "error_code: 0, warning_code: 0, additional_code: 0" # everything ok
55+
expected_msg = (
56+
"error_code: 0x0, warning_code: 0x0, additional_code: 0x0" # everything ok
57+
)
5558
assert future.result().message == expected_msg
56-
lifecycle_interface.change_state(Transition.TRANSITION_CLEANUP)
5759

5860

5961
@skip_without_gripper
@@ -65,8 +67,8 @@ def test_driver_implements_fast_stop(lifecycle_interface):
6567
client.wait_for_service(timeout_sec=2)
6668
future = client.call_async(Trigger.Request())
6769
rclpy.spin_until_future_complete(node, future)
70+
lifecycle_interface.change_state(Transition.TRANSITION_CLEANUP)
6871

6972
assert future.result().success
70-
expected_msg = "error_code: 0, warning_code: 0, additional_code: 0" # everything ok
73+
expected_msg = "error_code: 0xD9, warning_code: 0x0, additional_code: 0x0"
7174
assert future.result().message == expected_msg
72-
lifecycle_interface.change_state(Transition.TRANSITION_CLEANUP)

0 commit comments

Comments
 (0)