Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 12 additions & 0 deletions launch_ros/launch_ros/actions/load_composable_nodes.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@ def __init__(
*,
composable_node_descriptions: List[ComposableNode],
target_container: Union[SomeSubstitutionsType, ComposableNodeContainer],
on_failure_shutdown: bool = False,
**kwargs,
) -> None:
"""
Expand All @@ -79,6 +80,7 @@ def __init__(

:param composable_node_descriptions: descriptions of composable nodes to be loaded
:param target_container: the container to load the nodes into
:param on_failure_shutdown: if True, the launch will shutdown if a node fails to load
"""
ensure_argument_type(
target_container,
Expand All @@ -90,6 +92,7 @@ def __init__(
super().__init__(**kwargs)
self.__composable_node_descriptions = composable_node_descriptions
self.__target_container = target_container
self.__on_failure_shutdown = on_failure_shutdown
self.__final_target_container_name: Optional[Text] = None
self.__logger = launch.logging.get_logger(__name__)

Expand All @@ -101,6 +104,12 @@ def parse(cls, entity: Entity, parser: Parser):
kwargs['target_container'] = parser.parse_substitution(
entity.get_attr('target', data_type=str))

on_failure_shutdown = entity.get_attr(
'on_failure_shutdown', data_type=bool, optional=True
)
if on_failure_shutdown is not None:
kwargs['on_failure_shutdown'] = on_failure_shutdown

kwargs['composable_node_descriptions'] = []
composable_nodes = entity.get_attr(
'composable_node', data_type=List[Entity], optional=True) or []
Expand Down Expand Up @@ -201,6 +210,9 @@ def unblock(future):
response.error_message
)
)
# If the user requested strict behavior, trigger a clean shutdown
if self.__on_failure_shutdown:
raise RuntimeError('Failed to load component. Triggering shutdown.')

def _load_in_sequence(
self,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ class MockComponentContainer(rclpy.node.Node):
def __init__(self, context):
# List of LoadNode requests received
self.requests = []
self.fail_request = False

super().__init__(TEST_CONTAINER_NAME, context=context)

Expand All @@ -56,8 +57,16 @@ def __init__(self, context):
self.load_node_callback
)

def set_fail_request(self, fail_request: bool):
self.fail_request = fail_request

def load_node_callback(self, request, response):
self.requests.append(request)
if self.fail_request:
response.success = False
response.error_message = 'Component failure'
return response

response.success = True
if request.node_namespace == '/':
response.full_node_name = f'/{request.node_name}'
Expand All @@ -75,11 +84,20 @@ def _assert_launch_no_errors(actions):
return ls.context


def _assert_launch_errors(actions):
ld = LaunchDescription(actions)
ls = LaunchService(debug=True)
ls.include_launch_description(ld)
assert 0 != ls.run()
return ls.context


def _load_composable_node(
*,
package,
plugin,
name,
on_failure_shutdown=False,
namespace='',
condition=None,
parameters=None,
Expand All @@ -88,6 +106,7 @@ def _load_composable_node(
):
return LoadComposableNodes(
target_container=target_container,
on_failure_shutdown=on_failure_shutdown,
composable_node_descriptions=[
ComposableNode(
condition=condition,
Expand Down Expand Up @@ -654,3 +673,38 @@ def test_load_node_with_condition_in_group(mock_component_container):
assert len(request.remap_rules) == 0
assert len(request.parameters) == 0
assert len(request.extra_arguments) == 0


def test_load_node_failure_no_shutdown(mock_component_container):
"""Test that failure doesn't stop launch by default (on_failure_shutdown=False)."""
mock_component_container.set_fail_request(True)

# This should NOT raise an exception and should return 0 (success)
context = _assert_launch_no_errors([
_load_composable_node(
package='bad_package',
plugin='bad_plugin',
name='fail_node',
on_failure_shutdown=False
)
])

# The node count should be 0 because it failed to load
assert get_node_name_count(context, '/fail_node') == 0
assert len(mock_component_container.requests) == 1


def test_load_node_failure_with_shutdown(mock_component_container):
"""Test that failure triggers RuntimeError when on_failure_shutdown=True."""
mock_component_container.set_fail_request(True)

context = _assert_launch_errors([
_load_composable_node(
package='bad_package',
plugin='bad_plugin',
name='fail_node',
on_failure_shutdown=True
)
])

assert context.is_shutdown is True
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ def test_launch_component_container_yaml():

- load_composable_node:
target: my_container
on_failure_shutdown: false
composable_node:
- pkg: composition
plugin: composition::Listener
Expand Down Expand Up @@ -83,7 +84,7 @@ def test_launch_component_container_xml():
</composable_node>
</node_container>

<load_composable_node target="my_container">
<load_composable_node target="my_container" on_failure_shutdown="false">
<composable_node pkg="composition" plugin="composition::Listener" name="listener" namespace="test_namespace">
<remap from="chatter" to="/remap/chatter" />
<param name="use_sim_time" value="true"/>
Expand Down Expand Up @@ -121,6 +122,7 @@ def perform(substitution):
assert perform(node_container._Node__arguments[0]) == 'test_args'

assert perform(load_composable_node._LoadComposableNodes__target_container) == 'my_container'
assert load_composable_node._LoadComposableNodes__on_failure_shutdown is False

# Check node parameters
talker_remappings = list(talker._ComposableNode__remappings)
Expand Down