|
22 | 22 | from rclpy.lifecycle import TransitionCallbackReturn
|
23 | 23 | from schunk_gripper_library.driver import Driver as GripperDriver
|
24 | 24 | from std_srvs.srv import Trigger
|
25 |
| -import time |
| 25 | +import asyncio |
26 | 26 |
|
27 | 27 |
|
28 | 28 | class Driver(Node):
|
@@ -87,62 +87,18 @@ def on_shutdown(self, state: State) -> TransitionCallbackReturn:
|
87 | 87 | return TransitionCallbackReturn.SUCCESS
|
88 | 88 |
|
89 | 89 | def status_update(self):
|
90 |
| - self.gripper.receive_plc_input() |
91 | 90 | self.get_logger().info(f"---> Status update: {self.gripper.get_plc_input()}")
|
92 | 91 |
|
93 | 92 | # Service callbacks
|
94 | 93 | def _acknowledge_cb(self, request: Trigger.Request, response: Trigger.Response):
|
95 | 94 | 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()) |
121 | 96 | response.message = self.gripper.get_status_diagnostics()
|
122 | 97 | return response
|
123 | 98 |
|
124 | 99 | def _fast_stop_cb(self, request: Trigger.Request, response: Trigger.Response):
|
125 | 100 | 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()) |
146 | 102 | response.message = self.gripper.get_status_diagnostics()
|
147 | 103 | return response
|
148 | 104 |
|
|
0 commit comments