Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Bug report: error when combining/nesting GroupAction, IncludeLaunchDescription and TimerAction with launch arguments #825

Open
M-Schroeder opened this issue Feb 4, 2025 · 6 comments · May be fixed by #836
Assignees

Comments

@M-Schroeder
Copy link

I have a nested launch structure. In one launch file, I used TimerAction to launch a Node with a time delay. This launch file is included in another launch file using IncludeLaunchDescription. If this IncludeLaunchDescription is used directly, it works. If it is again nested inside a GroupAction, it gives me an error.

Minimal example:

main_launch.py has following content:

from launch.actions import GroupAction
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource



def generate_launch_description():

    nested_launch = IncludeLaunchDescription(
        PythonLaunchDescriptionSource("./nested_launch.py"),
        launch_arguments={'robot_namespace': "scout_mini"}.items()
    )

    my_group_action = GroupAction(
        actions=[nested_launch]
    )


    ld = LaunchDescription()
    ld.add_action(my_group_action)
    # ld.add_action(nested_launch)
    return ld

nested_launch.py has following content:

from launch.actions import TimerAction
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument, TimerAction



def generate_launch_description():

    robot_namespace = LaunchConfiguration('robot_namespace')
    
    declare_robot_namespace_cmd = DeclareLaunchArgument(
        name='robot_namespace',
        default_value='scout_mini'
    )

    example_timer_action = TimerAction(
        actions=[
            Node(
                package="demo_nodes_py",
                executable="listener",
                namespace=robot_namespace
            )
        ],
        period=2.0
    )


    ld = LaunchDescription()
    ld.add_action(declare_robot_namespace_cmd)
    ld.add_action(example_timer_action)
    return ld

Error

Both launch files are in the same folder, I launch it with ros2 launch ./main_launch.py and get the following error:

[ERROR] [launch_ros.actions.node]: Error while expanding or validating node name or namespace for 'package=demo_nodes_py, executable=listener, name=None, namespace=<launch.substitutions.launch_configuration.LaunchConfiguration object at 0x7c5cff6e60b0>':
[ERROR] [launch]: Caught exception in launch (see debug for traceback): launch configuration 'robot_namespace' does not exist

(Similar behavior can be seen, if the launch files are properly organised in packages.)
Debugging in the upper level launch files was quite confusing, since putting something in a GroupAction shouldn't change its behavior much (from my understanding).

How it works

It works, if the main_launch.py instead ends with

    ld = LaunchDescription()
    # ld.add_action(my_group_action)
    ld.add_action(nested_launch)
    return ld

It also works, if alternatively you don't use TimerAction in nested_launch.py or if you have everything within one launch file. It seems to be a problem with this combination.

System

Ubuntu 22.04.5 LTS
ROS2 humble

@christophebedard christophebedard self-assigned this Feb 13, 2025
@christophebedard
Copy link
Member

Have you seen and played with the scoped and forwarding options?

"""
Action that yields other actions.
This action is used to nest other actions without including a separate
launch description, while also optionally having a condition (like all
other actions), scoping and forwarding launch configurations and
environment variables, and/or declaring launch configurations for just the
group and its yielded actions.
When scoped=True, changes to launch configurations and environment
variables are limited to the scope of actions in the group action.
When scoped=True and forwarding=True, all existing launch configurations
and environment variables are available in the scoped context.
When scoped=True and forwarding=False, all existing launch configurations
and environment variables are removed from the scoped context.
Any launch configuration defined in the launch_configurations dictionary
will be set in the current context.
When scoped=False these configurations will persist even after the
GroupAction has completed.
When scoped=True these configurations will only be available to actions in
the GroupAction.
When scoped=True and forwarding=False, the launch_configurations dictionary
is evaluated before clearing, and then re-set in the cleared scoped context.
"""
def __init__(
self,
actions: Iterable[Action],
*,
scoped: bool = True,
forwarding: bool = True,

@M-Schroeder
Copy link
Author

If I change the GroupAction to

    my_group_action = GroupAction(
        actions=[nested_launch],
        scoped = False,
    )

it works. I still don't understand why. Could you explain a bit more about the concepts of scoped and forwarding? Is it about separating everything inside the GroupAction from everything outside or is it about separating the actions inside the GroupAction from each other? (From my understanding, separating the inside and outside of the GroupAction would make more sense.) Keep in mind, that the TimerAction and DeclareLaunchArgument are within the IncludeLaunchDescription, which is itself inside the GroupAction. So everything is inside the GroupAction. Even if it was separated from the outside, it should still be in the same scope as DeclareLaunchArgument and at least get the argument with its default value.

I understand the concept as followed: With the default settings (scoped=True and forwarding=True) the actions inside should be in its own scope, so that e.g. setting environment variables inside the GroupAction has no effect outside. Because of forwarding, you should still have access (read access?) to everything, that was defined outside of the GroupAction. Are these assumptions correct? This would not explain the error and it should work with the default settings, right?

@christophebedard
Copy link
Member

I'm sorry, I haven't had time to properly dig into this. I'm hoping to do it by tomorrow.

@christophebedard
Copy link
Member

christophebedard commented Mar 14, 2025

Sorry again for the delay.

So I believe your understanding of the GroupAction's scoping and forwarding is correct, and that you should indeed not have to use scoped=False. However, your assumption about the TimerAction is unfortunately incorrect in practice.

I believe this a bug -- or at least a not-well-defined case -- with TimerAction. TimerActions's actions, in this case its Node, are only executed after the given period, which is 2.0 seconds in this case. This means that the substitution for the launch configuration used for the node's namespace (LaunchConfiguration('robot_namespace')) is only resolved (or "performed," as it's called in launch) then. By this point, the GroupAction's scoping feature has effectively reset the launch configurations, unless you disable scoping.

TimerAction already "saves" some of the launch context's data before it creates the timer so that it can be used later, when its actions execute:

  1. Save before creating the timer task:
    self.__context_locals = dict(context.get_locals_as_dict()) # Capture a copy
  2. Restore before the actions are executed:
    context.extend_locals(self.__context_locals)

If I do something similar for the launch context's launch configurations, then your original launch file works, without needing scoped=False:

diff --git a/launch/launch/actions/timer_action.py b/launch/launch/actions/timer_action.py
index ac9049c..863a07d 100644
--- a/launch/launch/actions/timer_action.py
+++ b/launch/launch/actions/timer_action.py
@@ -139,6 +139,7 @@ class TimerAction(Action):
     def handle(self, context: LaunchContext) -> Optional[SomeEntitiesType]:
         """Handle firing of timer."""
         context.extend_locals(self.__context_locals)
+        context.launch_configurations.update(self.__context_launch_configuration)
         return self.__actions
 
     def cancel(self) -> None:
@@ -191,6 +192,7 @@ class TimerAction(Action):
 
         # Capture the current context locals so the yielded actions can make use of them too.
         self.__context_locals = dict(context.get_locals_as_dict())  # Capture a copy
+        self.__context_launch_configuration = dict(context.launch_configurations)  # Capture a copy
         context.asyncio_loop.create_task(self._wait_to_fire_event(context))
 
         # By default, the 'shutdown' event will cause timers to cancel so they don't hold up the

I think this fix makes sense, but let me double-check and add a test, too.

@christophebedard
Copy link
Member

@M-Schroeder see #836. If you could give it a try and let me know if it works for you and if the changes to the TimerAction's behaviour make sense to you, that would be helpful.

@M-Schroeder
Copy link
Author

I tried the corresponding changes in ROS2 humble and it now works for me. Your explanation makes sense and the proposed behavior seems more intuitive. (Unfortunately, I am not familiar enough with this repo to understand everything of the code and your changes)
Thank you very much for the help

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging a pull request may close this issue.

2 participants