From 277d95cdb61e98cf5b7f0f53e1293a8423c7fb51 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 19 Dec 2024 15:36:02 -0800 Subject: [PATCH 01/21] autostarting lifecycle nodes and example Signed-off-by: Steve Macenski --- .../lifecycle_autostart_pub_sub_launch.py | 57 +++++++++++++++++++ .../launch_ros/actions/lifecycle_node.py | 29 +++++++++- launch_ros/launch_ros/actions/node.py | 11 ++++ .../event_handlers/on_state_transition.py | 15 +++-- .../actions/test_lifecycle_node.py | 8 ++- 5 files changed, 114 insertions(+), 6 deletions(-) create mode 100644 launch_ros/examples/lifecycle_autostart_pub_sub_launch.py diff --git a/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py b/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py new file mode 100644 index 00000000..abf7e368 --- /dev/null +++ b/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py @@ -0,0 +1,57 @@ +# Copyright 2018 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Launch a lifecycle talker and a lifecycle listener.""" + +import os +import sys +sys.path.insert(0, os.path.join(os.path.dirname(__file__), '..')) # noqa +sys.path.insert(0, os.path.join(os.path.dirname(__file__), '..', '..', 'launch')) # noqa + +import launch # noqa: E402 +import launch.actions # noqa: E402 +import launch.events # noqa: E402 + +import launch_ros.actions # noqa: E402 +import launch_ros.events # noqa: E402 +import launch_ros.events.lifecycle # noqa: E402 + +import lifecycle_msgs.msg # noqa: E402 + + +def main(argv=sys.argv[1:]): + ld = launch.LaunchDescription() + talker_node = launch_ros.actions.LifecycleNode( + name='talker', + namespace='', + package='lifecycle', + executable='lifecycle_talker', + output='screen', + autostart=True) + listener_node = launch_ros.actions.LifecycleNode( + name='listener', + namespace='', + package='lifecycle', + executable='lifecycle_listener', + output='screen', + autostart=True) + ld.add_action(talker_node) + ld.add_action(listener_node) + ls = launch.LaunchService(argv=argv) + ls.include_launch_description(ld) + return ls.run() + + +if __name__ == '__main__': + main() diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index dd5cb46b..796983e7 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -31,6 +31,7 @@ from .node import Node from ..events.lifecycle import ChangeState from ..events.lifecycle import StateTransition +from .lifecycle_transition import LifecycleTransition from ..ros_adapters import get_ros_node @@ -78,6 +79,10 @@ def __init__( self.__current_state = \ ChangeState.valid_states[lifecycle_msgs.msg.State.PRIMARY_STATE_UNKNOWN] + @property + def is_lifecycle_node(self): + return True + def _on_transition_event(self, context, msg): try: event = StateTransition(action=self, msg=msg) @@ -161,5 +166,27 @@ def execute(self, context: launch.LaunchContext) -> Optional[List[Action]]: matcher=lambda event: isinstance(event, ChangeState), entities=[launch.actions.OpaqueFunction(function=self._on_change_state_event)], )) + + # If autostart is enabled, transition to the 'active' state. + autostart_actions = None + if self.node_autostart: + autostart_actions = [ + LifecycleTransition( + lifecycle_node_names=[self.node_name], + transition_ids=[lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE] + ), + LifecycleTransition( + lifecycle_node_names=[self.node_name], + transition_ids=[lifecycle_msgs.msg.Transition.TRANSITION_ACTIVATE] + ), + ] + # Delegate execution to Node and ExecuteProcess. - return super().execute(context) + node_actions = super().execute(context) # type: Optional[List[Action]] + if node_actions is not None and autostart_actions is not None: + return node_actions + autostart_actions + if node_actions is not None: + return node_actions + if autostart_actions is not None: + return autostart_actions + return None diff --git a/launch_ros/launch_ros/actions/node.py b/launch_ros/launch_ros/actions/node.py index fd684ce2..451ddba3 100644 --- a/launch_ros/launch_ros/actions/node.py +++ b/launch_ros/launch_ros/actions/node.py @@ -125,6 +125,7 @@ def __init__( exec_name: Optional[SomeSubstitutionsType] = None, parameters: Optional[SomeParameters] = None, remappings: Optional[SomeRemapRules] = None, + autostart: Optional[bool] = False, ros_arguments: Optional[Iterable[SomeSubstitutionsType]] = None, arguments: Optional[Iterable[SomeSubstitutionsType]] = None, **kwargs @@ -222,6 +223,7 @@ def __init__( self.__node_executable = executable self.__node_name = name self.__node_namespace = namespace + self.__autostart = autostart self.__parameters = [] if parameters is None else normalized_params self.__remappings = [] if remappings is None else list(normalize_remap_rules(remappings)) self.__ros_arguments = ros_arguments @@ -362,6 +364,15 @@ def node_name(self): raise RuntimeError("cannot access 'node_name' before executing action") return self.__final_node_name + @property + def node_autostart(self): + """Getter for autostart.""" + return self.__autostart + + @property + def is_lifecycle_node(self): + return False + def is_node_name_fully_specified(self): keywords = (self.UNSPECIFIED_NODE_NAME, self.UNSPECIFIED_NODE_NAMESPACE) return all(x not in self.node_name for x in keywords) diff --git a/launch_ros/launch_ros/event_handlers/on_state_transition.py b/launch_ros/launch_ros/event_handlers/on_state_transition.py index f9b381e1..ed371d07 100644 --- a/launch_ros/launch_ros/event_handlers/on_state_transition.py +++ b/launch_ros/launch_ros/event_handlers/on_state_transition.py @@ -14,6 +14,7 @@ """Module for OnStateTransition class.""" +from inspect import getattr_static from typing import Callable from typing import Optional from typing import Text @@ -23,7 +24,6 @@ from launch.some_entities_type import SomeEntitiesType from launch.some_substitutions_type import SomeSubstitutionsType -from ..actions import LifecycleNode from ..events.lifecycle import StateTransition @@ -34,7 +34,7 @@ def __init__( self, *, entities: SomeEntitiesType, - target_lifecycle_node: LifecycleNode = None, + target_lifecycle_node: Optional[SomeSubstitutionsType] = None, transition: Optional[SomeSubstitutionsType] = None, start_state: Optional[SomeSubstitutionsType] = None, goal_state: Optional[SomeSubstitutionsType] = None, @@ -51,8 +51,15 @@ def __init__( If matcher is given, the other conditions are not considered. """ - if not isinstance(target_lifecycle_node, (LifecycleNode, type(None))): - raise RuntimeError("OnStateTransition requires a 'LifecycleNode' action as the target") + target_lifecycle_property = type(target_lifecycle_node).__dict__.get('is_lifecycle_node', None) + if not isinstance(target_lifecycle_property, (property, type(None))): + raise RuntimeError("OnStateTransition requires a 'LifecycleNode' action as the target," + " target_lifecycle_node is not a node type.") + + if target_lifecycle_node and not target_lifecycle_node.is_lifecycle_node: + raise RuntimeError("OnStateTransition requires a 'LifecycleNode' action as the target," + " target_lifecycle_node is not a lifecycle-enabled node.") + # Handle optional matcher argument. self.__custom_matcher = matcher if self.__custom_matcher is None: diff --git a/test_launch_ros/test/test_launch_ros/actions/test_lifecycle_node.py b/test_launch_ros/test/test_launch_ros/actions/test_lifecycle_node.py index d195a57f..1753829b 100644 --- a/test_launch_ros/test/test_launch_ros/actions/test_lifecycle_node.py +++ b/test_launch_ros/test/test_launch_ros/actions/test_lifecycle_node.py @@ -41,7 +41,13 @@ def test_lifecycle_node_constructor(): name='my_node', namespace='my_ns', ) - + LifecycleNode( + package='asd', + executable='bsd', + name='my_node', + namespace='my_ns', + autostart=True, + ) def test_node_name(): node_object = LifecycleNode( From e49ed4cf2b4ddd090010489ae4ca5b2daeb232c1 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 19 Dec 2024 16:20:19 -0800 Subject: [PATCH 02/21] fix linting Signed-off-by: Steve Macenski --- .../examples/lifecycle_autostart_pub_sub_launch.py | 2 -- launch_ros/launch_ros/actions/lifecycle_node.py | 2 +- .../event_handlers/on_state_transition.py | 13 ++++++------- 3 files changed, 7 insertions(+), 10 deletions(-) diff --git a/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py b/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py index abf7e368..04b00f4a 100644 --- a/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py +++ b/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py @@ -27,8 +27,6 @@ import launch_ros.events # noqa: E402 import launch_ros.events.lifecycle # noqa: E402 -import lifecycle_msgs.msg # noqa: E402 - def main(argv=sys.argv[1:]): ld = launch.LaunchDescription() diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index 796983e7..39b07165 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -28,10 +28,10 @@ import lifecycle_msgs.msg import lifecycle_msgs.srv +from .lifecycle_transition import LifecycleTransition from .node import Node from ..events.lifecycle import ChangeState from ..events.lifecycle import StateTransition -from .lifecycle_transition import LifecycleTransition from ..ros_adapters import get_ros_node diff --git a/launch_ros/launch_ros/event_handlers/on_state_transition.py b/launch_ros/launch_ros/event_handlers/on_state_transition.py index ed371d07..6751bf58 100644 --- a/launch_ros/launch_ros/event_handlers/on_state_transition.py +++ b/launch_ros/launch_ros/event_handlers/on_state_transition.py @@ -14,7 +14,6 @@ """Module for OnStateTransition class.""" -from inspect import getattr_static from typing import Callable from typing import Optional from typing import Text @@ -51,14 +50,14 @@ def __init__( If matcher is given, the other conditions are not considered. """ - target_lifecycle_property = type(target_lifecycle_node).__dict__.get('is_lifecycle_node', None) - if not isinstance(target_lifecycle_property, (property, type(None))): - raise RuntimeError("OnStateTransition requires a 'LifecycleNode' action as the target," - " target_lifecycle_node is not a node type.") + lifecycle_property = type(target_lifecycle_node).__dict__.get('is_lifecycle_node', None) + if not isinstance(lifecycle_property, (property, type(None))): + raise RuntimeError('OnStateTransition requires a "LifecycleNode" action as the target,' + ' target_lifecycle_node is not a node type.') if target_lifecycle_node and not target_lifecycle_node.is_lifecycle_node: - raise RuntimeError("OnStateTransition requires a 'LifecycleNode' action as the target," - " target_lifecycle_node is not a lifecycle-enabled node.") + raise RuntimeError('OnStateTransition requires a "LifecycleNode" action as the target,' + ' target_lifecycle_node is not a lifecycle-enabled node.') # Handle optional matcher argument. self.__custom_matcher = matcher From c41cdcca81270e6e40bfca38567e380793dbdae8 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 19 Dec 2024 16:28:19 -0800 Subject: [PATCH 03/21] fix linting Signed-off-by: Steve Macenski --- .../test/test_launch_ros/actions/test_lifecycle_node.py | 1 + 1 file changed, 1 insertion(+) diff --git a/test_launch_ros/test/test_launch_ros/actions/test_lifecycle_node.py b/test_launch_ros/test/test_launch_ros/actions/test_lifecycle_node.py index 1753829b..ca9b7f01 100644 --- a/test_launch_ros/test/test_launch_ros/actions/test_lifecycle_node.py +++ b/test_launch_ros/test/test_launch_ros/actions/test_lifecycle_node.py @@ -49,6 +49,7 @@ def test_lifecycle_node_constructor(): autostart=True, ) + def test_node_name(): node_object = LifecycleNode( package='asd', From cc3449e216dd95ae61fa887b4808ac1f1dd28e0f Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 20 Dec 2024 12:54:07 -0800 Subject: [PATCH 04/21] removing an unused variable Signed-off-by: Steve Macenski --- launch_ros/launch_ros/actions/lifecycle_node.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index 39b07165..e23c47db 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -76,8 +76,6 @@ def __init__( super().__init__(name=name, namespace=namespace, **kwargs) self.__logger = launch.logging.get_logger(__name__) self.__rclpy_subscription = None - self.__current_state = \ - ChangeState.valid_states[lifecycle_msgs.msg.State.PRIMARY_STATE_UNKNOWN] @property def is_lifecycle_node(self): @@ -86,7 +84,6 @@ def is_lifecycle_node(self): def _on_transition_event(self, context, msg): try: event = StateTransition(action=self, msg=msg) - self.__current_state = ChangeState.valid_states[msg.goal_state.id] context.asyncio_loop.call_soon_threadsafe(lambda: context.emit_event_sync(event)) except Exception as exc: self.__logger.error( From e60458a6bdd1aeef8539ab8d6dc435b370cbda44 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 20 Dec 2024 12:56:30 -0800 Subject: [PATCH 05/21] initializing a member client as none like sub Signed-off-by: Steve Macenski --- launch_ros/launch_ros/actions/lifecycle_node.py | 1 + 1 file changed, 1 insertion(+) diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index e23c47db..063ce607 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -76,6 +76,7 @@ def __init__( super().__init__(name=name, namespace=namespace, **kwargs) self.__logger = launch.logging.get_logger(__name__) self.__rclpy_subscription = None + self.__rclpy_change_state_client = None @property def is_lifecycle_node(self): From cfc9b53e0a16c89dbf613d02e7b20e224a259b54 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 20 Dec 2024 15:00:18 -0800 Subject: [PATCH 06/21] completing auto-start feature for composition nodes Signed-off-by: Steve Macenski --- .../lifecycle_autostart_pub_sub_launch.py | 2 +- ...ycle_component_autostart_pub_sub_launch.py | 66 ++++++++ .../launch_ros/actions/lifecycle_node.py | 80 +--------- .../actions/load_composable_nodes.py | 32 ++++ .../descriptions/composable_node.py | 14 ++ launch_ros/launch_ros/utilities/__init__.py | 2 + .../utilities/lifecycle_event_manager.py | 141 ++++++++++++++++++ 7 files changed, 261 insertions(+), 76 deletions(-) create mode 100644 launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py create mode 100644 launch_ros/launch_ros/utilities/lifecycle_event_manager.py diff --git a/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py b/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py index 04b00f4a..2138b26a 100644 --- a/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py +++ b/launch_ros/examples/lifecycle_autostart_pub_sub_launch.py @@ -1,4 +1,4 @@ -# Copyright 2018 Open Source Robotics Foundation, Inc. +# Copyright 2024 Open Navigation LLC # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. diff --git a/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py b/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py new file mode 100644 index 00000000..1f90fb4d --- /dev/null +++ b/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py @@ -0,0 +1,66 @@ +# Copyright 2024 Open Navigation LLC +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Launch a lifecycle talker and a lifecycle listener.""" + +import os +import sys +sys.path.insert(0, os.path.join(os.path.dirname(__file__), '..')) # noqa +sys.path.insert(0, os.path.join(os.path.dirname(__file__), '..', '..', 'launch')) # noqa + +import launch # noqa: E402 + +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.descriptions import ComposableNode + + +def main(argv=sys.argv[1:]): + ld = launch.LaunchDescription() + + # Can autostart from the container + container = ComposableNodeContainer( + name='lifecycle_component_container', + namespace='', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + ComposableNode( + package='composition', + plugin='composition::Listener', + name='listener', + autostart=True), + ] + ) + + # ... and also from an external loader + loader = LoadComposableNodes( + target_container='lifecycle_component_container', + composable_node_descriptions=[ + ComposableNode( + package='composition', + plugin='composition::Talker', + name='talker', + autostart=True), + ], + ) + + ld.add_action(container) + ld.add_action(loader) + ls = launch.LaunchService(argv=argv) + ls.include_launch_description(ld) + return ls.run() + + +if __name__ == '__main__': + main() diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index 063ce607..536e8800 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -34,6 +34,7 @@ from ..events.lifecycle import StateTransition from ..ros_adapters import get_ros_node +from ..utilities import LifecycleEventManager class LifecycleNode(Node): @@ -75,70 +76,12 @@ def __init__( """ super().__init__(name=name, namespace=namespace, **kwargs) self.__logger = launch.logging.get_logger(__name__) - self.__rclpy_subscription = None - self.__rclpy_change_state_client = None + self.__lifecycle_event_manager = None @property def is_lifecycle_node(self): return True - def _on_transition_event(self, context, msg): - try: - event = StateTransition(action=self, msg=msg) - context.asyncio_loop.call_soon_threadsafe(lambda: context.emit_event_sync(event)) - except Exception as exc: - self.__logger.error( - "Exception in handling of 'lifecycle.msg.TransitionEvent': {}".format(exc)) - - def _call_change_state(self, request, context: launch.LaunchContext): - while not self.__rclpy_change_state_client.wait_for_service(timeout_sec=1.0): - if context.is_shutdown: - self.__logger.warning( - "Abandoning wait for the '{}' service, due to shutdown.".format( - self.__rclpy_change_state_client.srv_name), - ) - return - - # Asynchronously wait so that we can periodically check for shutdown. - event = threading.Event() - - def unblock(future): - nonlocal event - event.set() - - response_future = self.__rclpy_change_state_client.call_async(request) - response_future.add_done_callback(unblock) - - while not event.wait(1.0): - if context.is_shutdown: - self.__logger.warning( - "Abandoning wait for the '{}' service response, due to shutdown.".format( - self.__rclpy_change_state_client.srv_name), - ) - response_future.cancel() - return - - if response_future.exception() is not None: - raise response_future.exception() - response = response_future.result() - - if not response.success: - self.__logger.error( - "Failed to make transition '{}' for LifecycleNode '{}'".format( - ChangeState.valid_transitions[request.transition.id], - self.node_name, - ) - ) - - def _on_change_state_event(self, context: launch.LaunchContext) -> None: - typed_event = cast(ChangeState, context.locals.event) - if not typed_event.lifecycle_node_matcher(self): - return None - request = lifecycle_msgs.srv.ChangeState.Request() - request.transition.id = typed_event.transition_id - context.add_completion_future( - context.asyncio_loop.run_in_executor(None, self._call_change_state, request, context)) - def execute(self, context: launch.LaunchContext) -> Optional[List[Action]]: """ Execute the action. @@ -148,22 +91,9 @@ def execute(self, context: launch.LaunchContext) -> Optional[List[Action]]: self._perform_substitutions(context) # ensure self.node_name is expanded if '' in self.node_name: raise RuntimeError('node_name unexpectedly incomplete for lifecycle node') - node = get_ros_node(context) - # Create a subscription to monitor the state changes of the subprocess. - self.__rclpy_subscription = node.create_subscription( - lifecycle_msgs.msg.TransitionEvent, - '{}/transition_event'.format(self.node_name), - functools.partial(self._on_transition_event, context), - 10) - # Create a service client to change state on demand. - self.__rclpy_change_state_client = node.create_client( - lifecycle_msgs.srv.ChangeState, - '{}/change_state'.format(self.node_name)) - # Register an event handler to change states on a ChangeState lifecycle event. - context.register_event_handler(launch.EventHandler( - matcher=lambda event: isinstance(event, ChangeState), - entities=[launch.actions.OpaqueFunction(function=self._on_change_state_event)], - )) + + self.__lifecycle_event_manager = LifecycleEventManager(self.node_name) + self.__lifecycle_event_manager.setup_lifecycle_manager(context) # If autostart is enabled, transition to the 'active' state. autostart_actions = None diff --git a/launch_ros/launch_ros/actions/load_composable_nodes.py b/launch_ros/launch_ros/actions/load_composable_nodes.py index 6ab36f7f..7127acb2 100644 --- a/launch_ros/launch_ros/actions/load_composable_nodes.py +++ b/launch_ros/launch_ros/actions/load_composable_nodes.py @@ -38,7 +38,10 @@ from launch.utilities import perform_substitutions from launch_ros.parameter_descriptions import ParameterFile +import lifecycle_msgs.msg + from .composable_node_container import ComposableNodeContainer +from .lifecycle_transition import LifecycleTransition from ..descriptions import ComposableNode from ..ros_adapters import get_ros_node @@ -230,12 +233,33 @@ def execute( # Generate load requests before execute() exits to avoid race with context changing # due to scope change (e.g. if loading nodes from within a GroupAction). load_node_requests = [] + autostart_actions = [] for node_description in self.__composable_node_descriptions: request = get_composable_node_load_request(node_description, context) # The request can be None if the node description's condition evaluates to False if request is not None: load_node_requests.append(request) + # If autostart is enabled, transition to the 'active' state. + if node_description.node_autostart: + complete_node_name = request.node_namespace + request.node_name + if not complete_node_name.startswith('/'): + complete_node_name = '/' + complete_node_name + self.__logger.info( + 'Autostart enabled for requested lifecycle node {}'.format(complete_node_name)) + node_description.init_lifecycle_event_manager(complete_node_name, context) + autostart_actions.append( + LifecycleTransition( + lifecycle_node_names=[complete_node_name], + transition_ids=[lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE] + )) + autostart_actions.append( + LifecycleTransition( + lifecycle_node_names=[complete_node_name], + transition_ids=[lifecycle_msgs.msg.Transition.TRANSITION_ACTIVATE] + ), + ) + if load_node_requests: context.add_completion_future( context.asyncio_loop.run_in_executor( @@ -243,6 +267,14 @@ def execute( ) ) + load_actions = super().execute(context) + if load_actions is not None and len(autostart_actions) != 0: + return load_actions + autostart_actions + if load_actions is not None: + return load_actions + if len(autostart_actions) != 0: + return autostart_actions + def get_composable_node_load_request( composable_node_description: ComposableNode, diff --git a/launch_ros/launch_ros/descriptions/composable_node.py b/launch_ros/launch_ros/descriptions/composable_node.py index 8ad35c5c..ce8dbc91 100644 --- a/launch_ros/launch_ros/descriptions/composable_node.py +++ b/launch_ros/launch_ros/descriptions/composable_node.py @@ -17,6 +17,7 @@ from typing import List from typing import Optional +import launch from launch.condition import Condition from launch.conditions import IfCondition, UnlessCondition from launch.frontend import Entity @@ -29,6 +30,7 @@ from launch_ros.parameters_type import SomeParameters from launch_ros.remap_rule_type import RemapRules from launch_ros.remap_rule_type import SomeRemapRules +from launch_ros.utilities import LifecycleEventManager from launch_ros.utilities import normalize_parameters from launch_ros.utilities import normalize_remap_rules @@ -43,6 +45,7 @@ def __init__( name: Optional[SomeSubstitutionsType] = None, namespace: Optional[SomeSubstitutionsType] = None, parameters: Optional[SomeParameters] = None, + autostart: Optional[bool] = False, remappings: Optional[SomeRemapRules] = None, extra_arguments: Optional[SomeParameters] = None, condition: Optional[Condition] = None, @@ -83,6 +86,8 @@ def __init__( self.__extra_arguments = normalize_parameters(extra_arguments) self.__condition = condition + self.__autostart = autostart + self.__lifecycle_event_manager = None @classmethod def parse(cls, parser: Parser, entity: Entity): @@ -143,6 +148,10 @@ def parse(cls, parser: Parser, entity: Entity): return cls, kwargs + def init_lifecycle_event_manager(self, node_name, context: launch.LaunchContext) -> None: + self.__lifecycle_event_manager = LifecycleEventManager(node_name) + self.__lifecycle_event_manager.setup_lifecycle_manager(context) + @property def package(self) -> List[Substitution]: """Get node package name as a sequence of substitutions to be performed.""" @@ -163,6 +172,11 @@ def node_namespace(self) -> Optional[List[Substitution]]: """Get node namespace as a sequence of substitutions to be performed.""" return self.__node_namespace + @property + def node_autostart(self): + """Getter for autostart.""" + return self.__autostart + @property def parameters(self) -> Optional[Parameters]: """Get node parameter YAML files or dicts with substitutions to be performed.""" diff --git a/launch_ros/launch_ros/utilities/__init__.py b/launch_ros/launch_ros/utilities/__init__.py index 8a530a7a..152479ac 100644 --- a/launch_ros/launch_ros/utilities/__init__.py +++ b/launch_ros/launch_ros/utilities/__init__.py @@ -19,6 +19,7 @@ """ from .evaluate_parameters import evaluate_parameters +from .lifecycle_event_manager import LifecycleEventManager from .namespace_utils import is_namespace_absolute from .namespace_utils import is_root_namespace from .namespace_utils import make_namespace_absolute @@ -37,6 +38,7 @@ 'get_node_name_count', 'is_namespace_absolute', 'is_root_namespace', + 'LifecycleEventManager', 'make_namespace_absolute', 'normalize_parameters', 'normalize_parameters_dict', diff --git a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py new file mode 100644 index 00000000..60d5bb07 --- /dev/null +++ b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py @@ -0,0 +1,141 @@ +# Copyright 2024 Open Navigation LLC +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Module for the management of LifecycleNode events.""" + +import functools +import threading +from typing import cast + +import launch +import launch.logging + +import lifecycle_msgs.msg +import lifecycle_msgs.srv + +from ..events.lifecycle import ChangeState +from ..events.lifecycle import StateTransition + +from ..ros_adapters import get_ros_node + + +class LifecycleEventManager: + def __init__(self, name) -> None: + """ + Construct a LifecycleEventManager utility. + + This utility emits some event(s) in certain circumstances: + + - :class:`launch.events.lifecycle.StateTransition`: + + - this event is emitted when a message is published to the + "//transition_event" topic, indicating the lifecycle + node represented by this action changed state + + This utility also handles some events related to lifecycle: + + - :class:`launch.events.lifecycle.ChangeState` + + - this event can be targeted to a single lifecycle node, or more than + one, or even all lifecycle nodes, and it requests the targeted nodes + to change state, see its documentation for more details. + + :param name: The name of the lifecycle node. + """ + self.__logger = launch.logging.get_logger(__name__) + self.__node_name = name + self.__rclpy_subscription = None + self.__rclpy_change_state_client = None + + @property + def node_name(self): + return self.__node_name + + def _on_transition_event(self, context, msg): + try: + event = StateTransition(action=self, msg=msg) + context.asyncio_loop.call_soon_threadsafe(lambda: context.emit_event_sync(event)) + except Exception as exc: + self.__logger.error( + "Exception in handling of 'lifecycle.msg.TransitionEvent': {}".format(exc)) + + def _call_change_state(self, request, context: launch.LaunchContext): + while not self.__rclpy_change_state_client.wait_for_service(timeout_sec=1.0): + if context.is_shutdown: + self.__logger.warning( + "Abandoning wait for the '{}' service, due to shutdown.".format( + self.__rclpy_change_state_client.srv_name), + ) + return + + # Asynchronously wait so that we can periodically check for shutdown. + event = threading.Event() + + def unblock(future): + nonlocal event + event.set() + + response_future = self.__rclpy_change_state_client.call_async(request) + response_future.add_done_callback(unblock) + + while not event.wait(1.0): + if context.is_shutdown: + self.__logger.warning( + "Abandoning wait for the '{}' service response, due to shutdown.".format( + self.__rclpy_change_state_client.srv_name), + ) + response_future.cancel() + return + + if response_future.exception() is not None: + raise response_future.exception() + response = response_future.result() + + if not response.success: + self.__logger.error( + "Failed to make transition '{}' for LifecycleNode '{}'".format( + ChangeState.valid_transitions[request.transition.id], + self.__node_name, + ) + ) + + def _on_change_state_event(self, context: launch.LaunchContext) -> None: + typed_event = cast(ChangeState, context.locals.event) + if not typed_event.lifecycle_node_matcher(self): + return None + request = lifecycle_msgs.srv.ChangeState.Request() + request.transition.id = typed_event.transition_id + context.add_completion_future( + context.asyncio_loop.run_in_executor(None, self._call_change_state, request, context)) + + def setup_lifecycle_manager(self, context: launch.LaunchContext) -> None: + node = get_ros_node(context) + + # Create a subscription to monitor the state changes of the subprocess. + self.__rclpy_subscription = node.create_subscription( + lifecycle_msgs.msg.TransitionEvent, + '{}/transition_event'.format(self.__node_name), + functools.partial(self._on_transition_event, context), + 10) + + # Create a service client to change state on demand. + self.__rclpy_change_state_client = node.create_client( + lifecycle_msgs.srv.ChangeState, + '{}/change_state'.format(self.__node_name)) + + # Register an event handler to change states on a ChangeState lifecycle event. + context.register_event_handler(launch.EventHandler( + matcher=lambda event: isinstance(event, ChangeState), + entities=[launch.actions.OpaqueFunction(function=self._on_change_state_event)], + )) From fa0e7415ff444b9a706f83d0fb7fa43362a10f7c Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 20 Dec 2024 15:10:58 -0800 Subject: [PATCH 07/21] linting Signed-off-by: Steve Macenski --- .../lifecycle_component_autostart_pub_sub_launch.py | 4 ++-- launch_ros/launch_ros/actions/lifecycle_node.py | 6 ------ launch_ros/launch_ros/utilities/lifecycle_event_manager.py | 3 ++- 3 files changed, 4 insertions(+), 9 deletions(-) diff --git a/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py b/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py index 1f90fb4d..ac8398fb 100644 --- a/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py +++ b/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py @@ -19,11 +19,11 @@ sys.path.insert(0, os.path.join(os.path.dirname(__file__), '..')) # noqa sys.path.insert(0, os.path.join(os.path.dirname(__file__), '..', '..', 'launch')) # noqa -import launch # noqa: E402 - from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode +import launch # noqa: E402 + def main(argv=sys.argv[1:]): ld = launch.LaunchDescription() diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index 536e8800..b66d9143 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -14,9 +14,6 @@ """Module for the LifecycleNode action.""" -import functools -import threading -from typing import cast from typing import List from typing import Optional @@ -30,10 +27,7 @@ from .lifecycle_transition import LifecycleTransition from .node import Node -from ..events.lifecycle import ChangeState -from ..events.lifecycle import StateTransition -from ..ros_adapters import get_ros_node from ..utilities import LifecycleEventManager diff --git a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py index 60d5bb07..097cf370 100644 --- a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py +++ b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py @@ -31,6 +31,7 @@ class LifecycleEventManager: + def __init__(self, name) -> None: """ Construct a LifecycleEventManager utility. @@ -57,7 +58,7 @@ def __init__(self, name) -> None: self.__node_name = name self.__rclpy_subscription = None self.__rclpy_change_state_client = None - + @property def node_name(self): return self.__node_name From f836f4b7ba5d69bee601f2a044f5a9de3e700516 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 20 Dec 2024 15:31:29 -0800 Subject: [PATCH 08/21] final linting fix Signed-off-by: Steve Macenski --- .../lifecycle_component_autostart_pub_sub_launch.py | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py b/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py index ac8398fb..22412913 100644 --- a/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py +++ b/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py @@ -14,16 +14,13 @@ """Launch a lifecycle talker and a lifecycle listener.""" -import os import sys -sys.path.insert(0, os.path.join(os.path.dirname(__file__), '..')) # noqa -sys.path.insert(0, os.path.join(os.path.dirname(__file__), '..', '..', 'launch')) # noqa + +import launch # noqa: E402 from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode -import launch # noqa: E402 - def main(argv=sys.argv[1:]): ld = launch.LaunchDescription() From 5d97fd864cae1194a733b3bcf5a734d31be11de1 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 16 Jan 2025 19:08:30 -0800 Subject: [PATCH 09/21] Resolving issue with StateTransition messages Signed-off-by: Steve Macenski --- launch_ros/launch_ros/actions/lifecycle_node.py | 2 +- .../utilities/lifecycle_event_manager.py | 15 +++++++++------ 2 files changed, 10 insertions(+), 7 deletions(-) diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index b66d9143..c02d7e88 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -86,7 +86,7 @@ def execute(self, context: launch.LaunchContext) -> Optional[List[Action]]: if '' in self.node_name: raise RuntimeError('node_name unexpectedly incomplete for lifecycle node') - self.__lifecycle_event_manager = LifecycleEventManager(self.node_name) + self.__lifecycle_event_manager = LifecycleEventManager(self) self.__lifecycle_event_manager.setup_lifecycle_manager(context) # If autostart is enabled, transition to the 'active' state. diff --git a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py index 097cf370..acdb7083 100644 --- a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py +++ b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py @@ -32,7 +32,7 @@ class LifecycleEventManager: - def __init__(self, name) -> None: + def __init__(self, lifecycle_node) -> None: """ Construct a LifecycleEventManager utility. @@ -55,13 +55,16 @@ def __init__(self, name) -> None: :param name: The name of the lifecycle node. """ self.__logger = launch.logging.get_logger(__name__) - self.__node_name = name + self.__lifecycle_node = lifecycle_node self.__rclpy_subscription = None self.__rclpy_change_state_client = None @property def node_name(self): - return self.__node_name + return self.__lifecycle_node.node_name + + def __eq__(self, other): + return self.__lifecycle_node == other def _on_transition_event(self, context, msg): try: @@ -107,7 +110,7 @@ def unblock(future): self.__logger.error( "Failed to make transition '{}' for LifecycleNode '{}'".format( ChangeState.valid_transitions[request.transition.id], - self.__node_name, + self.node_name, ) ) @@ -126,14 +129,14 @@ def setup_lifecycle_manager(self, context: launch.LaunchContext) -> None: # Create a subscription to monitor the state changes of the subprocess. self.__rclpy_subscription = node.create_subscription( lifecycle_msgs.msg.TransitionEvent, - '{}/transition_event'.format(self.__node_name), + '{}/transition_event'.format(self.node_name), functools.partial(self._on_transition_event, context), 10) # Create a service client to change state on demand. self.__rclpy_change_state_client = node.create_client( lifecycle_msgs.srv.ChangeState, - '{}/change_state'.format(self.__node_name)) + '{}/change_state'.format(self.node_name)) # Register an event handler to change states on a ChangeState lifecycle event. context.register_event_handler(launch.EventHandler( From 5e6bdb90bc42c8924f9fb687d86bd321b0577757 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 29 Jan 2025 17:27:29 -0800 Subject: [PATCH 10/21] removing Node's autostart Signed-off-by: Steve Macenski --- launch_ros/launch_ros/actions/node.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/launch_ros/launch_ros/actions/node.py b/launch_ros/launch_ros/actions/node.py index 451ddba3..bee43c83 100644 --- a/launch_ros/launch_ros/actions/node.py +++ b/launch_ros/launch_ros/actions/node.py @@ -125,7 +125,6 @@ def __init__( exec_name: Optional[SomeSubstitutionsType] = None, parameters: Optional[SomeParameters] = None, remappings: Optional[SomeRemapRules] = None, - autostart: Optional[bool] = False, ros_arguments: Optional[Iterable[SomeSubstitutionsType]] = None, arguments: Optional[Iterable[SomeSubstitutionsType]] = None, **kwargs @@ -223,7 +222,6 @@ def __init__( self.__node_executable = executable self.__node_name = name self.__node_namespace = namespace - self.__autostart = autostart self.__parameters = [] if parameters is None else normalized_params self.__remappings = [] if remappings is None else list(normalize_remap_rules(remappings)) self.__ros_arguments = ros_arguments @@ -367,7 +365,7 @@ def node_name(self): @property def node_autostart(self): """Getter for autostart.""" - return self.__autostart + return False @property def is_lifecycle_node(self): From 92997ae02ced2ba529c317480cc3c98f9cf4b28f Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 29 Jan 2025 17:29:38 -0800 Subject: [PATCH 11/21] Fixing lifecyclenode type Signed-off-by: Steve Macenski --- launch_ros/launch_ros/event_handlers/on_state_transition.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch_ros/launch_ros/event_handlers/on_state_transition.py b/launch_ros/launch_ros/event_handlers/on_state_transition.py index 6751bf58..2210e65e 100644 --- a/launch_ros/launch_ros/event_handlers/on_state_transition.py +++ b/launch_ros/launch_ros/event_handlers/on_state_transition.py @@ -33,7 +33,7 @@ def __init__( self, *, entities: SomeEntitiesType, - target_lifecycle_node: Optional[SomeSubstitutionsType] = None, + target_lifecycle_node: Optional['LifecycleNode'] = None, transition: Optional[SomeSubstitutionsType] = None, start_state: Optional[SomeSubstitutionsType] = None, goal_state: Optional[SomeSubstitutionsType] = None, From 656b96e7e9803fe015aab6858ea1d13b4dbaf5f9 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 29 Jan 2025 17:32:20 -0800 Subject: [PATCH 12/21] update docstring Signed-off-by: Steve Macenski --- launch_ros/launch_ros/utilities/lifecycle_event_manager.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py index acdb7083..5abe99e8 100644 --- a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py +++ b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py @@ -52,7 +52,7 @@ def __init__(self, lifecycle_node) -> None: one, or even all lifecycle nodes, and it requests the targeted nodes to change state, see its documentation for more details. - :param name: The name of the lifecycle node. + :param lifecycle_node: The lifecycle node to event manage. """ self.__logger = launch.logging.get_logger(__name__) self.__lifecycle_node = lifecycle_node From 2daab8d080d45eccf142fc26355b47b3736b1ad9 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 29 Jan 2025 19:01:18 -0800 Subject: [PATCH 13/21] adding in composable lifecycle node Signed-off-by: Steve Macenski --- ...ycle_component_autostart_pub_sub_launch.py | 6 +- .../launch_ros/actions/lifecycle_node.py | 7 + .../actions/load_composable_nodes.py | 2 +- .../launch_ros/descriptions/__init__.py | 2 + .../descriptions/composable_lifecycle_node.py | 121 ++++++++++++++++++ .../descriptions/composable_node.py | 9 +- 6 files changed, 135 insertions(+), 12 deletions(-) create mode 100644 launch_ros/launch_ros/descriptions/composable_lifecycle_node.py diff --git a/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py b/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py index 22412913..65a03f5f 100644 --- a/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py +++ b/launch_ros/examples/lifecycle_component_autostart_pub_sub_launch.py @@ -19,7 +19,7 @@ import launch # noqa: E402 from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes -from launch_ros.descriptions import ComposableNode +from launch_ros.descriptions import ComposableLifecycleNode def main(argv=sys.argv[1:]): @@ -32,7 +32,7 @@ def main(argv=sys.argv[1:]): package='rclcpp_components', executable='component_container', composable_node_descriptions=[ - ComposableNode( + ComposableLifecycleNode( package='composition', plugin='composition::Listener', name='listener', @@ -44,7 +44,7 @@ def main(argv=sys.argv[1:]): loader = LoadComposableNodes( target_container='lifecycle_component_container', composable_node_descriptions=[ - ComposableNode( + ComposableLifecycleNode( package='composition', plugin='composition::Talker', name='talker', diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index c02d7e88..4fa029d0 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -39,6 +39,7 @@ def __init__( *, name: SomeSubstitutionsType, namespace: SomeSubstitutionsType, + autostart: Optional[bool] = False, **kwargs ) -> None: """ @@ -70,8 +71,14 @@ def __init__( """ super().__init__(name=name, namespace=namespace, **kwargs) self.__logger = launch.logging.get_logger(__name__) + self.__autostart = autostart self.__lifecycle_event_manager = None + @property + def node_autostart(self): + """Getter for autostart.""" + return self.__autostart + @property def is_lifecycle_node(self): return True diff --git a/launch_ros/launch_ros/actions/load_composable_nodes.py b/launch_ros/launch_ros/actions/load_composable_nodes.py index 7127acb2..ba3f3f3e 100644 --- a/launch_ros/launch_ros/actions/load_composable_nodes.py +++ b/launch_ros/launch_ros/actions/load_composable_nodes.py @@ -247,7 +247,7 @@ def execute( complete_node_name = '/' + complete_node_name self.__logger.info( 'Autostart enabled for requested lifecycle node {}'.format(complete_node_name)) - node_description.init_lifecycle_event_manager(complete_node_name, context) + node_description.init_lifecycle_event_manager(node_description, context) autostart_actions.append( LifecycleTransition( lifecycle_node_names=[complete_node_name], diff --git a/launch_ros/launch_ros/descriptions/__init__.py b/launch_ros/launch_ros/descriptions/__init__.py index fd5d9beb..b961a38d 100644 --- a/launch_ros/launch_ros/descriptions/__init__.py +++ b/launch_ros/launch_ros/descriptions/__init__.py @@ -15,6 +15,7 @@ """descriptions Module.""" from .composable_node import ComposableNode +from .composable_lifecycle_node import ComposableLifecycleNode from ..parameter_descriptions import Parameter from ..parameter_descriptions import ParameterFile from ..parameter_descriptions import ParameterValue @@ -22,6 +23,7 @@ __all__ = [ 'ComposableNode', + 'ComposableLifecycleNode', 'Parameter', 'ParameterFile', 'ParameterValue', diff --git a/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py b/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py new file mode 100644 index 00000000..b08989aa --- /dev/null +++ b/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py @@ -0,0 +1,121 @@ +# Copyright 2025 Open Navigation LLC +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Module for a description of a ComposableLifecycleNode.""" + +from typing import List +from typing import Optional + +import launch +from launch.condition import Condition +from launch.some_substitutions_type import SomeSubstitutionsType +from launch.substitution import Substitution +# from launch.utilities import ensure_argument_type +from launch.utilities import perform_substitutions +from launch_ros.parameters_type import Parameters +from launch_ros.parameters_type import SomeParameters +from launch_ros.remap_rule_type import RemapRules +from launch_ros.remap_rule_type import SomeRemapRules +from launch_ros.utilities import LifecycleEventManager + +from .composable_node import ComposableNode + + +class ComposableLifecycleNode(ComposableNode): + """Describes a lifecycle node that can be loaded into a container with other nodes.""" + + def __init__( + self, *, + package: SomeSubstitutionsType, + plugin: SomeSubstitutionsType, + name: Optional[SomeSubstitutionsType] = None, + namespace: Optional[SomeSubstitutionsType] = None, + parameters: Optional[SomeParameters] = None, + autostart: Optional[bool] = False, + remappings: Optional[SomeRemapRules] = None, + extra_arguments: Optional[SomeParameters] = None, + condition: Optional[Condition] = None, + ) -> None: + """ + Initialize a ComposableNode description. + + :param package: name of the ROS package the node plugin lives in + :param plugin: name of the plugin to be loaded + :param name: name to give to the ROS node + :param namespace: namespace to give to the ROS node + :param parameters: list of either paths to yaml files or dictionaries of parameters + :param autostart: Whether to autostart lifecycle node in the activated state + :param remappings: list of from/to pairs for remapping names + :param extra_arguments: container specific arguments to be passed to the loaded node + :param condition: action will be executed if the condition evaluates to true + """ + super().__init__( + package=package, + plugin=plugin, + name=name, + namespace=namespace, + parameters=parameters, + remappings=remappings, + extra_arguments=extra_arguments, + condition=condition) + + self.__autostart = autostart + self.__lifecycle_event_manager = None + self.__node_name = self._ComposableNode__node_name + + def init_lifecycle_event_manager(self, node, context: launch.LaunchContext) -> None: + # LifecycleEventManager needs a pre-substitution node name + self.__node_name = perform_substitutions(context, node.node_name) + self.__lifecycle_event_manager = LifecycleEventManager(node) + self.__lifecycle_event_manager.setup_lifecycle_manager(context) + + @property + def package(self) -> List[Substitution]: + """Get node package name as a sequence of substitutions to be performed.""" + return self._ComposableNode__package + + @property + def node_plugin(self) -> List[Substitution]: + """Get node plugin name as a sequence of substitutions to be performed.""" + return self._ComposableNode__node_plugin + + @property + def node_name(self) -> Optional[List[Substitution]]: + """Get node name as a sequence of substitutions to be performed.""" + return self.__node_name + + @property + def node_namespace(self) -> Optional[List[Substitution]]: + """Get node namespace as a sequence of substitutions to be performed.""" + return self._ComposableNode__node_namespace + + @property + def node_autostart(self): + """Getter for autostart.""" + return self.__autostart + + @property + def parameters(self) -> Optional[Parameters]: + """Get node parameter YAML files or dicts with substitutions to be performed.""" + return self._ComposableNode__parameters + + @property + def remappings(self) -> Optional[RemapRules]: + """Get node remapping rules as (from, to) tuples with substitutions to be performed.""" + return self._ComposableNode__remappings + + @property + def extra_arguments(self) -> Optional[Parameters]: + """Get container extra arguments YAML files or dicts with substitutions to be performed.""" + return self._ComposableNode__extra_arguments diff --git a/launch_ros/launch_ros/descriptions/composable_node.py b/launch_ros/launch_ros/descriptions/composable_node.py index ce8dbc91..1e3e42fe 100644 --- a/launch_ros/launch_ros/descriptions/composable_node.py +++ b/launch_ros/launch_ros/descriptions/composable_node.py @@ -45,7 +45,6 @@ def __init__( name: Optional[SomeSubstitutionsType] = None, namespace: Optional[SomeSubstitutionsType] = None, parameters: Optional[SomeParameters] = None, - autostart: Optional[bool] = False, remappings: Optional[SomeRemapRules] = None, extra_arguments: Optional[SomeParameters] = None, condition: Optional[Condition] = None, @@ -86,8 +85,6 @@ def __init__( self.__extra_arguments = normalize_parameters(extra_arguments) self.__condition = condition - self.__autostart = autostart - self.__lifecycle_event_manager = None @classmethod def parse(cls, parser: Parser, entity: Entity): @@ -148,10 +145,6 @@ def parse(cls, parser: Parser, entity: Entity): return cls, kwargs - def init_lifecycle_event_manager(self, node_name, context: launch.LaunchContext) -> None: - self.__lifecycle_event_manager = LifecycleEventManager(node_name) - self.__lifecycle_event_manager.setup_lifecycle_manager(context) - @property def package(self) -> List[Substitution]: """Get node package name as a sequence of substitutions to be performed.""" @@ -175,7 +168,7 @@ def node_namespace(self) -> Optional[List[Substitution]]: @property def node_autostart(self): """Getter for autostart.""" - return self.__autostart + return False @property def parameters(self) -> Optional[Parameters]: From ed8a18fa268545403923ee9019505f2372b2054a Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 7 Feb 2025 14:43:28 -0800 Subject: [PATCH 14/21] Adding docstring Signed-off-by: Steve Macenski --- launch_ros/launch_ros/actions/lifecycle_node.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index 4fa029d0..e8cb468c 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -68,6 +68,8 @@ def __init__( :param name: The name of the lifecycle node. Although it defaults to None it is a required parameter and the default will be removed in a future release. + :param namespace: The ROS namespace for this Node + :param autostart: Whether or not to automatically transition to the 'active' state. """ super().__init__(name=name, namespace=namespace, **kwargs) self.__logger = launch.logging.get_logger(__name__) From 281035a23cd3b0467ddb0e69c509e5eab48aabc2 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 7 Feb 2025 14:44:35 -0800 Subject: [PATCH 15/21] require autostart non-None Signed-off-by: Steve Macenski --- launch_ros/launch_ros/actions/lifecycle_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index e8cb468c..b5085509 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -39,7 +39,7 @@ def __init__( *, name: SomeSubstitutionsType, namespace: SomeSubstitutionsType, - autostart: Optional[bool] = False, + autostart: bool = False, **kwargs ) -> None: """ From a487b95b0c96265ab347d34e4b4e1908cd4488cd Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 7 Feb 2025 14:53:38 -0800 Subject: [PATCH 16/21] remove unused imports Signed-off-by: Steve Macenski --- launch_ros/launch_ros/descriptions/composable_node.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/launch_ros/launch_ros/descriptions/composable_node.py b/launch_ros/launch_ros/descriptions/composable_node.py index 1e3e42fe..be8fe301 100644 --- a/launch_ros/launch_ros/descriptions/composable_node.py +++ b/launch_ros/launch_ros/descriptions/composable_node.py @@ -17,7 +17,6 @@ from typing import List from typing import Optional -import launch from launch.condition import Condition from launch.conditions import IfCondition, UnlessCondition from launch.frontend import Entity @@ -30,7 +29,6 @@ from launch_ros.parameters_type import SomeParameters from launch_ros.remap_rule_type import RemapRules from launch_ros.remap_rule_type import SomeRemapRules -from launch_ros.utilities import LifecycleEventManager from launch_ros.utilities import normalize_parameters from launch_ros.utilities import normalize_remap_rules From 0f7b4a19528d700e3f3fcb49bfd69dcf9e24c683 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 7 Feb 2025 15:14:39 -0800 Subject: [PATCH 17/21] review comments continued Signed-off-by: Steve Macenski --- .../actions/load_composable_nodes.py | 2 +- .../descriptions/composable_lifecycle_node.py | 52 +++++-------------- 2 files changed, 15 insertions(+), 39 deletions(-) diff --git a/launch_ros/launch_ros/actions/load_composable_nodes.py b/launch_ros/launch_ros/actions/load_composable_nodes.py index ba3f3f3e..fde8cb31 100644 --- a/launch_ros/launch_ros/actions/load_composable_nodes.py +++ b/launch_ros/launch_ros/actions/load_composable_nodes.py @@ -247,7 +247,7 @@ def execute( complete_node_name = '/' + complete_node_name self.__logger.info( 'Autostart enabled for requested lifecycle node {}'.format(complete_node_name)) - node_description.init_lifecycle_event_manager(node_description, context) + node_description.init_lifecycle_event_manager(context) autostart_actions.append( LifecycleTransition( lifecycle_node_names=[complete_node_name], diff --git a/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py b/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py index b08989aa..e5d60cb1 100644 --- a/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py +++ b/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py @@ -34,61 +34,37 @@ class ComposableLifecycleNode(ComposableNode): """Describes a lifecycle node that can be loaded into a container with other nodes.""" - def __init__( self, *, - package: SomeSubstitutionsType, - plugin: SomeSubstitutionsType, - name: Optional[SomeSubstitutionsType] = None, - namespace: Optional[SomeSubstitutionsType] = None, - parameters: Optional[SomeParameters] = None, - autostart: Optional[bool] = False, - remappings: Optional[SomeRemapRules] = None, - extra_arguments: Optional[SomeParameters] = None, - condition: Optional[Condition] = None, + autostart: bool = False, + **kwargs ) -> None: """ - Initialize a ComposableNode description. + Initialize a ComposableLifecycleNode description. - :param package: name of the ROS package the node plugin lives in - :param plugin: name of the plugin to be loaded - :param name: name to give to the ROS node - :param namespace: namespace to give to the ROS node - :param parameters: list of either paths to yaml files or dictionaries of parameters :param autostart: Whether to autostart lifecycle node in the activated state - :param remappings: list of from/to pairs for remapping names - :param extra_arguments: container specific arguments to be passed to the loaded node - :param condition: action will be executed if the condition evaluates to true """ - super().__init__( - package=package, - plugin=plugin, - name=name, - namespace=namespace, - parameters=parameters, - remappings=remappings, - extra_arguments=extra_arguments, - condition=condition) + super().__init__(**kwargs) self.__autostart = autostart self.__lifecycle_event_manager = None - self.__node_name = self._ComposableNode__node_name + self.__node_name = super().node_name - def init_lifecycle_event_manager(self, node, context: launch.LaunchContext) -> None: + def init_lifecycle_event_manager(self, context: launch.LaunchContext) -> None: # LifecycleEventManager needs a pre-substitution node name - self.__node_name = perform_substitutions(context, node.node_name) - self.__lifecycle_event_manager = LifecycleEventManager(node) + self.__node_name = perform_substitutions(context, self.node_name) + self.__lifecycle_event_manager = LifecycleEventManager(self) self.__lifecycle_event_manager.setup_lifecycle_manager(context) @property def package(self) -> List[Substitution]: """Get node package name as a sequence of substitutions to be performed.""" - return self._ComposableNode__package + return super().package @property def node_plugin(self) -> List[Substitution]: """Get node plugin name as a sequence of substitutions to be performed.""" - return self._ComposableNode__node_plugin + return super().node_plugin @property def node_name(self) -> Optional[List[Substitution]]: @@ -98,7 +74,7 @@ def node_name(self) -> Optional[List[Substitution]]: @property def node_namespace(self) -> Optional[List[Substitution]]: """Get node namespace as a sequence of substitutions to be performed.""" - return self._ComposableNode__node_namespace + return super().node_namespace @property def node_autostart(self): @@ -108,14 +84,14 @@ def node_autostart(self): @property def parameters(self) -> Optional[Parameters]: """Get node parameter YAML files or dicts with substitutions to be performed.""" - return self._ComposableNode__parameters + return super().parameters @property def remappings(self) -> Optional[RemapRules]: """Get node remapping rules as (from, to) tuples with substitutions to be performed.""" - return self._ComposableNode__remappings + return super().remappings @property def extra_arguments(self) -> Optional[Parameters]: """Get container extra arguments YAML files or dicts with substitutions to be performed.""" - return self._ComposableNode__extra_arguments + return super().extra_arguments From 04914a4f25b8b79360771264cacf476ea0e7dca8 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 7 Feb 2025 15:24:37 -0800 Subject: [PATCH 18/21] is lifecycle node and autostart to lifecycle-only classes Signed-off-by: Steve Macenski --- launch_ros/launch_ros/actions/load_composable_nodes.py | 2 +- launch_ros/launch_ros/actions/node.py | 9 --------- launch_ros/launch_ros/descriptions/composable_node.py | 5 ----- .../launch_ros/event_handlers/on_state_transition.py | 6 +++++- 4 files changed, 6 insertions(+), 16 deletions(-) diff --git a/launch_ros/launch_ros/actions/load_composable_nodes.py b/launch_ros/launch_ros/actions/load_composable_nodes.py index fde8cb31..ba4f6e21 100644 --- a/launch_ros/launch_ros/actions/load_composable_nodes.py +++ b/launch_ros/launch_ros/actions/load_composable_nodes.py @@ -241,7 +241,7 @@ def execute( load_node_requests.append(request) # If autostart is enabled, transition to the 'active' state. - if node_description.node_autostart: + if hasattr(node_description, 'node_autostart') and node_description.node_autostart: complete_node_name = request.node_namespace + request.node_name if not complete_node_name.startswith('/'): complete_node_name = '/' + complete_node_name diff --git a/launch_ros/launch_ros/actions/node.py b/launch_ros/launch_ros/actions/node.py index bee43c83..fd684ce2 100644 --- a/launch_ros/launch_ros/actions/node.py +++ b/launch_ros/launch_ros/actions/node.py @@ -362,15 +362,6 @@ def node_name(self): raise RuntimeError("cannot access 'node_name' before executing action") return self.__final_node_name - @property - def node_autostart(self): - """Getter for autostart.""" - return False - - @property - def is_lifecycle_node(self): - return False - def is_node_name_fully_specified(self): keywords = (self.UNSPECIFIED_NODE_NAME, self.UNSPECIFIED_NODE_NAMESPACE) return all(x not in self.node_name for x in keywords) diff --git a/launch_ros/launch_ros/descriptions/composable_node.py b/launch_ros/launch_ros/descriptions/composable_node.py index be8fe301..8ad35c5c 100644 --- a/launch_ros/launch_ros/descriptions/composable_node.py +++ b/launch_ros/launch_ros/descriptions/composable_node.py @@ -163,11 +163,6 @@ def node_namespace(self) -> Optional[List[Substitution]]: """Get node namespace as a sequence of substitutions to be performed.""" return self.__node_namespace - @property - def node_autostart(self): - """Getter for autostart.""" - return False - @property def parameters(self) -> Optional[Parameters]: """Get node parameter YAML files or dicts with substitutions to be performed.""" diff --git a/launch_ros/launch_ros/event_handlers/on_state_transition.py b/launch_ros/launch_ros/event_handlers/on_state_transition.py index 2210e65e..6ecb09b4 100644 --- a/launch_ros/launch_ros/event_handlers/on_state_transition.py +++ b/launch_ros/launch_ros/event_handlers/on_state_transition.py @@ -55,7 +55,11 @@ def __init__( raise RuntimeError('OnStateTransition requires a "LifecycleNode" action as the target,' ' target_lifecycle_node is not a node type.') - if target_lifecycle_node and not target_lifecycle_node.is_lifecycle_node: + if ( + target_lifecycle_node and + hasattr(target_lifecycle_node, 'is_lifecycle_node') and + not target_lifecycle_node.is_lifecycle_node + ): raise RuntimeError('OnStateTransition requires a "LifecycleNode" action as the target,' ' target_lifecycle_node is not a lifecycle-enabled node.') From d125a69b5cca25be388cc11720330041ed953a42 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 7 Feb 2025 15:45:54 -0800 Subject: [PATCH 19/21] final bits Signed-off-by: Steve Macenski --- launch_ros/launch_ros/actions/lifecycle_node.py | 3 +++ .../launch_ros/utilities/lifecycle_event_manager.py | 8 +++----- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/launch_ros/launch_ros/actions/lifecycle_node.py b/launch_ros/launch_ros/actions/lifecycle_node.py index b5085509..79bca627 100644 --- a/launch_ros/launch_ros/actions/lifecycle_node.py +++ b/launch_ros/launch_ros/actions/lifecycle_node.py @@ -85,6 +85,9 @@ def node_autostart(self): def is_lifecycle_node(self): return True + def get_lifecycle_event_manager(self): + return self.__lifecycle_event_manager + def execute(self, context: launch.LaunchContext) -> Optional[List[Action]]: """ Execute the action. diff --git a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py index 5abe99e8..77c04b7b 100644 --- a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py +++ b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py @@ -63,12 +63,9 @@ def __init__(self, lifecycle_node) -> None: def node_name(self): return self.__lifecycle_node.node_name - def __eq__(self, other): - return self.__lifecycle_node == other - def _on_transition_event(self, context, msg): try: - event = StateTransition(action=self, msg=msg) + event = StateTransition(action=self.__lifecycle_node, msg=msg) context.asyncio_loop.call_soon_threadsafe(lambda: context.emit_event_sync(event)) except Exception as exc: self.__logger.error( @@ -116,8 +113,9 @@ def unblock(future): def _on_change_state_event(self, context: launch.LaunchContext) -> None: typed_event = cast(ChangeState, context.locals.event) - if not typed_event.lifecycle_node_matcher(self): + if not typed_event.lifecycle_node_matcher(self.__lifecycle_node): return None + print('Ju lee, were doing the thing!') request = lifecycle_msgs.srv.ChangeState.Request() request.transition.id = typed_event.transition_id context.add_completion_future( From 7b4fd4aa9b85a0009ef74d18f2113bc4f468c4e0 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 7 Feb 2025 15:50:00 -0800 Subject: [PATCH 20/21] whoops, remove the Avatar-inspired printout Signed-off-by: Steve Macenski --- launch_ros/launch_ros/utilities/lifecycle_event_manager.py | 1 - 1 file changed, 1 deletion(-) diff --git a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py index 77c04b7b..9e384d03 100644 --- a/launch_ros/launch_ros/utilities/lifecycle_event_manager.py +++ b/launch_ros/launch_ros/utilities/lifecycle_event_manager.py @@ -115,7 +115,6 @@ def _on_change_state_event(self, context: launch.LaunchContext) -> None: typed_event = cast(ChangeState, context.locals.event) if not typed_event.lifecycle_node_matcher(self.__lifecycle_node): return None - print('Ju lee, were doing the thing!') request = lifecycle_msgs.srv.ChangeState.Request() request.transition.id = typed_event.transition_id context.add_completion_future( From e03c8b22a30fac9922ec2dfc588230d80c379134 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 11 Feb 2025 18:43:55 -0800 Subject: [PATCH 21/21] finish linting Signed-off-by: Steve Macenski --- launch_ros/launch_ros/descriptions/__init__.py | 2 +- .../descriptions/composable_lifecycle_node.py | 5 +---- .../launch_ros/event_handlers/on_state_transition.py | 12 ++++++------ 3 files changed, 8 insertions(+), 11 deletions(-) diff --git a/launch_ros/launch_ros/descriptions/__init__.py b/launch_ros/launch_ros/descriptions/__init__.py index b961a38d..1d693013 100644 --- a/launch_ros/launch_ros/descriptions/__init__.py +++ b/launch_ros/launch_ros/descriptions/__init__.py @@ -14,8 +14,8 @@ """descriptions Module.""" -from .composable_node import ComposableNode from .composable_lifecycle_node import ComposableLifecycleNode +from .composable_node import ComposableNode from ..parameter_descriptions import Parameter from ..parameter_descriptions import ParameterFile from ..parameter_descriptions import ParameterValue diff --git a/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py b/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py index e5d60cb1..cca531ca 100644 --- a/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py +++ b/launch_ros/launch_ros/descriptions/composable_lifecycle_node.py @@ -18,15 +18,11 @@ from typing import Optional import launch -from launch.condition import Condition -from launch.some_substitutions_type import SomeSubstitutionsType from launch.substitution import Substitution # from launch.utilities import ensure_argument_type from launch.utilities import perform_substitutions from launch_ros.parameters_type import Parameters -from launch_ros.parameters_type import SomeParameters from launch_ros.remap_rule_type import RemapRules -from launch_ros.remap_rule_type import SomeRemapRules from launch_ros.utilities import LifecycleEventManager from .composable_node import ComposableNode @@ -34,6 +30,7 @@ class ComposableLifecycleNode(ComposableNode): """Describes a lifecycle node that can be loaded into a container with other nodes.""" + def __init__( self, *, autostart: bool = False, diff --git a/launch_ros/launch_ros/event_handlers/on_state_transition.py b/launch_ros/launch_ros/event_handlers/on_state_transition.py index 6ecb09b4..a4d57e74 100644 --- a/launch_ros/launch_ros/event_handlers/on_state_transition.py +++ b/launch_ros/launch_ros/event_handlers/on_state_transition.py @@ -33,7 +33,7 @@ def __init__( self, *, entities: SomeEntitiesType, - target_lifecycle_node: Optional['LifecycleNode'] = None, + target_lifecycle_node: Optional['LifecycleNode'] = None, # noqa: F821 transition: Optional[SomeSubstitutionsType] = None, start_state: Optional[SomeSubstitutionsType] = None, goal_state: Optional[SomeSubstitutionsType] = None, @@ -51,17 +51,17 @@ def __init__( If matcher is given, the other conditions are not considered. """ lifecycle_property = type(target_lifecycle_node).__dict__.get('is_lifecycle_node', None) - if not isinstance(lifecycle_property, (property, type(None))): - raise RuntimeError('OnStateTransition requires a "LifecycleNode" action as the target,' - ' target_lifecycle_node is not a node type.') + if target_lifecycle_node and not isinstance(lifecycle_property, (property)): + raise RuntimeError('OnStateTransition requires a lifecycle enabled node as the target,' + ' target_lifecycle_node is not a lifecycle-enabled node type.') if ( target_lifecycle_node and hasattr(target_lifecycle_node, 'is_lifecycle_node') and not target_lifecycle_node.is_lifecycle_node ): - raise RuntimeError('OnStateTransition requires a "LifecycleNode" action as the target,' - ' target_lifecycle_node is not a lifecycle-enabled node.') + raise RuntimeError('OnStateTransition requires a lifecycle enabled node as the target,' + ' target_lifecycle_node is not lifecycle-enabled.') # Handle optional matcher argument. self.__custom_matcher = matcher