diff --git a/launch/launch/actions/__init__.py b/launch/launch/actions/__init__.py
index ae0577e33..d92717857 100644
--- a/launch/launch/actions/__init__.py
+++ b/launch/launch/actions/__init__.py
@@ -29,6 +29,7 @@
from .push_environment import PushEnvironment
from .push_launch_configurations import PushLaunchConfigurations
from .register_event_handler import RegisterEventHandler
+from .replace_environment_variables import ReplaceEnvironmentVariables
from .reset_environment import ResetEnvironment
from .reset_launch_configurations import ResetLaunchConfigurations
from .set_environment_variable import SetEnvironmentVariable
@@ -57,6 +58,7 @@
'ResetEnvironment',
'ResetLaunchConfigurations',
'RegisterEventHandler',
+ 'ReplaceEnvironmentVariables',
'SetEnvironmentVariable',
'SetLaunchConfiguration',
'Shutdown',
diff --git a/launch/launch/actions/replace_environment_variables.py b/launch/launch/actions/replace_environment_variables.py
new file mode 100644
index 000000000..5bba73830
--- /dev/null
+++ b/launch/launch/actions/replace_environment_variables.py
@@ -0,0 +1,78 @@
+# Copyright 2023 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.
+
+"""Module for the ReplaceEnvironmentVariables action."""
+
+from typing import List
+from typing import Mapping
+from typing import Text
+
+from ..action import Action
+from ..frontend import Entity
+from ..frontend import expose_action
+from ..frontend import Parser
+from ..launch_context import LaunchContext
+from ..utilities import normalize_to_list_of_substitutions
+from ..utilities import perform_substitutions
+
+
+@expose_action('rep_env')
+class ReplaceEnvironmentVariables(Action):
+ """
+ Action that replaces the environment variables in the current context.
+
+ The previous state can be saved by pushing the stack with the
+ :py:class:`launch.actions.PushEnvironment` action.
+ And can be restored by popping the stack with the
+ :py:class:`launch.actions.PopEnvironment` action.
+ """
+
+ def __init__(self, environment: Mapping[Text, Text] = {}, **kwargs) -> None:
+ """Create a ReplaceEnvironmentVariables action."""
+ super().__init__(**kwargs)
+ self.__environment = environment
+
+ @classmethod
+ def parse(
+ cls,
+ entity: Entity,
+ parser: Parser
+ ):
+ """Return the `ReplaceEnvironmentVariables` action and kwargs for constructing it."""
+ _, kwargs = super().parse(entity, parser)
+ env = entity.get_attr('env', data_type=List[Entity], optional=True)
+
+ if env is not None:
+ kwargs['environment'] = {
+ tuple(parser.parse_substitution(e.get_attr('name'))):
+ parser.parse_substitution(e.get_attr('value')) for e in env
+ }
+ for e in env:
+ e.assert_entity_completely_parsed()
+ return cls, kwargs
+
+ @property
+ def environment(self):
+ """Getter for environment."""
+ return self.__environment
+
+ def execute(self, context: LaunchContext):
+ """Execute the action."""
+ evaluated_environment = {}
+ for k, v in self.__environment.items():
+ evaluated_k = perform_substitutions(context, normalize_to_list_of_substitutions(k))
+ evaluated_v = perform_substitutions(context, normalize_to_list_of_substitutions(v))
+ evaluated_environment[evaluated_k] = evaluated_v
+
+ context._replace_environment(evaluated_environment)
diff --git a/launch/launch/actions/timer_action.py b/launch/launch/actions/timer_action.py
index ac9049c07..d0efc2b2f 100644
--- a/launch/launch/actions/timer_action.py
+++ b/launch/launch/actions/timer_action.py
@@ -30,6 +30,9 @@
import launch.logging
from .opaque_function import OpaqueFunction
+from .pop_environment import PopEnvironment
+from .push_environment import PushEnvironment
+from .replace_environment_variables import ReplaceEnvironmentVariables
from ..action import Action
from ..event_handler import EventHandler
@@ -84,6 +87,7 @@ def __init__(
self.__period = type_utils.normalize_typed_substitution(period, float)
self.__actions = actions
self.__context_locals: Dict[Text, Any] = {}
+ self.__context_environment: Dict[Text, Text] = {}
self._completed_future: Optional[asyncio.Future] = None
self.__canceled = False
self._canceled_future: Optional[asyncio.Future] = None
@@ -139,7 +143,12 @@ def describe_conditional_sub_entities(self) -> List[Tuple[
def handle(self, context: LaunchContext) -> Optional[SomeEntitiesType]:
"""Handle firing of timer."""
context.extend_locals(self.__context_locals)
- return self.__actions
+ return [
+ PushEnvironment(),
+ ReplaceEnvironmentVariables(self.__context_environment),
+ *self.__actions,
+ PopEnvironment(),
+ ]
def cancel(self) -> None:
"""
@@ -191,6 +200,8 @@ def execute(self, context: LaunchContext) -> Optional[List[LaunchDescriptionEnti
# 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
+ # Capture the current context environment so the yielded actions can make use of them too.
+ self.__context_environment = dict(context.environment) # 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
diff --git a/launch/launch/launch_context.py b/launch/launch/launch_context.py
index e86092f4f..b88a4d03e 100644
--- a/launch/launch/launch_context.py
+++ b/launch/launch/launch_context.py
@@ -188,6 +188,10 @@ def _reset_environment(self):
os.environ.clear()
os.environ.update(self.__environment_reset)
+ def _replace_environment(self, environment: Mapping[Text, Text]):
+ os.environ.clear()
+ os.environ.update(environment)
+
def _push_launch_configurations(self):
self.__launch_configurations_stack.append(self.__launch_configurations.copy())
diff --git a/launch/test/launch/actions/test_replace_environment_variables.py b/launch/test/launch/actions/test_replace_environment_variables.py
new file mode 100644
index 000000000..bfddcabde
--- /dev/null
+++ b/launch/test/launch/actions/test_replace_environment_variables.py
@@ -0,0 +1,93 @@
+# Copyright 2023 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.
+
+"""Tests for the ReplaceEnvironmentVariables action classes."""
+
+import os
+
+from launch import LaunchContext
+from launch.actions import PopEnvironment
+from launch.actions import PushEnvironment
+from launch.actions import ReplaceEnvironmentVariables
+
+from temporary_environment import sandbox_environment_variables
+
+
+@sandbox_environment_variables
+def test_replace_environment_constructors():
+ """Test the constructors for ReplaceEnvironmentVariables class."""
+ ReplaceEnvironmentVariables({})
+ ReplaceEnvironmentVariables({'foo': 'bar', 'spam': 'eggs'})
+
+
+@sandbox_environment_variables
+def test_replace_environment_execute():
+ """Test the execute() of the ReplaceEnvironmentVariables class."""
+ assert isinstance(os.environ, os._Environ)
+
+ # replaces empty state
+ context = LaunchContext()
+ context.environment.clear()
+ assert len(context.environment) == 0
+ ReplaceEnvironmentVariables({'foo': 'bar', 'spam': 'eggs'}).visit(context)
+ assert len(context.environment) == 2
+ assert 'foo' in context.environment
+ assert context.environment['foo'] == 'bar'
+ assert 'spam' in context.environment
+ assert context.environment['spam'] == 'eggs'
+
+ # replaces non empty state
+ context = LaunchContext()
+ context.environment.clear()
+ assert len(context.environment) == 0
+ context.environment['quux'] = 'quuux'
+ assert len(context.environment) == 1
+ assert 'quux' in context.environment
+ assert context.environment['quux'] == 'quuux'
+ ReplaceEnvironmentVariables({'foo': 'bar', 'spam': 'eggs'}).visit(context)
+ assert len(context.environment) == 2
+ assert 'foo' in context.environment
+ assert context.environment['foo'] == 'bar'
+ assert 'spam' in context.environment
+ assert context.environment['spam'] == 'eggs'
+
+ # replaces existing environment variable
+ context = LaunchContext()
+ context.environment.clear()
+ assert len(context.environment) == 0
+ context.environment['quux'] = 'quuux'
+ assert len(context.environment) == 1
+ assert 'quux' in context.environment
+ assert context.environment['quux'] == 'quuux'
+ ReplaceEnvironmentVariables({'quux': 'eggs'}).visit(context)
+ assert len(context.environment) == 1
+ assert 'quux' in context.environment
+ assert context.environment['quux'] == 'eggs'
+
+ # Replacing the environment should not change the type of os.environ
+ assert isinstance(os.environ, os._Environ)
+
+ # does not interfere with PopEnvironment and PushEnvironment action classes
+ context = LaunchContext()
+ context.environment.clear()
+ context.environment['quux'] = 'quuux'
+ assert len(context.environment) == 1
+ assert 'quux' in context.environment
+ assert context.environment['quux'] == 'quuux'
+ PushEnvironment().visit(context)
+ ReplaceEnvironmentVariables({'foo': 'bar', 'spam': 'eggs'}).visit(context)
+ PopEnvironment().visit(context)
+ assert len(context.environment) == 1
+ assert 'quux' in context.environment
+ assert context.environment['quux'] == 'quuux'
diff --git a/launch/test/launch/test_timer_action.py b/launch/test/launch/test_timer_action.py
index b5bb75373..e28b2f2f5 100644
--- a/launch/test/launch/test_timer_action.py
+++ b/launch/test/launch/test_timer_action.py
@@ -16,9 +16,72 @@
"""Tests for the TimerAction Action."""
import sys
-import launch
-import launch.actions
-import launch.event_handlers
+from launch import LaunchDescription
+from launch import LaunchService
+from launch.actions import ExecuteProcess
+from launch.actions import GroupAction
+from launch.actions import RegisterEventHandler
+from launch.actions import SetEnvironmentVariable
+from launch.actions import Shutdown
+from launch.actions import TimerAction
+from launch.conditions import IfCondition
+from launch.event_handlers import OnShutdown
+from launch.substitutions import EnvironmentVariable
+from launch.substitutions import NotSubstitution
+from launch.substitutions import PythonExpression
+
+
+def test_timer_action_can_capture_the_environment():
+ """Test that timer actions capture the environment variables present when executed."""
+ # Regression test for https://github.com/ros2/launch_ros/issues/376
+ shutdown_reasons = []
+
+ variable_is_set = PythonExpression([
+ "'",
+ EnvironmentVariable('LAUNCH_TEST_ENV_VAR', default_value='BAR'),
+ "' == 'FOO'"
+ ])
+
+ ld = LaunchDescription([
+
+ ExecuteProcess(
+ cmd=[sys.executable, '-c', 'while True: pass'],
+ ),
+
+ GroupAction(
+ actions=[
+
+ SetEnvironmentVariable(
+ name='LAUNCH_TEST_ENV_VAR',
+ value='FOO'
+ ),
+
+ TimerAction(
+ period=1.,
+ actions=[
+
+ Shutdown(
+ condition=IfCondition(variable_is_set),
+ reason='Test passing'
+ ),
+
+ Shutdown(
+ condition=IfCondition(NotSubstitution(variable_is_set)),
+ reason='Test failing'
+ ),
+ ]
+ ),
+ ]
+ ),
+
+ _shutdown_listener_factory(shutdown_reasons),
+ ])
+
+ ls = LaunchService()
+ ls.include_launch_description(ld)
+ assert 0 == ls.run()
+ assert len(shutdown_reasons) == 1
+ assert shutdown_reasons[0].reason == 'Test passing'
def test_multiple_launch_with_timers():
@@ -27,33 +90,33 @@ def test_multiple_launch_with_timers():
# ls.run
def generate_launch_description():
- return launch.LaunchDescription([
+ return LaunchDescription([
- launch.actions.ExecuteProcess(
+ ExecuteProcess(
cmd=[sys.executable, '-c', 'while True: pass'],
),
- launch.actions.TimerAction(
+ TimerAction(
period=1.,
actions=[
- launch.actions.Shutdown(reason='Timer expired')
+ Shutdown(reason='Timer expired')
]
)
])
- ls = launch.LaunchService()
+ ls = LaunchService()
ls.include_launch_description(generate_launch_description())
assert 0 == ls.run() # Always works
- ls = launch.LaunchService()
+ ls = LaunchService()
ls.include_launch_description(generate_launch_description())
# Next line hangs forever before https://github.com/ros2/launch/issues/183 was fixed.
assert 0 == ls.run()
def _shutdown_listener_factory(reasons_arr):
- return launch.actions.RegisterEventHandler(
- launch.event_handlers.OnShutdown(
+ return RegisterEventHandler(
+ OnShutdown(
on_shutdown=lambda event, context: reasons_arr.append(event)
)
)
@@ -66,22 +129,22 @@ def test_timer_action_sanity_check():
# and other launch related infrastructure works as expected
shutdown_reasons = []
- ld = launch.LaunchDescription([
- launch.actions.ExecuteProcess(
+ ld = LaunchDescription([
+ ExecuteProcess(
cmd=[sys.executable, '-c', 'while True: pass'],
),
- launch.actions.TimerAction(
+ TimerAction(
period=1.,
actions=[
- launch.actions.Shutdown(reason='One second timeout')
+ Shutdown(reason='One second timeout')
]
),
_shutdown_listener_factory(shutdown_reasons),
])
- ls = launch.LaunchService()
+ ls = LaunchService()
ls.include_launch_description(ld)
assert 0 == ls.run()
assert shutdown_reasons[0].reason == 'One second timeout'
@@ -90,30 +153,30 @@ def test_timer_action_sanity_check():
def test_shutdown_preempts_timers():
shutdown_reasons = []
- ld = launch.LaunchDescription([
+ ld = LaunchDescription([
- launch.actions.ExecuteProcess(
+ ExecuteProcess(
cmd=[sys.executable, '-c', 'while True: pass'],
),
- launch.actions.TimerAction(
+ TimerAction(
period=1.,
actions=[
- launch.actions.Shutdown(reason='fast shutdown')
+ Shutdown(reason='fast shutdown')
]
),
- launch.actions.TimerAction(
+ TimerAction(
period=2.,
actions=[
- launch.actions.Shutdown(reason='slow shutdown')
+ Shutdown(reason='slow shutdown')
]
),
_shutdown_listener_factory(shutdown_reasons),
])
- ls = launch.LaunchService()
+ ls = LaunchService()
ls.include_launch_description(ld)
assert 0 == ls.run()
assert len(shutdown_reasons) == 1
@@ -123,23 +186,23 @@ def test_shutdown_preempts_timers():
def test_timer_can_block_preemption():
shutdown_reasons = []
- ld = launch.LaunchDescription([
+ ld = LaunchDescription([
- launch.actions.ExecuteProcess(
+ ExecuteProcess(
cmd=[sys.executable, '-c', 'while True: pass'],
),
- launch.actions.TimerAction(
+ TimerAction(
period=1.,
actions=[
- launch.actions.Shutdown(reason='fast shutdown')
+ Shutdown(reason='fast shutdown')
]
),
- launch.actions.TimerAction(
+ TimerAction(
period=2.,
actions=[
- launch.actions.Shutdown(reason='slow shutdown')
+ Shutdown(reason='slow shutdown')
],
cancel_on_shutdown=False # Preempted in test_shutdown_preempts_timers, but not here
),
@@ -147,7 +210,7 @@ def test_timer_can_block_preemption():
_shutdown_listener_factory(shutdown_reasons),
])
- ls = launch.LaunchService()
+ ls = LaunchService()
ls.include_launch_description(ld)
assert 0 == ls.run()
assert len(shutdown_reasons) == 2 # Should see 'shutdown' event twice because
diff --git a/launch_xml/test/launch_xml/test_rep_env.py b/launch_xml/test/launch_xml/test_rep_env.py
new file mode 100644
index 000000000..1e749be4e
--- /dev/null
+++ b/launch_xml/test/launch_xml/test_rep_env.py
@@ -0,0 +1,80 @@
+# Copyright 2023 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.
+
+"""Test parsing a rep_env action."""
+
+import io
+import textwrap
+
+from launch import LaunchContext
+from launch.actions import ReplaceEnvironmentVariables
+from launch.actions import SetLaunchConfiguration
+from launch.frontend import Parser
+
+
+def test_rep_env():
+ xml_file = \
+ """\
+
+
+
+
+
+
+
+
+ """
+ xml_file = textwrap.dedent(xml_file)
+ root_entity, parser = Parser.load(io.StringIO(xml_file))
+ ld = parser.parse_description(root_entity)
+
+ assert len(ld.entities) == 2
+ assert isinstance(ld.entities[0], SetLaunchConfiguration)
+ assert isinstance(ld.entities[1], ReplaceEnvironmentVariables)
+
+ lc = LaunchContext()
+ ld.entities[0].visit(lc)
+ ld.entities[1].execute(lc)
+
+ assert 3 == len(lc.environment)
+ assert 'foo' in lc.environment
+ assert lc.environment['foo'] == 'bar'
+ assert 'spam' in lc.environment
+ assert lc.environment['spam'] == 'eggs'
+ assert 'quux' in lc.environment
+ assert lc.environment['quux'] == 'quuux'
+
+
+def test_rep_env_no_envs():
+ xml_file = \
+ """\
+
+
+
+ """
+ xml_file = textwrap.dedent(xml_file)
+ root_entity, parser = Parser.load(io.StringIO(xml_file))
+ ld = parser.parse_description(root_entity)
+
+ assert len(ld.entities) == 1
+ assert isinstance(ld.entities[0], ReplaceEnvironmentVariables)
+
+ lc = LaunchContext()
+ ld.entities[0].execute(lc)
+
+ assert 0 == len(lc.environment)
+
+
+if __name__ == '__main__':
+ test_rep_env()
diff --git a/launch_yaml/test/launch_yaml/test_rep_env.py b/launch_yaml/test/launch_yaml/test_rep_env.py
new file mode 100644
index 000000000..ef8867587
--- /dev/null
+++ b/launch_yaml/test/launch_yaml/test_rep_env.py
@@ -0,0 +1,83 @@
+# Copyright 2023 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.
+
+"""Test parsing a rep_env action."""
+
+import io
+import textwrap
+
+from launch import LaunchContext
+from launch.actions import ReplaceEnvironmentVariables
+from launch.actions import SetLaunchConfiguration
+from launch.frontend import Parser
+
+
+def test_rep_env():
+ yaml_file = \
+ """\
+ launch:
+ - let:
+ name: 'bar'
+ value: 'bar'
+ - rep_env:
+ env:
+ - name: 'foo'
+ value: $(var bar)
+ - name: 'spam'
+ value: 'eggs'
+ - name: 'quux'
+ value: 'quuux'
+ """ # noqa: E501
+ yaml_file = textwrap.dedent(yaml_file)
+ root_entity, parser = Parser.load(io.StringIO(yaml_file))
+ ld = parser.parse_description(root_entity)
+
+ assert len(ld.entities) == 2
+ assert isinstance(ld.entities[0], SetLaunchConfiguration)
+ assert isinstance(ld.entities[1], ReplaceEnvironmentVariables)
+
+ lc = LaunchContext()
+ ld.entities[0].visit(lc)
+ ld.entities[1].execute(lc)
+
+ assert 3 == len(lc.environment)
+ assert 'foo' in lc.environment
+ assert lc.environment['foo'] == 'bar'
+ assert 'spam' in lc.environment
+ assert lc.environment['spam'] == 'eggs'
+ assert 'quux' in lc.environment
+ assert lc.environment['quux'] == 'quuux'
+
+
+def test_rep_env_no_envs():
+ yaml_file = \
+ """\
+ launch:
+ - rep_env: {}
+ """ # noqa: E501
+ yaml_file = textwrap.dedent(yaml_file)
+ root_entity, parser = Parser.load(io.StringIO(yaml_file))
+ ld = parser.parse_description(root_entity)
+
+ assert len(ld.entities) == 1
+ assert isinstance(ld.entities[0], ReplaceEnvironmentVariables)
+
+ lc = LaunchContext()
+ ld.entities[0].execute(lc)
+
+ assert 0 == len(lc.environment)
+
+
+if __name__ == '__main__':
+ test_rep_env()