Skip to content

Commit

Permalink
Change all of the demos to use the new rclpy context manager. (#694)
Browse files Browse the repository at this point in the history
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]>
  • Loading branch information
clalancette authored Jul 10, 2024
1 parent 2614f4a commit 6503d8e
Show file tree
Hide file tree
Showing 24 changed files with 566 additions and 609 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

import rclpy
from rclpy.action import ActionClient
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node


Expand Down Expand Up @@ -62,13 +63,15 @@ def feedback_callback(self, feedback_msg):


def main(args=None):
rclpy.init(args=args)
try:
with rclpy.init(args=args):
action_client = FibonacciActionClient()

action_client = FibonacciActionClient()
action_client.send_goal(10)

action_client.send_goal(10)

rclpy.spin(action_client)
rclpy.spin(action_client)
except (KeyboardInterrupt, ExternalShutdownException):
pass


if __name__ == '__main__':
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

import rclpy
from rclpy.action import ActionServer
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node


Expand Down Expand Up @@ -53,13 +54,11 @@ def execute_callback(self, goal_handle):


def main(args=None):
rclpy.init(args=args)

fibonacci_action_server = FibonacciActionServer()

try:
rclpy.spin(fibonacci_action_server)
except KeyboardInterrupt:
with rclpy.init(args=args):
fibonacci_action_server = FibonacciActionServer()
rclpy.spin(fibonacci_action_server)
except (KeyboardInterrupt, ExternalShutdownException):
pass


Expand Down
130 changes: 64 additions & 66 deletions demo_nodes_py/demo_nodes_py/events/matched_event_detect.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
from rclpy.event_handler import QoSPublisherMatchedInfo
from rclpy.event_handler import QoSSubscriptionMatchedInfo
from rclpy.event_handler import SubscriptionEventCallbacks
from rclpy.executors import ExternalShutdownException
from rclpy.executors import SingleThreadedExecutor
from rclpy.node import Node
from rclpy.publisher import Publisher
Expand Down Expand Up @@ -133,72 +134,69 @@ def destroy_one_pub(self, pub: Publisher):


def main(args=None):
rclpy.init(args=args)

topic_name_for_detect_pub_matched_event = 'pub_topic_matched_event_detect'
topic_name_for_detect_sub_matched_event = 'sub_topic_matched_event_detect'

matched_event_detect_node = MatchedEventDetectNode(
topic_name_for_detect_pub_matched_event, topic_name_for_detect_sub_matched_event)
multi_subs_node = MultiSubNode(topic_name_for_detect_pub_matched_event)
multi_pubs_node = MultiPubNode(topic_name_for_detect_sub_matched_event)

maximum_wait_time = 10 # 10s

executor = SingleThreadedExecutor()

executor.add_node(matched_event_detect_node)
executor.add_node(multi_subs_node)
executor.add_node(multi_pubs_node)

# MatchedEventDetectNode will output:
# First subscription is connected.
sub1 = multi_subs_node.create_one_sub()
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected subscription is 1 and current number of connected
# subscription is 2.
sub2 = multi_subs_node.create_one_sub()
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected subscription is -1 and current number of connected
# subscription is 1.
multi_subs_node.destroy_one_sub(sub1)
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# Last subscription is disconnected.
multi_subs_node.destroy_one_sub(sub2)
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# First publisher is connected.
pub1 = multi_pubs_node.create_one_pub()
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected publisher is 1 and current number of connected publisher
# is 2.
pub2 = multi_pubs_node.create_one_pub()
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected publisher is -1 and current number of connected publisher
# is 1.
multi_pubs_node.destroy_one_pub(pub1)
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# Last publisher is disconnected.
multi_pubs_node.destroy_one_pub(pub2)
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)

multi_pubs_node.destroy_node()
multi_subs_node.destroy_node()
matched_event_detect_node.destroy_node()
rclpy.try_shutdown()
try:
with rclpy.init(args=args):
topic_name_for_detect_pub_matched_event = 'pub_topic_matched_event_detect'
topic_name_for_detect_sub_matched_event = 'sub_topic_matched_event_detect'

matched_node = MatchedEventDetectNode(
topic_name_for_detect_pub_matched_event, topic_name_for_detect_sub_matched_event)
multi_subs_node = MultiSubNode(topic_name_for_detect_pub_matched_event)
multi_pubs_node = MultiPubNode(topic_name_for_detect_sub_matched_event)

max_wait_time = 10 # 10s

executor = SingleThreadedExecutor()

executor.add_node(matched_node)
executor.add_node(multi_subs_node)
executor.add_node(multi_pubs_node)

# MatchedEventDetectNode will output:
# First subscription is connected.
sub1 = multi_subs_node.create_one_sub()
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected subscription is 1 and current number of connected
# subscription is 2.
sub2 = multi_subs_node.create_one_sub()
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected subscription is -1 and current number of connected
# subscription is 1.
multi_subs_node.destroy_one_sub(sub1)
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)

# MatchedEventDetectNode will output:
# Last subscription is disconnected.
multi_subs_node.destroy_one_sub(sub2)
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)

# MatchedEventDetectNode will output:
# First publisher is connected.
pub1 = multi_pubs_node.create_one_pub()
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected publisher is 1 and current number of connected
# publisher is 2.
pub2 = multi_pubs_node.create_one_pub()
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected publisher is -1 and current number of connected
# publisher is 1.
multi_pubs_node.destroy_one_pub(pub1)
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)

# MatchedEventDetectNode will output:
# Last publisher is disconnected.
multi_pubs_node.destroy_one_pub(pub2)
executor.spin_until_future_complete(matched_node.get_future(), max_wait_time)
except (KeyboardInterrupt, ExternalShutdownException):
pass


if __name__ == '__main__':
Expand Down
132 changes: 68 additions & 64 deletions demo_nodes_py/demo_nodes_py/logging/use_logger_service.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
from rcl_interfaces.srv import GetLoggerLevels
from rcl_interfaces.srv import SetLoggerLevels
import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.executors import SingleThreadedExecutor
from rclpy.impl.logging_severity import LoggingSeverity
from rclpy.node import Node
Expand Down Expand Up @@ -106,70 +107,73 @@ def get_logger_level_func(test_node):


def main(args=None):
rclpy.init(args=args)

logger_service_node = LoggerServiceNode()
test_node = TestNode('LoggerServiceNode')

executor = SingleThreadedExecutor()
executor.add_node(logger_service_node)

thread = threading.Thread(target=executor.spin)
thread.start()

# Output with default logger level
test_node.get_logger().info('Output with default logger level:')
msg = String()
msg.data = 'Output 1'
test_node.pub.publish(msg)
time.sleep(0.5)

# Get logger level. Logger level should be 0 (Unset)
get_logger_level_func(test_node)

# Output with debug logger level
test_node.get_logger().info('Output with debug logger level:')
if test_node.set_logger_level_on_remote_node(LoggingSeverity.DEBUG):
msg = String()
msg.data = 'Output 2'
test_node.pub.publish(msg)
time.sleep(0.5)
else:
test_node.get_logger().error('Failed to set debug logger level via logger service !')

# Get logger level. Logger level should be 10 (Debug)
get_logger_level_func(test_node)

# Output with warn logger level
test_node.get_logger().info('Output with warn logger level:')
if test_node.set_logger_level_on_remote_node(LoggingSeverity.WARN):
msg = String()
msg.data = 'Output 3'
test_node.pub.publish(msg)
time.sleep(0.5)
else:
test_node.get_logger().error('Failed to set warn logger level via logger service !')

# Get logger level. Logger level should be 30 (warn)
get_logger_level_func(test_node)

# Output with error logger level
test_node.get_logger().info('Output with error logger level:')
if test_node.set_logger_level_on_remote_node(LoggingSeverity.ERROR):
msg = String()
msg.data = 'Output 4'
test_node.pub.publish(msg)
time.sleep(0.5)
else:
test_node.get_logger().error('Failed to set error logger level via logger service !')

# Get logger level. Logger level should be 40 (Error)
get_logger_level_func(test_node)

executor.shutdown()
if thread.is_alive():
thread.join()
rclpy.try_shutdown()
try:
with rclpy.init(args=args):
logger_service_node = LoggerServiceNode()
test_node = TestNode('LoggerServiceNode')

executor = SingleThreadedExecutor()
executor.add_node(logger_service_node)

thread = threading.Thread(target=executor.spin)
thread.start()

logger = test_node.get_logger()

# Output with default logger level
logger.info('Output with default logger level:')
msg = String()
msg.data = 'Output 1'
test_node.pub.publish(msg)
time.sleep(0.5)

# Get logger level. Logger level should be 0 (Unset)
get_logger_level_func(test_node)

# Output with debug logger level
logger.info('Output with debug logger level:')
if test_node.set_logger_level_on_remote_node(LoggingSeverity.DEBUG):
msg = String()
msg.data = 'Output 2'
test_node.pub.publish(msg)
time.sleep(0.5)
else:
logger.error('Failed to set debug logger level via logger service !')

# Get logger level. Logger level should be 10 (Debug)
get_logger_level_func(test_node)

# Output with warn logger level
logger.info('Output with warn logger level:')
if test_node.set_logger_level_on_remote_node(LoggingSeverity.WARN):
msg = String()
msg.data = 'Output 3'
test_node.pub.publish(msg)
time.sleep(0.5)
else:
logger.error('Failed to set warn logger level via logger service !')

# Get logger level. Logger level should be 30 (warn)
get_logger_level_func(test_node)

# Output with error logger level
logger.info('Output with error logger level:')
if test_node.set_logger_level_on_remote_node(LoggingSeverity.ERROR):
msg = String()
msg.data = 'Output 4'
test_node.pub.publish(msg)
time.sleep(0.5)
else:
logger.error('Failed to set error logger level via logger service !')

# Get logger level. Logger level should be 40 (Error)
get_logger_level_func(test_node)

executor.shutdown()
if thread.is_alive():
thread.join()
except (KeyboardInterrupt, ExternalShutdownException):
pass


if __name__ == '__main__':
Expand Down
Loading

0 comments on commit 6503d8e

Please sign in to comment.