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
3 changes: 2 additions & 1 deletion ros2/cc_defs.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ def _ros2_cpp_exec(target, name, ros2_package_name, set_up_ament, idl_deps, **kw
ament_setup_deps = ament_setup_deps,
template = "@com_github_mvukov_rules_ros2//ros2:launch_exec.sh.tpl",
substitutions = {
"{entry_point}": "$(rootpath {})".format(target_impl),
"{entry_point}": "$(rlocationpath {})".format(target_impl),
},
tags = ["manual"],
data = [target_impl],
Expand All @@ -100,6 +100,7 @@ def _ros2_cpp_exec(target, name, ros2_package_name, set_up_ament, idl_deps, **kw
name = name,
srcs = [launcher],
data = [target_impl],
use_bash_launcher = True,

Copy link
Copy Markdown
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this mean that we had a bug before?

**launcher_target_kwargs
)

Expand Down
3 changes: 2 additions & 1 deletion ros2/launch_exec.py.tpl
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
import os
import sys
from python.runfiles import runfiles

Copy link
Copy Markdown
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please insert an empty line above as this is an external dep.


env = os.environ.copy()

Expand All @@ -16,5 +17,5 @@ if not ament_prefix_path:
else:
env["AMENT_PREFIX_PATH"] = ament_prefix_path

entry_point = "{entry_point}"
entry_point = runfiles.Create().Rlocation("{entry_point}")
os.execve(entry_point, [entry_point, *sys.argv[1:]], env)
6 changes: 4 additions & 2 deletions ros2/launch_exec.sh.tpl
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,12 @@ if [ -n "${BAZEL_TEST:-}" ]; then
fi
fi

ENTRYPOINT="$(rlocation {entry_point})"

@mvukov mvukov May 25, 2026

Copy link
Copy Markdown
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Don't you have to depend on a target from rules_sh for this to work? I remember that earlier versions of rules_sh required copy/pasting of a snippet.


ament_prefix_path="{{ament_prefix_path}}"
if [ -z "${ament_prefix_path}" ]; then
unset AMENT_PREFIX_PATH
exec {entry_point} "$@"
exec ${ENTRYPOINT} "$@"
else
AMENT_PREFIX_PATH="${ament_prefix_path}" exec {entry_point} "$@"
AMENT_PREFIX_PATH="${ament_prefix_path}" exec ${ENTRYPOINT} "$@"
fi
3 changes: 2 additions & 1 deletion ros2/py_defs.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ def _ros2_py_exec(target, name, srcs, main, set_up_ament, testonly, **kwargs):
ament_setup_deps = ament_setup_deps,
template = "@com_github_mvukov_rules_ros2//ros2:launch_exec.py.tpl",
substitutions = {
"{entry_point}": "$(rootpath {})".format(target_impl_symlink),
"{entry_point}": "$(rlocationpath {})".format(target_impl_symlink),
},
tags = ["manual"],
data = [target_impl_symlink],
Expand All @@ -50,6 +50,7 @@ def _ros2_py_exec(target, name, srcs, main, set_up_ament, testonly, **kwargs):
srcs = [launcher],
main = launcher + ".py",
data = [target_impl_symlink],
deps = ["@rules_python//python/runfiles"],
**launcher_target_kwargs
)

Expand Down
3 changes: 2 additions & 1 deletion ros2/rust_defs.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ def ros2_rust_test(name, **kwargs):
name = launcher,
template = "@com_github_mvukov_rules_ros2//ros2:launch_exec.sh.tpl",
substitutions = {
"{entry_point}": "$(rootpath {})".format(target_impl),
"{entry_point}": "$(rlocationpath {})".format(target_impl),
},
tags = ["manual"],
data = [target_impl],
Expand All @@ -43,5 +43,6 @@ def ros2_rust_test(name, **kwargs):
name = name,
srcs = [launcher],
data = [target_impl],
use_bash_launcher = True,
**launcher_target_kwargs
)
Loading