Skip to content

Commit 6503d8e

Browse files
authored
Change all of the demos to use the new rclpy context manager. (#694)
This will cleans things up at a much more predictable time. While we are in here, we make the handling of KeyboardInterrupt and ExternalShutdownException more consistent across all of the demos. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 2614f4a commit 6503d8e

24 files changed

+566
-609
lines changed

action_tutorials/action_tutorials_py/action_tutorials_py/fibonacci_action_client.py

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
import rclpy
1919
from rclpy.action import ActionClient
20+
from rclpy.executors import ExternalShutdownException
2021
from rclpy.node import Node
2122

2223

@@ -62,13 +63,15 @@ def feedback_callback(self, feedback_msg):
6263

6364

6465
def main(args=None):
65-
rclpy.init(args=args)
66+
try:
67+
with rclpy.init(args=args):
68+
action_client = FibonacciActionClient()
6669

67-
action_client = FibonacciActionClient()
70+
action_client.send_goal(10)
6871

69-
action_client.send_goal(10)
70-
71-
rclpy.spin(action_client)
72+
rclpy.spin(action_client)
73+
except (KeyboardInterrupt, ExternalShutdownException):
74+
pass
7275

7376

7477
if __name__ == '__main__':

action_tutorials/action_tutorials_py/action_tutorials_py/fibonacci_action_server.py

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
import rclpy
2121
from rclpy.action import ActionServer
22+
from rclpy.executors import ExternalShutdownException
2223
from rclpy.node import Node
2324

2425

@@ -53,13 +54,11 @@ def execute_callback(self, goal_handle):
5354

5455

5556
def main(args=None):
56-
rclpy.init(args=args)
57-
58-
fibonacci_action_server = FibonacciActionServer()
59-
6057
try:
61-
rclpy.spin(fibonacci_action_server)
62-
except KeyboardInterrupt:
58+
with rclpy.init(args=args):
59+
fibonacci_action_server = FibonacciActionServer()
60+
rclpy.spin(fibonacci_action_server)
61+
except (KeyboardInterrupt, ExternalShutdownException):
6362
pass
6463

6564

demo_nodes_py/demo_nodes_py/events/matched_event_detect.py

Lines changed: 64 additions & 66 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
from rclpy.event_handler import QoSPublisherMatchedInfo
1818
from rclpy.event_handler import QoSSubscriptionMatchedInfo
1919
from rclpy.event_handler import SubscriptionEventCallbacks
20+
from rclpy.executors import ExternalShutdownException
2021
from rclpy.executors import SingleThreadedExecutor
2122
from rclpy.node import Node
2223
from rclpy.publisher import Publisher
@@ -133,72 +134,69 @@ def destroy_one_pub(self, pub: Publisher):
133134

134135

135136
def main(args=None):
136-
rclpy.init(args=args)
137-
138-
topic_name_for_detect_pub_matched_event = 'pub_topic_matched_event_detect'
139-
topic_name_for_detect_sub_matched_event = 'sub_topic_matched_event_detect'
140-
141-
matched_event_detect_node = MatchedEventDetectNode(
142-
topic_name_for_detect_pub_matched_event, topic_name_for_detect_sub_matched_event)
143-
multi_subs_node = MultiSubNode(topic_name_for_detect_pub_matched_event)
144-
multi_pubs_node = MultiPubNode(topic_name_for_detect_sub_matched_event)
145-
146-
maximum_wait_time = 10 # 10s
147-
148-
executor = SingleThreadedExecutor()
149-
150-
executor.add_node(matched_event_detect_node)
151-
executor.add_node(multi_subs_node)
152-
executor.add_node(multi_pubs_node)
153-
154-
# MatchedEventDetectNode will output:
155-
# First subscription is connected.
156-
sub1 = multi_subs_node.create_one_sub()
157-
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
158-
159-
# MatchedEventDetectNode will output:
160-
# The changed number of connected subscription is 1 and current number of connected
161-
# subscription is 2.
162-
sub2 = multi_subs_node.create_one_sub()
163-
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
164-
165-
# MatchedEventDetectNode will output:
166-
# The changed number of connected subscription is -1 and current number of connected
167-
# subscription is 1.
168-
multi_subs_node.destroy_one_sub(sub1)
169-
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
170-
171-
# MatchedEventDetectNode will output:
172-
# Last subscription is disconnected.
173-
multi_subs_node.destroy_one_sub(sub2)
174-
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
175-
176-
# MatchedEventDetectNode will output:
177-
# First publisher is connected.
178-
pub1 = multi_pubs_node.create_one_pub()
179-
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
180-
181-
# MatchedEventDetectNode will output:
182-
# The changed number of connected publisher is 1 and current number of connected publisher
183-
# is 2.
184-
pub2 = multi_pubs_node.create_one_pub()
185-
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
186-
187-
# MatchedEventDetectNode will output:
188-
# The changed number of connected publisher is -1 and current number of connected publisher
189-
# is 1.
190-
multi_pubs_node.destroy_one_pub(pub1)
191-
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
192-
193-
# MatchedEventDetectNode will output:
194-
# Last publisher is disconnected.
195-
multi_pubs_node.destroy_one_pub(pub2)
196-
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
197-
198-
multi_pubs_node.destroy_node()
199-
multi_subs_node.destroy_node()
200-
matched_event_detect_node.destroy_node()
201-
rclpy.try_shutdown()
137+
try:
138+
with rclpy.init(args=args):
139+
topic_name_for_detect_pub_matched_event = 'pub_topic_matched_event_detect'
140+
topic_name_for_detect_sub_matched_event = 'sub_topic_matched_event_detect'
141+
142+
matched_node = MatchedEventDetectNode(
143+
topic_name_for_detect_pub_matched_event, topic_name_for_detect_sub_matched_event)
144+
multi_subs_node = MultiSubNode(topic_name_for_detect_pub_matched_event)
145+
multi_pubs_node = MultiPubNode(topic_name_for_detect_sub_matched_event)
146+
147+
max_wait_time = 10 # 10s
148+
149+
executor = SingleThreadedExecutor()
150+
151+
executor.add_node(matched_node)
152+
executor.add_node(multi_subs_node)
153+
executor.add_node(multi_pubs_node)
154+
155+
# MatchedEventDetectNode will output:
156+
# First subscription is connected.
157+
sub1 = multi_subs_node.create_one_sub()
158+
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)
159+
160+
# MatchedEventDetectNode will output:
161+
# The changed number of connected subscription is 1 and current number of connected
162+
# subscription is 2.
163+
sub2 = multi_subs_node.create_one_sub()
164+
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)
165+
166+
# MatchedEventDetectNode will output:
167+
# The changed number of connected subscription is -1 and current number of connected
168+
# subscription is 1.
169+
multi_subs_node.destroy_one_sub(sub1)
170+
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)
171+
172+
# MatchedEventDetectNode will output:
173+
# Last subscription is disconnected.
174+
multi_subs_node.destroy_one_sub(sub2)
175+
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)
176+
177+
# MatchedEventDetectNode will output:
178+
# First publisher is connected.
179+
pub1 = multi_pubs_node.create_one_pub()
180+
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)
181+
182+
# MatchedEventDetectNode will output:
183+
# The changed number of connected publisher is 1 and current number of connected
184+
# publisher is 2.
185+
pub2 = multi_pubs_node.create_one_pub()
186+
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)
187+
188+
# MatchedEventDetectNode will output:
189+
# The changed number of connected publisher is -1 and current number of connected
190+
# publisher is 1.
191+
multi_pubs_node.destroy_one_pub(pub1)
192+
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)
193+
194+
# MatchedEventDetectNode will output:
195+
# Last publisher is disconnected.
196+
multi_pubs_node.destroy_one_pub(pub2)
197+
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)
198+
except (KeyboardInterrupt, ExternalShutdownException):
199+
pass
202200

203201

204202
if __name__ == '__main__':

demo_nodes_py/demo_nodes_py/logging/use_logger_service.py

Lines changed: 68 additions & 64 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
from rcl_interfaces.srv import GetLoggerLevels
2020
from rcl_interfaces.srv import SetLoggerLevels
2121
import rclpy
22+
from rclpy.executors import ExternalShutdownException
2223
from rclpy.executors import SingleThreadedExecutor
2324
from rclpy.impl.logging_severity import LoggingSeverity
2425
from rclpy.node import Node
@@ -106,70 +107,73 @@ def get_logger_level_func(test_node):
106107

107108

108109
def main(args=None):
109-
rclpy.init(args=args)
110-
111-
logger_service_node = LoggerServiceNode()
112-
test_node = TestNode('LoggerServiceNode')
113-
114-
executor = SingleThreadedExecutor()
115-
executor.add_node(logger_service_node)
116-
117-
thread = threading.Thread(target=executor.spin)
118-
thread.start()
119-
120-
# Output with default logger level
121-
test_node.get_logger().info('Output with default logger level:')
122-
msg = String()
123-
msg.data = 'Output 1'
124-
test_node.pub.publish(msg)
125-
time.sleep(0.5)
126-
127-
# Get logger level. Logger level should be 0 (Unset)
128-
get_logger_level_func(test_node)
129-
130-
# Output with debug logger level
131-
test_node.get_logger().info('Output with debug logger level:')
132-
if test_node.set_logger_level_on_remote_node(LoggingSeverity.DEBUG):
133-
msg = String()
134-
msg.data = 'Output 2'
135-
test_node.pub.publish(msg)
136-
time.sleep(0.5)
137-
else:
138-
test_node.get_logger().error('Failed to set debug logger level via logger service !')
139-
140-
# Get logger level. Logger level should be 10 (Debug)
141-
get_logger_level_func(test_node)
142-
143-
# Output with warn logger level
144-
test_node.get_logger().info('Output with warn logger level:')
145-
if test_node.set_logger_level_on_remote_node(LoggingSeverity.WARN):
146-
msg = String()
147-
msg.data = 'Output 3'
148-
test_node.pub.publish(msg)
149-
time.sleep(0.5)
150-
else:
151-
test_node.get_logger().error('Failed to set warn logger level via logger service !')
152-
153-
# Get logger level. Logger level should be 30 (warn)
154-
get_logger_level_func(test_node)
155-
156-
# Output with error logger level
157-
test_node.get_logger().info('Output with error logger level:')
158-
if test_node.set_logger_level_on_remote_node(LoggingSeverity.ERROR):
159-
msg = String()
160-
msg.data = 'Output 4'
161-
test_node.pub.publish(msg)
162-
time.sleep(0.5)
163-
else:
164-
test_node.get_logger().error('Failed to set error logger level via logger service !')
165-
166-
# Get logger level. Logger level should be 40 (Error)
167-
get_logger_level_func(test_node)
168-
169-
executor.shutdown()
170-
if thread.is_alive():
171-
thread.join()
172-
rclpy.try_shutdown()
110+
try:
111+
with rclpy.init(args=args):
112+
logger_service_node = LoggerServiceNode()
113+
test_node = TestNode('LoggerServiceNode')
114+
115+
executor = SingleThreadedExecutor()
116+
executor.add_node(logger_service_node)
117+
118+
thread = threading.Thread(target=executor.spin)
119+
thread.start()
120+
121+
logger = test_node.get_logger()
122+
123+
# Output with default logger level
124+
logger.info('Output with default logger level:')
125+
msg = String()
126+
msg.data = 'Output 1'
127+
test_node.pub.publish(msg)
128+
time.sleep(0.5)
129+
130+
# Get logger level. Logger level should be 0 (Unset)
131+
get_logger_level_func(test_node)
132+
133+
# Output with debug logger level
134+
logger.info('Output with debug logger level:')
135+
if test_node.set_logger_level_on_remote_node(LoggingSeverity.DEBUG):
136+
msg = String()
137+
msg.data = 'Output 2'
138+
test_node.pub.publish(msg)
139+
time.sleep(0.5)
140+
else:
141+
logger.error('Failed to set debug logger level via logger service !')
142+
143+
# Get logger level. Logger level should be 10 (Debug)
144+
get_logger_level_func(test_node)
145+
146+
# Output with warn logger level
147+
logger.info('Output with warn logger level:')
148+
if test_node.set_logger_level_on_remote_node(LoggingSeverity.WARN):
149+
msg = String()
150+
msg.data = 'Output 3'
151+
test_node.pub.publish(msg)
152+
time.sleep(0.5)
153+
else:
154+
logger.error('Failed to set warn logger level via logger service !')
155+
156+
# Get logger level. Logger level should be 30 (warn)
157+
get_logger_level_func(test_node)
158+
159+
# Output with error logger level
160+
logger.info('Output with error logger level:')
161+
if test_node.set_logger_level_on_remote_node(LoggingSeverity.ERROR):
162+
msg = String()
163+
msg.data = 'Output 4'
164+
test_node.pub.publish(msg)
165+
time.sleep(0.5)
166+
else:
167+
logger.error('Failed to set error logger level via logger service !')
168+
169+
# Get logger level. Logger level should be 40 (Error)
170+
get_logger_level_func(test_node)
171+
172+
executor.shutdown()
173+
if thread.is_alive():
174+
thread.join()
175+
except (KeyboardInterrupt, ExternalShutdownException):
176+
pass
173177

174178

175179
if __name__ == '__main__':

0 commit comments

Comments
 (0)