29
29
30
30
import rclpy
31
31
from rclpy .node import Node
32
+ from rclpy .callback_groups import MutuallyExclusiveCallbackGroup
32
33
from sensor_msgs .msg import Joy
33
34
from std_msgs .msg import Int16
34
35
from std_srvs .srv import SetBool
@@ -120,27 +121,36 @@ def __init__(self):
120
121
self ._pub_buzzer = self .create_publisher (Int16 , 'buzzer' , 1 )
121
122
self ._pub_leds = self .create_publisher (Leds , 'leds' , 1 )
122
123
123
- self ._sub_joy = self .create_subscription (
124
- Joy , 'joy' , self ._callback_joy , 1 )
125
- self ._sub_lightsensor = self .create_subscription (
126
- LightSensors , 'light_sensors' , self ._callback_lightsensors , 1 )
127
- self ._sub_switches = self .create_subscription (
128
- Switches , 'switches' , self ._callback_switches , 1 )
124
+ self ._sub_cb_group = MutuallyExclusiveCallbackGroup ()
125
+ self ._client_cb_group = MutuallyExclusiveCallbackGroup ()
129
126
130
- self ._client_get_state = self .create_client (GetState , 'raspimouse/get_state' )
127
+ self ._client_get_state = self .create_client (
128
+ GetState , 'raspimouse/get_state' , callback_group = self ._client_cb_group )
131
129
while not self ._client_get_state .wait_for_service (timeout_sec = 1.0 ):
132
130
self ._node_logger .warn (self ._client_get_state .srv_name + ' service not available' )
133
131
134
- self ._client_change_state = self .create_client (ChangeState , 'raspimouse/change_state' )
132
+ self ._client_change_state = self .create_client (
133
+ ChangeState , 'raspimouse/change_state' , callback_group = self ._client_cb_group )
135
134
while not self ._client_change_state .wait_for_service (timeout_sec = 1.0 ):
136
135
self ._node_logger .warn (self ._client_change_state .srv_name + ' service not available' )
137
136
self ._activate_raspimouse ()
138
137
139
- self ._client_motor_power = self .create_client (SetBool , 'motor_power' )
138
+ self ._client_motor_power = self .create_client (
139
+ SetBool , 'motor_power' , callback_group = self ._client_cb_group )
140
140
while not self ._client_motor_power .wait_for_service (timeout_sec = 1.0 ):
141
141
self ._node_logger .warn (self ._client_motor_power .srv_name + ' service not available' )
142
142
self ._motor_on ()
143
143
144
+ self ._sub_joy = self .create_subscription (
145
+ Joy , 'joy' , self ._callback_joy , 1 ,
146
+ callback_group = self ._sub_cb_group )
147
+ self ._sub_lightsensor = self .create_subscription (
148
+ LightSensors , 'light_sensors' , self ._callback_lightsensors , 1 ,
149
+ callback_group = self ._sub_cb_group )
150
+ self ._sub_switches = self .create_subscription (
151
+ Switches , 'switches' , self ._callback_switches , 1 ,
152
+ callback_group = self ._sub_cb_group )
153
+
144
154
def _activate_raspimouse (self ):
145
155
self ._set_mouse_lifecycle_state (Transition .TRANSITION_CONFIGURE )
146
156
self ._set_mouse_lifecycle_state (Transition .TRANSITION_ACTIVATE )
@@ -151,14 +161,12 @@ def _set_mouse_lifecycle_state(self, transition_id):
151
161
request = ChangeState .Request ()
152
162
request .transition .id = transition_id
153
163
future = self ._client_change_state .call_async (request )
154
- executor = rclpy .executors .SingleThreadedExecutor (context = self .context )
155
- rclpy .spin_until_future_complete (self , future , executor = executor )
164
+ rclpy .spin_until_future_complete (self , future )
156
165
return future .result ().success
157
166
158
167
def _get_mouse_lifecycle_state (self ):
159
168
future = self ._client_get_state .call_async (GetState .Request ())
160
- executor = rclpy .executors .SingleThreadedExecutor (context = self .context )
161
- rclpy .spin_until_future_complete (self , future , executor = executor )
169
+ rclpy .spin_until_future_complete (self , future )
162
170
return future .result ().current_state .label
163
171
164
172
def _motor_request (self , request_data = False ):
@@ -194,6 +202,7 @@ def _joy_shutdown(self, joy_msg):
194
202
self ._motor_off ()
195
203
self ._set_mouse_lifecycle_state (Transition .TRANSITION_DEACTIVATE )
196
204
self .destroy_node ()
205
+ raise SystemExit
197
206
198
207
def _joy_motor_onoff (self , joy_msg ):
199
208
if joy_msg .buttons [self ._BUTTON_MOTOR_ON ]:
@@ -397,7 +406,10 @@ def main(args=None):
397
406
398
407
joy_wrapper = JoyWrapper ()
399
408
400
- rclpy .spin (joy_wrapper )
409
+ try :
410
+ rclpy .spin (joy_wrapper )
411
+ except SystemExit :
412
+ rclpy .logging .get_logger ("joystick_control" ).info ('_joy_shutdown() has been executed' )
401
413
402
414
joy_wrapper .destroy_node ()
403
415
0 commit comments