Skip to content

Commit

Permalink
Switch to using rclpy.init context manager. (#918)
Browse files Browse the repository at this point in the history
This allows us to clean up things substantially, so we
can still clean up after ourselves, but use less code
doing so.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Jul 8, 2024
1 parent f92225c commit 6e743c8
Show file tree
Hide file tree
Showing 13 changed files with 156 additions and 252 deletions.
19 changes: 5 additions & 14 deletions ros2action/test/fixtures/fibonacci_action_server.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
#!/usr/bin/env python3
# Copyright 2019 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
Expand All @@ -13,10 +12,9 @@
# See the License for the specific language governing permissions and
# limitations under the License.import time

import sys

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

from test_msgs.action import Fibonacci
Expand Down Expand Up @@ -52,19 +50,12 @@ def execute_callback(self, goal_handle):


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

node = FibonacciActionServer()
try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init(args=args):
node = FibonacciActionServer()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
print('server stopped cleanly')
except BaseException:
print('exception in server:', file=sys.stderr)
raise
finally:
node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
Expand Down
19 changes: 5 additions & 14 deletions ros2doctor/test/fixtures/listener_node_with_reliable_qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import sys

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy
Expand All @@ -39,20 +38,12 @@ def callback(self, msg):


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

node = ListenerNode()

try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init(args=args):
node = ListenerNode()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
print('listener stopped cleanly')
except BaseException:
print('exception in listener:', file=sys.stderr)
raise
finally:
node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
Expand Down
19 changes: 5 additions & 14 deletions ros2doctor/test/fixtures/talker_node_with_best_effort_qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import sys

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy
Expand All @@ -40,20 +39,12 @@ def callback(self):


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

node = TalkerNode()

try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init(args=args):
node = TalkerNode()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
print('talker stopped cleanly')
except BaseException:
print('exception in talker:', file=sys.stderr)
raise
finally:
node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
Expand Down
19 changes: 5 additions & 14 deletions ros2doctor/test/fixtures/talker_node_with_reliable_qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import sys

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy
Expand All @@ -40,20 +39,12 @@ def callback(self):


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

node = TalkerNode()

try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init(args=args):
node = TalkerNode()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
print('talker stopped cleanly')
except BaseException:
print('exception in talker:', file=sys.stderr)
raise
finally:
node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
Expand Down
19 changes: 5 additions & 14 deletions ros2node/test/fixtures/complex_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,9 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import sys

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

Expand Down Expand Up @@ -56,20 +55,12 @@ def action_callback(self, goal_handle):


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

node = ComplexNode()

try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init(args=args):
node = ComplexNode()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
print('node stopped cleanly')
except BaseException:
print('exception in node:', file=sys.stderr)
raise
finally:
node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
Expand Down
39 changes: 18 additions & 21 deletions ros2param/test/fixtures/parameter_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,33 +13,30 @@
# limitations under the License.

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.parameter import PARAMETER_SEPARATOR_STRING


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

node = rclpy.create_node('parameter_node')
node.declare_parameter('bool_param', True)
node.declare_parameter('int_param', 42)
node.declare_parameter('double_param', 1.23)
node.declare_parameter('str_param', 'Hello World')
node.declare_parameter('bool_array_param', [False, False, True])
node.declare_parameter('int_array_param', [1, 2, 3])
node.declare_parameter('str_array_param', ['foo', 'bar', 'baz'])
node.declare_parameter('double_array_param', [3.125, 6.25, 12.5])
node.declare_parameter('foo' + PARAMETER_SEPARATOR_STRING + 'str_param', 'foo')
node.declare_parameter('foo' + PARAMETER_SEPARATOR_STRING +
'bar' + PARAMETER_SEPARATOR_STRING +
'str_param', 'foobar')

try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init(args=args):
node = rclpy.create_node('parameter_node')
node.declare_parameter('bool_param', True)
node.declare_parameter('int_param', 42)
node.declare_parameter('double_param', 1.23)
node.declare_parameter('str_param', 'Hello World')
node.declare_parameter('bool_array_param', [False, False, True])
node.declare_parameter('int_array_param', [1, 2, 3])
node.declare_parameter('str_array_param', ['foo', 'bar', 'baz'])
node.declare_parameter('double_array_param', [3.125, 6.25, 12.5])
node.declare_parameter('foo' + PARAMETER_SEPARATOR_STRING + 'str_param', 'foo')
node.declare_parameter('foo' + PARAMETER_SEPARATOR_STRING +
'bar' + PARAMETER_SEPARATOR_STRING +
'str_param', 'foobar')

rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
print('parameter node stopped cleanly')
finally:
node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
Expand Down
64 changes: 30 additions & 34 deletions ros2service/ros2service/verb/call.py
Original file line number Diff line number Diff line change
Expand Up @@ -89,37 +89,33 @@ def requester(service_type, service_name, values, period):

values_dictionary = yaml.safe_load(values)

rclpy.init()

node = rclpy.create_node(NODE_NAME_PREFIX + '_requester_%s_%s' % (package_name, srv_name))

cli = node.create_client(srv_module, service_name)

request = srv_module.Request()

try:
set_message_fields(request, values_dictionary)
except Exception as e:
return 'Failed to populate field: {0}'.format(e)

if not cli.service_is_ready():
print('waiting for service to become available...')
cli.wait_for_service()

while True:
print('requester: making request: %r\n' % request)
last_call = time.time()
future = cli.call_async(request)
rclpy.spin_until_future_complete(node, future)
if future.result() is not None:
print('response:\n%r\n' % future.result())
else:
raise RuntimeError('Exception while calling service: %r' % future.exception())
if period is None or not rclpy.ok():
break
time_until_next_period = (last_call + period) - time.time()
if time_until_next_period > 0:
time.sleep(time_until_next_period)

node.destroy_node()
rclpy.shutdown()
with rclpy.init():
node = rclpy.create_node(NODE_NAME_PREFIX + '_requester_%s_%s' % (package_name, srv_name))

cli = node.create_client(srv_module, service_name)

request = srv_module.Request()

try:
set_message_fields(request, values_dictionary)
except Exception as e:
return 'Failed to populate field: {0}'.format(e)

if not cli.service_is_ready():
print('waiting for service to become available...')
cli.wait_for_service()

while True:
print('requester: making request: %r\n' % request)
last_call = time.time()
future = cli.call_async(request)
rclpy.spin_until_future_complete(node, future)
if future.result() is not None:
print('response:\n%r\n' % future.result())
else:
raise RuntimeError('Exception while calling service: %r' % future.exception())
if period is None or not rclpy.ok():
break
time_until_next_period = (last_call + period) - time.time()
if time_until_next_period > 0:
time.sleep(time_until_next_period)
20 changes: 5 additions & 15 deletions ros2service/test/fixtures/echo_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import sys

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

from test_msgs.srv import BasicTypes
Expand All @@ -33,21 +32,12 @@ def callback(self, request, response):


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

node = EchoServer()
try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init(args=args):
node = EchoServer()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
print('server stopped cleanly')
except BaseException:
print('exception in server:', file=sys.stderr)
raise
finally:
# Destroy the node explicitly
# (optional - Done automatically when node is garbage collected)
node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
Expand Down
19 changes: 5 additions & 14 deletions ros2topic/test/fixtures/controller_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,10 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import sys

from geometry_msgs.msg import TwistStamped

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
from rclpy.qos import qos_profile_system_default

Expand All @@ -38,20 +37,12 @@ def callback(self):


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

node = ControllerNode()

try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init(args=args):
node = ControllerNode()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
print('controller stopped cleanly')
except BaseException:
print('exception in controller:', file=sys.stderr)
raise
finally:
node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
Expand Down
Loading

0 comments on commit 6e743c8

Please sign in to comment.