diff --git a/launch/launch/actions/execute_local.py b/launch/launch/actions/execute_local.py
index 487ae905c..146cca0ae 100644
--- a/launch/launch/actions/execute_local.py
+++ b/launch/launch/actions/execute_local.py
@@ -19,6 +19,7 @@
import logging
import os
import platform
+import shlex
import signal
import traceback
from typing import Any # noqa: F401
@@ -73,6 +74,8 @@
from ..utilities.type_utils import normalize_typed_substitution
from ..utilities.type_utils import perform_typed_substitution
+g_is_windows = 'win' in platform.system().lower()
+
class ExecuteLocal(Action):
"""Action that begins executing a process on the local system and sets up event handlers."""
@@ -82,6 +85,10 @@ def __init__(
*,
process_description: Executable,
shell: bool = False,
+ split_arguments: Union[
+ bool,
+ SomeSubstitutionsType
+ ] = LaunchConfiguration('split_arguments', default='False'),
sigterm_timeout: SomeSubstitutionsType = LaunchConfiguration(
'sigterm_timeout', default=5),
sigkill_timeout: SomeSubstitutionsType = LaunchConfiguration(
@@ -150,6 +157,24 @@ def __init__(
:param: process_description the `launch.descriptions.Executable` to execute
as a local process
:param: shell if True, a shell is used to execute the cmd
+ :param: split_arguments if True, and shell=False, the arguments are
+ split by whitespace as if parsed by a shell, e.g. like shlex.split()
+ from Python's standard library.
+ Useful if the arguments need to be split, e.g. if a substitution
+ evaluates to multiple whitespace separated arguments but shell=True
+ cannot be used.
+ Usually it does not make sense to split the arguments if shell=True
+ because the shell will split them again, e.g. the single
+ substitution '--opt1 --opt2 "Hello world"' would become ['--opt1',
+ '--opt2', '"Hello World"'] if split_arguments=True, and then become
+ ['--opt1', '--opt2', 'Hello', 'World'] because of shell=True, which
+ is likely not what was originally intended.
+ Therefore, when both shell=True and split_arguments=True, the
+ arguments will not be split before executing, depending on the
+ shell to split the arguments instead.
+ If not explicitly passed, the LaunchConfiguration called
+ 'split_arguments' will be used as the default, and if that
+ LaunchConfiguration is not set, the default will be False.
:param: sigterm_timeout time until shutdown should escalate to SIGTERM,
as a string or a list of strings and Substitutions to be resolved
at runtime, defaults to the LaunchConfiguration called
@@ -188,6 +213,9 @@ def __init__(
super().__init__(**kwargs)
self.__process_description = process_description
self.__shell = shell
+ if isinstance(split_arguments, bool):
+ split_arguments = 'True' if split_arguments else 'False'
+ self.__split_arguments = normalize_to_list_of_substitutions(split_arguments)
self.__sigterm_timeout = normalize_to_list_of_substitutions(sigterm_timeout)
self.__sigkill_timeout = normalize_to_list_of_substitutions(sigkill_timeout)
self.__emulate_tty = emulate_tty
@@ -234,6 +262,11 @@ def shell(self):
"""Getter for shell."""
return self.__shell
+ @property
+ def split_arguments(self):
+ """Getter for split_arguments."""
+ return self.__split_arguments
+
@property
def emulate_tty(self):
"""Getter for emulate_tty."""
@@ -326,7 +359,7 @@ def __on_signal_process_event(
typed_event.signal_name, self.process_details['name']),
)
return None
- if platform.system() == 'Windows' and typed_event.signal_name == 'SIGINT':
+ if g_is_windows and typed_event.signal_name == 'SIGINT':
# TODO(wjwwood): remove this when/if SIGINT is fixed on Windows
self.__logger.warning(
"'SIGINT' sent to process[{}] not supported on Windows, escalating to 'SIGTERM'"
@@ -550,11 +583,14 @@ async def __execute_process(self, context: LaunchContext) -> None:
cwd = process_event_args['cwd']
env = process_event_args['env']
if self.__log_cmd:
- self.__logger.info("process details: cmd='{}', cwd='{}', custom_env?={}".format(
- ' '.join(filter(lambda part: part.strip(), cmd)),
- cwd,
- 'True' if env is not None else 'False'
- ))
+ self.__logger.info(
+ "process details: cmd=['{}'], cwd='{}', shell='{}', custom_env?={}".format(
+ "', '".join(cmd),
+ cwd,
+ 'True' if self.__shell else 'False',
+ 'True' if env is not None else 'False',
+ )
+ )
emulate_tty = self.__emulate_tty
if 'emulate_tty' in context.launch_configurations:
@@ -593,8 +629,8 @@ async def __execute_process(self, context: LaunchContext) -> None:
if returncode == 0:
self.__logger.info('process has finished cleanly [pid {}]'.format(pid))
else:
- self.__logger.error("process has died [pid {}, exit code {}, cmd '{}'].".format(
- pid, returncode, ' '.join(filter(lambda part: part.strip(), cmd))
+ self.__logger.error("process has died [pid {}, exit code {}, cmd ['{}']].".format(
+ pid, returncode, "', '".join(cmd)
))
await context.emit_event(
ProcessExited(returncode=returncode, **process_event_args)
@@ -714,6 +750,18 @@ def execute(self, context: LaunchContext) -> Optional[List[LaunchDescriptionEnti
else:
self.__stdout_logger, self.__stderr_logger = \
launch.logging.get_output_loggers(name, self.__output)
+ # Update the cmd to respect split_arguments option.
+ if evaluate_condition_expression(context, self.__split_arguments):
+ if self.__shell:
+ self.__logger.debug("Ignoring 'split_arguments=True' because 'shell=True'.")
+ else:
+ self.__logger.debug("Splitting arguments because 'split_arguments=True'.")
+ expanded_cmd = []
+ assert self.__process_event_args is not None
+ for token in self.__process_event_args['cmd']:
+ expanded_cmd.extend(shlex.split(token, posix=(not g_is_windows)))
+ # Also update self.__process_event_args['cmd'] so it reflects the splitting.
+ self.__process_event_args['cmd'] = expanded_cmd
context.asyncio_loop.create_task(self.__execute_process(context))
except Exception:
for event_handler in event_handlers:
diff --git a/launch/launch/actions/execute_process.py b/launch/launch/actions/execute_process.py
index c780af7be..ce511d9d1 100644
--- a/launch/launch/actions/execute_process.py
+++ b/launch/launch/actions/execute_process.py
@@ -14,6 +14,7 @@
"""Module for the ExecuteProcess action."""
+import platform
import shlex
from typing import Dict
from typing import Iterable
@@ -21,6 +22,8 @@
from typing import Optional
from typing import Text
+import launch.logging
+
from .execute_local import ExecuteLocal
from .shutdown_action import Shutdown
from ..descriptions import Executable
@@ -32,6 +35,8 @@
from ..substitution import Substitution
from ..substitutions import TextSubstitution
+g_is_windows = 'win' in platform.system().lower()
+
@expose_action('executable')
class ExecuteProcess(ExecuteLocal):
@@ -260,14 +265,21 @@ def _append_arg():
nonlocal arg
result_args.append(arg)
arg = []
+
for sub in parser.parse_substitution(cmd):
if isinstance(sub, TextSubstitution):
- tokens = shlex.split(sub.text)
- if not tokens:
- # String with just spaces.
+ try:
+ tokens = shlex.split(sub.text, posix=(not g_is_windows))
+ except Exception:
+ logger = launch.logging.get_logger(cls.__name__)
+ logger.error(f"Failed to parse token '{sub.text}' of cmd '{cmd}'")
+ raise
+ if len(tokens) == 0:
+ # String with just spaces produces an empty list.
# Appending args allow splitting two substitutions
- # separated by a space.
- # e.g.: `$(subst1 asd) $(subst2 bsd)` will be two separate arguments.
+ # separated by some amount of whitespace.
+ # e.g.: `$(subst1 asd) $(subst2 bsd)` will be two separate arguments,
+ # first `$(subst1 asd)`, then this case ` `, then the `$(subst2 bsd)`.
_append_arg()
continue
if sub.text[0].isspace():
@@ -397,11 +409,21 @@ def parse(
if shell is not None:
kwargs['shell'] = shell
+ if 'split_arguments' not in ignore:
+ split_arguments = entity.get_attr('split_arguments', data_type=bool, optional=True)
+ if split_arguments is not None:
+ kwargs['split_arguments'] = split_arguments
+
if 'emulate_tty' not in ignore:
emulate_tty = entity.get_attr('emulate_tty', data_type=bool, optional=True)
if emulate_tty is not None:
kwargs['emulate_tty'] = emulate_tty
+ if 'log_cmd' not in ignore:
+ log_cmd = entity.get_attr('log_cmd', data_type=bool, optional=True)
+ if log_cmd is not None:
+ kwargs['log_cmd'] = log_cmd
+
if 'additional_env' not in ignore:
# Conditions won't be allowed in the `env` tag.
# If that feature is needed, `set_enviroment_variable` and
diff --git a/launch/launch/descriptions/executable.py b/launch/launch/descriptions/executable.py
index 3d1d0640b..930801921 100644
--- a/launch/launch/descriptions/executable.py
+++ b/launch/launch/descriptions/executable.py
@@ -18,6 +18,7 @@
"""Module for a description of an Executable."""
import os
+import platform
import re
import shlex
import threading
@@ -37,6 +38,7 @@
_executable_process_counter_lock = threading.Lock()
_executable_process_counter = 0 # in Python3, this number is unbounded (no rollover)
+g_is_windows = 'win' in platform.system().lower()
class Executable:
@@ -179,7 +181,9 @@ def prepare(self, context: LaunchContext, action: Action):
# Apply if filter regex matches (empty regex matches all strings)
should_apply_prefix = re.match(prefix_filter, os.path.basename(cmd[0])) is not None
if should_apply_prefix:
- cmd = shlex.split(perform_substitutions(context, self.__prefix)) + cmd
+ cmd = shlex.split(
+ perform_substitutions(context, self.__prefix), posix=(not g_is_windows)
+ ) + cmd
self.__final_cmd = cmd
name = os.path.basename(cmd[0]) if self.__name is None \
else perform_substitutions(context, self.__name)
diff --git a/launch/launch/substitutions/command.py b/launch/launch/substitutions/command.py
index 0aed7a9d6..6d0ddc840 100644
--- a/launch/launch/substitutions/command.py
+++ b/launch/launch/substitutions/command.py
@@ -14,7 +14,7 @@
"""Module for the Command substitution."""
-import os
+import platform
import shlex
import subprocess
from typing import List
@@ -30,6 +30,8 @@
from ..some_substitutions_type import SomeSubstitutionsType
from ..substitution import Substitution
+g_is_windows = 'win' in platform.system().lower()
+
@expose_substitution('command')
class Command(Substitution):
@@ -94,10 +96,7 @@ def perform(self, context: LaunchContext) -> Text:
from ..utilities import perform_substitutions # import here to avoid loop
command_str = perform_substitutions(context, self.command)
command: Union[str, List[str]]
- if os.name != 'nt':
- command = shlex.split(command_str)
- else:
- command = command_str
+ command = shlex.split(command_str, posix=(not g_is_windows))
on_stderr = perform_substitutions(context, self.on_stderr)
if on_stderr not in ('fail', 'ignore', 'warn', 'capture'):
raise SubstitutionFailure(
diff --git a/launch/test/launch/argv_echo.py b/launch/test/launch/argv_echo.py
new file mode 100644
index 000000000..ac6b3915c
--- /dev/null
+++ b/launch/test/launch/argv_echo.py
@@ -0,0 +1,28 @@
+# 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.
+
+"""Used from test_execute_process.py and others."""
+
+
+import sys
+
+
+def print_argv(argv):
+ joined_args = "', '".join(argv)
+ print(f"['{joined_args}']")
+ sys.exit(len(argv))
+
+
+if __name__ == '__main__':
+ print_argv(sys.argv)
diff --git a/launch/test/launch/test_execute_process.py b/launch/test/launch/test_execute_process.py
index fe6408fbe..264710496 100644
--- a/launch/test/launch/test_execute_process.py
+++ b/launch/test/launch/test_execute_process.py
@@ -24,12 +24,15 @@
from launch import LaunchService
from launch.actions import SetLaunchConfiguration
from launch.actions.emit_event import EmitEvent
+from launch.actions.execute_local import g_is_windows
from launch.actions.execute_process import ExecuteProcess
from launch.actions.opaque_function import OpaqueFunction
from launch.actions.register_event_handler import RegisterEventHandler
from launch.actions.shutdown_action import Shutdown
from launch.actions.timer_action import TimerAction
+from launch.event_handlers.on_process_io import OnProcessIO
from launch.event_handlers.on_process_start import OnProcessStart
+from launch.events.process import ProcessIO
from launch.events.shutdown import Shutdown as ShutdownEvent
from launch.substitutions.launch_configuration import LaunchConfiguration
@@ -318,3 +321,129 @@ def test_execute_process_prefix_filter_override_in_launch_file():
test_process.execute(lc)
assert 'echo' in test_process.process_details['cmd'] and \
'time' not in test_process.process_details['cmd']
+
+
+preamble = [sys.executable, os.path.join(os.path.dirname(__file__), 'argv_echo.py')]
+
+
+@pytest.mark.parametrize('test_parameters', [
+ # This case will result in 2 arguments, keeping the --some-arg and "some string" together.
+ {
+ 'cmd': preamble + ['--some-arg "some string"'],
+ 'shell': False,
+ 'split_arguments': False,
+ 'expected_number_of_args': 2,
+ },
+ # This case will split the --some-arg and "some string" up, resulting in 3 args.
+ {
+ 'cmd': preamble + ['--some-arg "some string"'],
+ 'shell': False,
+ 'split_arguments': True,
+ 'expected_number_of_args': 3,
+ },
+ # This case the split_arguments is ignored, due to shell=True,
+ # and produces again 3 arguments, not 4.
+ {
+ 'cmd': preamble + ['--some-arg "some string"'],
+ 'shell': True,
+ 'split_arguments': True,
+ 'expected_number_of_args': 3,
+ },
+ # This is the "normal" shell=True behavior.
+ {
+ 'cmd': preamble + ['--some-arg "some string"'],
+ 'shell': True,
+ 'split_arguments': False,
+ 'expected_number_of_args': 3,
+ },
+ # Test single argument for cmd (still a list), which will require shell=True.
+ {
+ 'cmd': [' '.join(preamble + ['--some-arg "some string"'])],
+ 'shell': True,
+ 'split_arguments': False,
+ 'expected_number_of_args': 3,
+ },
+ # This case also ignores split_arguments.
+ {
+ 'cmd': [' '.join(preamble + ['--some-arg "some string"'])],
+ 'shell': True,
+ 'split_arguments': True,
+ 'expected_number_of_args': 3,
+ },
+])
+def test_execute_process_split_arguments(test_parameters):
+ """Test the use of the split_arguments option."""
+ execute_process_action = ExecuteProcess(
+ cmd=test_parameters['cmd'],
+ output='screen',
+ shell=test_parameters['shell'],
+ split_arguments=test_parameters['split_arguments'],
+ )
+
+ ld = LaunchDescription([execute_process_action])
+ ls = LaunchService()
+ ls.include_launch_description(ld)
+ assert 0 == ls.run(shutdown_when_idle=True)
+ assert execute_process_action.return_code == test_parameters['expected_number_of_args'], \
+ execute_process_action.process_details['cmd']
+
+
+def test_execute_process_split_arguments_override_in_launch_file():
+ execute_process_args = {
+ 'cmd': preamble + ['--some-arg "some string"'],
+ 'output': 'screen',
+ 'shell': False,
+ 'log_cmd': True,
+ }
+ execute_process_action1 = ExecuteProcess(**execute_process_args)
+ execute_process_action2 = ExecuteProcess(**execute_process_args)
+
+ ld = LaunchDescription([
+ # Control to test the default.
+ execute_process_action1,
+ # Change default with LaunchConfiguration, test again.
+ SetLaunchConfiguration('split_arguments', 'True'),
+ execute_process_action2,
+ ])
+ ls = LaunchService()
+ ls.include_launch_description(ld)
+ assert 0 == ls.run(shutdown_when_idle=True)
+
+ assert execute_process_action1.return_code == 2, execute_process_action1.process_details['cmd']
+ assert execute_process_action2.return_code == 3, execute_process_action2.process_details['cmd']
+
+
+def test_execute_process_split_arguments_with_windows_like_pathsep():
+ # On POSIX platforms the `\` will be removed, but not on windows.
+ path = b'C:\\some\\path'
+ execute_process_args = {
+ 'cmd': preamble + [f'--some-arg {path.decode()}'],
+ 'output': 'screen',
+ 'shell': False,
+ 'split_arguments': True,
+ 'log_cmd': True,
+ }
+ execute_process_action1 = ExecuteProcess(**execute_process_args)
+
+ did_see_path = False
+
+ def on_stdout(event: ProcessIO):
+ nonlocal did_see_path
+ if event.from_stdout and path in event.text:
+ did_see_path = True
+
+ event_handler = OnProcessIO(
+ target_action=execute_process_action1,
+ on_stdout=on_stdout,
+ )
+
+ ld = LaunchDescription([
+ RegisterEventHandler(event_handler),
+ execute_process_action1,
+ ])
+ ls = LaunchService()
+ ls.include_launch_description(ld)
+ assert 0 == ls.run(shutdown_when_idle=True)
+
+ assert execute_process_action1.return_code == 3, execute_process_action1.process_details['cmd']
+ assert did_see_path == g_is_windows
diff --git a/launch_xml/test/launch_xml/arg_echo.py b/launch_xml/test/launch_xml/arg_echo.py
new file mode 100644
index 000000000..978e780b2
--- /dev/null
+++ b/launch_xml/test/launch_xml/arg_echo.py
@@ -0,0 +1,28 @@
+# 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.
+
+"""Used from test_executable.py and others."""
+
+
+import sys
+
+
+def print_argv(argv):
+ joined_args = "', '".join(argv)
+ print(f"['{joined_args}']")
+ sys.exit(len(argv))
+
+
+if __name__ == '__main__':
+ print_argv(sys.argv)
diff --git a/launch_xml/test/launch_xml/executable.xml b/launch_xml/test/launch_xml/executable.xml
deleted file mode 100644
index 3195dd1ad..000000000
--- a/launch_xml/test/launch_xml/executable.xml
+++ /dev/null
@@ -1,5 +0,0 @@
-
-
-
-
-
diff --git a/launch_xml/test/launch_xml/test_executable.py b/launch_xml/test/launch_xml/test_executable.py
index 878556ea3..73b638760 100644
--- a/launch_xml/test/launch_xml/test_executable.py
+++ b/launch_xml/test/launch_xml/test_executable.py
@@ -15,8 +15,8 @@
"""Test parsing an executable action."""
import io
-from pathlib import Path
-import textwrap
+import os
+import sys
from launch import LaunchService
from launch.actions import Shutdown
@@ -24,15 +24,27 @@
import pytest
+test_executable_xml = f"""
+
+
+
+
+
+"""
+
def test_executable():
"""Parse node xml example."""
- xml_file = str(Path(__file__).parent / 'executable.xml')
- root_entity, parser = Parser.load(xml_file)
+ root_entity, parser = Parser.load(io.StringIO(test_executable_xml))
ld = parser.parse_description(root_entity)
executable = ld.entities[0]
cmd = [i[0].perform(None) for i in executable.cmd]
- assert cmd == ['ls', '-l', '-a', '-s']
+ assert cmd == [sys.executable, '--version']
assert executable.cwd[0].perform(None) == '/'
assert executable.name[0].perform(None) == 'my_ls'
assert executable.shell is True
@@ -48,26 +60,49 @@ def test_executable():
ls = LaunchService()
ls.include_launch_description(ld)
assert 0 == ls.run()
+ assert executable.return_code == 0
+
+
+test_executable_wrong_subtag_xml = """
+
+
+
+
+
+
+"""
def test_executable_wrong_subtag():
- xml_file = \
- """\
-
-
-
-
-
-
- """ # noqa, line too long
- xml_file = textwrap.dedent(xml_file)
- root_entity, parser = Parser.load(io.StringIO(xml_file))
+ root_entity, parser = Parser.load(io.StringIO(test_executable_wrong_subtag_xml))
with pytest.raises(ValueError) as excinfo:
parser.parse_description(root_entity)
assert '`executable`' in str(excinfo.value)
assert 'whats_this' in str(excinfo.value)
+split_arguments_example1 = f"""
+
+
+
+
+"""
+
+
+def test_executable_with_split_arguments():
+ """Parse node xml example."""
+ root_entity, parser = Parser.load(io.StringIO(split_arguments_example1))
+ ld = parser.parse_description(root_entity)
+ ls = LaunchService()
+ ls.include_launch_description(ld)
+ assert 0 == ls.run()
+
+
def test_executable_on_exit():
xml_file = \
"""\
diff --git a/launch_yaml/test/launch_yaml/arg_echo.py b/launch_yaml/test/launch_yaml/arg_echo.py
new file mode 100644
index 000000000..978e780b2
--- /dev/null
+++ b/launch_yaml/test/launch_yaml/arg_echo.py
@@ -0,0 +1,28 @@
+# 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.
+
+"""Used from test_executable.py and others."""
+
+
+import sys
+
+
+def print_argv(argv):
+ joined_args = "', '".join(argv)
+ print(f"['{joined_args}']")
+ sys.exit(len(argv))
+
+
+if __name__ == '__main__':
+ print_argv(sys.argv)
diff --git a/launch_yaml/test/launch_yaml/test_executable.py b/launch_yaml/test/launch_yaml/test_executable.py
index a4e1a9bf2..f2048b8b0 100644
--- a/launch_yaml/test/launch_yaml/test_executable.py
+++ b/launch_yaml/test/launch_yaml/test_executable.py
@@ -15,6 +15,8 @@
"""Test parsing an executable action."""
import io
+import os
+import sys
import textwrap
from launch import LaunchService
@@ -82,5 +84,32 @@ def test_executable_on_exit():
assert isinstance(sub_entities[0], Shutdown)
+split_arguments_example1 = f"""
+launch:
+ - let:
+ name: args
+ value: '--some-arg "some string"'
+ - executable:
+ cmd: {sys.executable} {os.path.join(os.path.dirname(__file__), 'arg_echo.py')} $(var args)
+ log_cmd: True
+ shell: False
+ split_arguments: True
+ output: screen
+"""
+
+
+def test_executable_with_split_arguments():
+ """Parse node xml example."""
+ root_entity, parser = Parser.load(io.StringIO(split_arguments_example1))
+ ld = parser.parse_description(root_entity)
+ ls = LaunchService()
+ ls.include_launch_description(ld)
+ assert 0 == ls.run()
+
+ executable = ld.entities[-1]
+ # expect a return code that matches the number of arguments after the executable
+ assert executable.return_code == 3
+
+
if __name__ == '__main__':
test_executable()