Skip to content

Commit 05aa97e

Browse files
authored
Update the shutdown handling in all of the Python examples. (#379)
* Update the shutdown handling in all of the Python examples. In particular, we should deal with KeyboardInterrupt (by just doing 'pass'), as well as ExternalShutdownException (which can come from the executor). In all cases, we should call 'rclpy.try_shutdown()' to cleanup at the end. Note well that I removed some of the *destroy() calls in the cleanup. That's because they weren't correct in all cases, and to fix them up properly would really require us to have a nested set of try..except statements. Given that these are examples, having that complex set of exception handling didn't seem like the correct way to go here. Signed-off-by: Chris Lalancette <clalancette@gmail.com>
1 parent b14d2a8 commit 05aa97e

File tree

28 files changed

+407
-329
lines changed

28 files changed

+407
-329
lines changed

rclpy/actions/minimal_action_client/examples_rclpy_minimal_action_client/client.py

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,14 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
import sys
16+
1517
from action_msgs.msg import GoalStatus
1618
from example_interfaces.action import Fibonacci
1719

1820
import rclpy
1921
from rclpy.action import ActionClient
22+
from rclpy.executors import ExternalShutdownException
2023
from rclpy.node import Node
2124

2225

@@ -70,11 +73,16 @@ def send_goal(self):
7073
def main(args=None):
7174
rclpy.init(args=args)
7275

73-
action_client = MinimalActionClient()
76+
try:
77+
action_client = MinimalActionClient()
7478

75-
action_client.send_goal()
79+
action_client.send_goal()
7680

77-
rclpy.spin(action_client)
81+
rclpy.spin(action_client)
82+
except KeyboardInterrupt:
83+
pass
84+
except ExternalShutdownException:
85+
sys.exit(1)
7886

7987

8088
if __name__ == '__main__':

rclpy/actions/minimal_action_client/examples_rclpy_minimal_action_client/client_cancel.py

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,13 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
import sys
16+
1517
from example_interfaces.action import Fibonacci
1618

1719
import rclpy
1820
from rclpy.action import ActionClient
21+
from rclpy.executors import ExternalShutdownException
1922
from rclpy.node import Node
2023

2124

@@ -78,11 +81,16 @@ def send_goal(self):
7881
def main(args=None):
7982
rclpy.init(args=args)
8083

81-
action_client = MinimalActionClient()
84+
try:
85+
action_client = MinimalActionClient()
8286

83-
action_client.send_goal()
87+
action_client.send_goal()
8488

85-
rclpy.spin(action_client)
89+
rclpy.spin(action_client)
90+
except KeyboardInterrupt:
91+
pass
92+
except ExternalShutdownException:
93+
sys.exit(1)
8694

8795

8896
if __name__ == '__main__':

rclpy/actions/minimal_action_client/examples_rclpy_minimal_action_client/client_not_composable.py

Lines changed: 35 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -12,12 +12,15 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
import sys
16+
1517
from action_msgs.msg import GoalStatus
1618

1719
from example_interfaces.action import Fibonacci
1820

1921
import rclpy
2022
from rclpy.action import ActionClient
23+
from rclpy.executors import ExternalShutdownException
2124

2225

2326
def feedback_cb(logger, feedback):
@@ -27,50 +30,51 @@ def feedback_cb(logger, feedback):
2730
def main(args=None):
2831
rclpy.init(args=args)
2932

30-
node = rclpy.create_node('minimal_action_client')
31-
32-
action_client = ActionClient(node, Fibonacci, 'fibonacci')
33+
try:
34+
node = rclpy.create_node('minimal_action_client')
3335

34-
node.get_logger().info('Waiting for action server...')
36+
action_client = ActionClient(node, Fibonacci, 'fibonacci')
3537

36-
action_client.wait_for_server()
38+
node.get_logger().info('Waiting for action server...')
3739

38-
goal_msg = Fibonacci.Goal()
39-
goal_msg.order = 10
40+
action_client.wait_for_server()
4041

41-
node.get_logger().info('Sending goal request...')
42+
goal_msg = Fibonacci.Goal()
43+
goal_msg.order = 10
4244

43-
send_goal_future = action_client.send_goal_async(
44-
goal_msg, feedback_callback=lambda feedback: feedback_cb(node.get_logger(), feedback))
45+
node.get_logger().info('Sending goal request...')
4546

46-
rclpy.spin_until_future_complete(node, send_goal_future)
47+
send_goal_future = action_client.send_goal_async(
48+
goal_msg, feedback_callback=lambda feedback: feedback_cb(node.get_logger(), feedback))
4749

48-
goal_handle = send_goal_future.result()
50+
rclpy.spin_until_future_complete(node, send_goal_future)
4951

50-
if not goal_handle.accepted:
51-
node.get_logger().info('Goal rejected :(')
52-
action_client.destroy()
53-
node.destroy_node()
54-
rclpy.shutdown()
55-
return
52+
goal_handle = send_goal_future.result()
5653

57-
node.get_logger().info('Goal accepted :)')
54+
if not goal_handle.accepted:
55+
node.get_logger().info('Goal rejected :(')
56+
action_client.destroy()
57+
node.destroy_node()
58+
rclpy.shutdown()
59+
return
5860

59-
get_result_future = goal_handle.get_result_async()
61+
node.get_logger().info('Goal accepted :)')
6062

61-
rclpy.spin_until_future_complete(node, get_result_future)
63+
get_result_future = goal_handle.get_result_async()
6264

63-
result = get_result_future.result().result
64-
status = get_result_future.result().status
65-
if status == GoalStatus.STATUS_SUCCEEDED:
66-
node.get_logger().info(
67-
'Goal succeeded! Result: {0}'.format(result.sequence))
68-
else:
69-
node.get_logger().info('Goal failed with status code: {0}'.format(status))
65+
rclpy.spin_until_future_complete(node, get_result_future)
7066

71-
action_client.destroy()
72-
node.destroy_node()
73-
rclpy.shutdown()
67+
result = get_result_future.result().result
68+
status = get_result_future.result().status
69+
if status == GoalStatus.STATUS_SUCCEEDED:
70+
node.get_logger().info(
71+
'Goal succeeded! Result: {0}'.format(result.sequence))
72+
else:
73+
node.get_logger().info('Goal failed with status code: {0}'.format(status))
74+
except KeyboardInterrupt:
75+
pass
76+
except ExternalShutdownException:
77+
sys.exit(1)
7478

7579

7680
if __name__ == '__main__':

rclpy/actions/minimal_action_server/examples_rclpy_minimal_action_server/server.py

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,15 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
import sys
1516
import time
1617

1718
from example_interfaces.action import Fibonacci
1819

1920
import rclpy
2021
from rclpy.action import ActionServer, CancelResponse, GoalResponse
2122
from rclpy.callback_groups import ReentrantCallbackGroup
23+
from rclpy.executors import ExternalShutdownException
2224
from rclpy.executors import MultiThreadedExecutor
2325
from rclpy.node import Node
2426

@@ -92,15 +94,17 @@ async def execute_callback(self, goal_handle):
9294
def main(args=None):
9395
rclpy.init(args=args)
9496

95-
minimal_action_server = MinimalActionServer()
97+
try:
98+
minimal_action_server = MinimalActionServer()
9699

97-
# Use a MultiThreadedExecutor to enable processing goals concurrently
98-
executor = MultiThreadedExecutor()
100+
# Use a MultiThreadedExecutor to enable processing goals concurrently
101+
executor = MultiThreadedExecutor()
99102

100-
rclpy.spin(minimal_action_server, executor=executor)
101-
102-
minimal_action_server.destroy()
103-
rclpy.shutdown()
103+
rclpy.spin(minimal_action_server, executor=executor)
104+
except KeyboardInterrupt:
105+
pass
106+
except ExternalShutdownException:
107+
sys.exit(1)
104108

105109

106110
if __name__ == '__main__':

rclpy/actions/minimal_action_server/examples_rclpy_minimal_action_server/server_defer.py

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,15 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
import sys
1516
import time
1617

1718
from example_interfaces.action import Fibonacci
1819

1920
import rclpy
2021
from rclpy.action import ActionServer, CancelResponse, GoalResponse
2122
from rclpy.callback_groups import ReentrantCallbackGroup
23+
from rclpy.executors import ExternalShutdownException
2224
from rclpy.executors import MultiThreadedExecutor
2325
from rclpy.node import Node
2426

@@ -106,15 +108,17 @@ async def execute_callback(self, goal_handle):
106108
def main(args=None):
107109
rclpy.init(args=args)
108110

109-
minimal_action_server = MinimalActionServer()
111+
try:
112+
minimal_action_server = MinimalActionServer()
110113

111-
# Use a MultiThreadedExecutor to enable processing goals concurrently
112-
executor = MultiThreadedExecutor()
114+
# Use a MultiThreadedExecutor to enable processing goals concurrently
115+
executor = MultiThreadedExecutor()
113116

114-
rclpy.spin(minimal_action_server, executor=executor)
115-
116-
minimal_action_server.destroy()
117-
rclpy.shutdown()
117+
rclpy.spin(minimal_action_server, executor=executor)
118+
except KeyboardInterrupt:
119+
pass
120+
except ExternalShutdownException:
121+
sys.exit(1)
118122

119123

120124
if __name__ == '__main__':

rclpy/actions/minimal_action_server/examples_rclpy_minimal_action_server/server_not_composable.py

Lines changed: 26 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,15 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
import sys
1516
import time
1617

1718
from example_interfaces.action import Fibonacci
1819

1920
import rclpy
2021
from rclpy.action import ActionServer, CancelResponse
2122
from rclpy.callback_groups import ReentrantCallbackGroup
23+
from rclpy.executors import ExternalShutdownException
2224
from rclpy.executors import MultiThreadedExecutor
2325

2426

@@ -71,28 +73,30 @@ def main(args=None):
7173
global logger
7274
rclpy.init(args=args)
7375

74-
node = rclpy.create_node('minimal_action_server')
75-
logger = node.get_logger()
76-
77-
# Use a ReentrantCallbackGroup to enable processing multiple goals concurrently
78-
# Default goal callback accepts all goals
79-
# Default cancel callback rejects cancel requests
80-
action_server = ActionServer(
81-
node,
82-
Fibonacci,
83-
'fibonacci',
84-
execute_callback=execute_callback,
85-
cancel_callback=cancel_callback,
86-
callback_group=ReentrantCallbackGroup())
87-
88-
# Use a MultiThreadedExecutor to enable processing goals concurrently
89-
executor = MultiThreadedExecutor()
90-
91-
rclpy.spin(node, executor=executor)
92-
93-
action_server.destroy()
94-
node.destroy_node()
95-
rclpy.shutdown()
76+
try:
77+
node = rclpy.create_node('minimal_action_server')
78+
logger = node.get_logger()
79+
80+
# Use a ReentrantCallbackGroup to enable processing multiple goals concurrently
81+
# Default goal callback accepts all goals
82+
# Default cancel callback rejects cancel requests
83+
action_server = ActionServer(
84+
node,
85+
Fibonacci,
86+
'fibonacci',
87+
execute_callback=execute_callback,
88+
cancel_callback=cancel_callback,
89+
callback_group=ReentrantCallbackGroup())
90+
action_server # Quiet flake8 warnings about unused variable
91+
92+
# Use a MultiThreadedExecutor to enable processing goals concurrently
93+
executor = MultiThreadedExecutor()
94+
95+
rclpy.spin(node, executor=executor)
96+
except KeyboardInterrupt:
97+
pass
98+
except ExternalShutdownException:
99+
sys.exit(1)
96100

97101

98102
if __name__ == '__main__':

rclpy/actions/minimal_action_server/examples_rclpy_minimal_action_server/server_queue_goals.py

Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
# limitations under the License.
1414

1515
import collections
16+
import sys
1617
import threading
1718
import time
1819

@@ -21,6 +22,7 @@
2122
import rclpy
2223
from rclpy.action import ActionServer, CancelResponse, GoalResponse
2324
from rclpy.callback_groups import ReentrantCallbackGroup
25+
from rclpy.executors import ExternalShutdownException
2426
from rclpy.executors import MultiThreadedExecutor
2527
from rclpy.node import Node
2628

@@ -123,14 +125,16 @@ def execute_callback(self, goal_handle):
123125
def main(args=None):
124126
rclpy.init(args=args)
125127

126-
minimal_action_server = MinimalActionServer()
128+
try:
129+
minimal_action_server = MinimalActionServer()
127130

128-
executor = MultiThreadedExecutor()
131+
executor = MultiThreadedExecutor()
129132

130-
rclpy.spin(minimal_action_server, executor=executor)
131-
132-
minimal_action_server.destroy()
133-
rclpy.shutdown()
133+
rclpy.spin(minimal_action_server, executor=executor)
134+
except KeyboardInterrupt:
135+
pass
136+
except ExternalShutdownException:
137+
sys.exit(1)
134138

135139

136140
if __name__ == '__main__':

rclpy/actions/minimal_action_server/examples_rclpy_minimal_action_server/server_single_goal.py

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
import sys
1516
import threading
1617
import time
1718

@@ -20,6 +21,7 @@
2021
import rclpy
2122
from rclpy.action import ActionServer, CancelResponse, GoalResponse
2223
from rclpy.callback_groups import ReentrantCallbackGroup
24+
from rclpy.executors import ExternalShutdownException
2325
from rclpy.executors import MultiThreadedExecutor
2426
from rclpy.node import Node
2527

@@ -112,14 +114,16 @@ def execute_callback(self, goal_handle):
112114
def main(args=None):
113115
rclpy.init(args=args)
114116

115-
action_server = MinimalActionServer()
117+
try:
118+
action_server = MinimalActionServer()
116119

117-
# We use a MultiThreadedExecutor to handle incoming goal requests concurrently
118-
executor = MultiThreadedExecutor()
119-
rclpy.spin(action_server, executor=executor)
120-
121-
action_server.destroy()
122-
rclpy.shutdown()
120+
# We use a MultiThreadedExecutor to handle incoming goal requests concurrently
121+
executor = MultiThreadedExecutor()
122+
rclpy.spin(action_server, executor=executor)
123+
except KeyboardInterrupt:
124+
pass
125+
except ExternalShutdownException:
126+
sys.exit(1)
123127

124128

125129
if __name__ == '__main__':

0 commit comments

Comments
 (0)