diff --git a/examples/actions/py_server.py b/examples/actions/py_server.py index e2e10efb..cf176380 100644 --- a/examples/actions/py_server.py +++ b/examples/actions/py_server.py @@ -11,9 +11,14 @@ # 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. +import os +import sys import threading import time +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + +# ruff: noqa: E402 import rclpy from fibonacci_msgs.action import Fibonacci from rclpy.action import ActionServer diff --git a/examples/chatter/py_talker.py b/examples/chatter/py_talker.py index 4c9d1a9e..69c35e32 100644 --- a/examples/chatter/py_talker.py +++ b/examples/chatter/py_talker.py @@ -11,6 +11,12 @@ # 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. +import os +import sys + +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + +# ruff: noqa: E402 import rclpy from rclpy import node from std_msgs.msg import String diff --git a/repositories/class_loader.BUILD.bazel b/repositories/class_loader.BUILD.bazel index 7410f0b8..469a081f 100644 --- a/repositories/class_loader.BUILD.bazel +++ b/repositories/class_loader.BUILD.bazel @@ -3,24 +3,9 @@ load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library") -cc_binary( - name = "class_loader.so", - srcs = glob([ - "src/*.cpp", - "include/class_loader/*.hpp", - ]), - copts = ["-std=c++17"], - includes = ["include"], - linkshared = True, - deps = [ - "@console_bridge", - "@ros2_rcpputils//:rcpputils", - ], -) - cc_library( name = "class_loader", - srcs = ["class_loader.so"], + srcs = glob(["src/*.cpp"]), hdrs = glob(["include/class_loader/*.hpp"]), copts = ["-std=c++17"], includes = ["include"], diff --git a/repositories/patches/rmw_cyclonedds-fix-typesupport-conditions-bug.patch b/repositories/patches/rmw_cyclonedds-fix-typesupport-conditions-bug.patch deleted file mode 100644 index 993e665a..00000000 --- a/repositories/patches/rmw_cyclonedds-fix-typesupport-conditions-bug.patch +++ /dev/null @@ -1,27 +0,0 @@ -diff --git a/rmw_cyclonedds_cpp/src/serdata.cpp b/rmw_cyclonedds_cpp/src/serdata.cpp -index 05b3286..b3382cc 100644 ---- a/rmw_cyclonedds_cpp/src/serdata.cpp -+++ b/rmw_cyclonedds_cpp/src/serdata.cpp -@@ -60,14 +60,16 @@ using ResponseTypeSupport_cpp = rmw_cyclonedds_cpp::ResponseTypeSupport< - rosidl_typesupport_introspection_cpp::ServiceMembers, - rosidl_typesupport_introspection_cpp::MessageMembers>; - --static bool using_introspection_c_typesupport(const char * typesupport_identifier) --{ -- return typesupport_identifier == rosidl_typesupport_introspection_c__identifier; -+static bool using_introspection_c_typesupport( -+ const char* typesupport_identifier) { -+ return !std::string(typesupport_identifier) -+ .compare(rosidl_typesupport_introspection_c__identifier); - } - --static bool using_introspection_cpp_typesupport(const char * typesupport_identifier) --{ -- return typesupport_identifier == rosidl_typesupport_introspection_cpp::typesupport_identifier; -+static bool using_introspection_cpp_typesupport( -+ const char* typesupport_identifier) { -+ return !std::string(typesupport_identifier) -+ .compare(rosidl_typesupport_introspection_cpp::typesupport_identifier); - } - - void * create_message_type_support( diff --git a/repositories/ros2_repo_mappings.yaml b/repositories/ros2_repo_mappings.yaml index 22755fff..f6b09d23 100644 --- a/repositories/ros2_repo_mappings.yaml +++ b/repositories/ros2_repo_mappings.yaml @@ -90,9 +90,6 @@ repositories: rmw_cyclonedds: name: ros2_rmw_cyclonedds build_file: "@com_github_mvukov_rules_ros2//repositories:rmw_cyclonedds.BUILD.bazel" - patch_args: ["-p1"] - patches: - - "@com_github_mvukov_rules_ros2//repositories/patches:rmw_cyclonedds-fix-typesupport-conditions-bug.patch" rmw_dds_common: name: ros2_rmw_dds_common build_file: "@com_github_mvukov_rules_ros2//repositories:rmw_dds_common.BUILD.bazel" diff --git a/repositories/ros2_repositories_impl.bzl b/repositories/ros2_repositories_impl.bzl index d0fec188..18395fff 100644 --- a/repositories/ros2_repositories_impl.bzl +++ b/repositories/ros2_repositories_impl.bzl @@ -237,8 +237,6 @@ def ros2_repositories_impl(): http_archive, name = "ros2_rmw_cyclonedds", build_file = "@com_github_mvukov_rules_ros2//repositories:rmw_cyclonedds.BUILD.bazel", - patch_args = ["-p1"], - patches = ["@com_github_mvukov_rules_ros2//repositories/patches:rmw_cyclonedds-fix-typesupport-conditions-bug.patch"], sha256 = "58ef4fe3fd18eb723906df77eb10df1e69222b451e479c6ec85426ba48e16a8a", strip_prefix = "rmw_cyclonedds-1.3.4", url = "https://github.com/ros2/rmw_cyclonedds/archive/refs/tags/1.3.4.tar.gz", diff --git a/ros2/BUILD.bazel b/ros2/BUILD.bazel index 59a136f2..9e2c179f 100644 --- a/ros2/BUILD.bazel +++ b/ros2/BUILD.bazel @@ -10,6 +10,7 @@ exports_files([ "bag.bzl", "bag.py.tpl", "cc_defs.bzl", + "exported_symbols.lds", "interfaces.bzl", "launch.bzl", "launch.py.tpl", diff --git a/ros2/bag.py.tpl b/ros2/bag.py.tpl index ab8429b5..ca302589 100644 --- a/ros2/bag.py.tpl +++ b/ros2/bag.py.tpl @@ -1,6 +1,8 @@ import os import sys +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + import ros2.ros2_cmd import ros2bag.verb.convert import ros2bag.verb.info diff --git a/ros2/cc_defs.bzl b/ros2/cc_defs.bzl index 19921e86..adff7e19 100644 --- a/ros2/cc_defs.bzl +++ b/ros2/cc_defs.bzl @@ -14,6 +14,15 @@ def _ros2_cc_target(target, lang, name, ros2_package_name, **kwargs): fail("lang must be set to c or cpp!") all_copts = all_copts + kwargs.pop("copts", []) + # This solution requires Bazel 6.4.0. https://github.com/bazelbuild/bazel/issues/17788 + # all_linkopts = ["-Wl,--dynamic-list=$(location @com_github_mvukov_rules_ros2//ros2:exported_symbols.lds)"] + kwargs.pop("linkopts", []) + # kwargs["linkopts"] = all_linkopts + # all_additional_linker_inputs = ["@com_github_mvukov_rules_ros2//ros2:exported_symbols.lds"] + kwargs.pop("additional_linker_inputs", []) + # kwargs["additional_linker_inputs"] = all_additional_linker_inputs + + all_linkopts = ["-Wl,--export-dynamic"] + kwargs.pop("linkopts", []) + kwargs["linkopts"] = all_linkopts + ros2_package_name = ros2_package_name or name all_local_defines = ["ROS_PACKAGE_NAME=\\\"{}\\\"".format(ros2_package_name)] all_local_defines = all_local_defines + kwargs.pop("local_defines", []) diff --git a/ros2/exported_symbols.lds b/ros2/exported_symbols.lds new file mode 100644 index 00000000..d971731f --- /dev/null +++ b/ros2/exported_symbols.lds @@ -0,0 +1,5 @@ +{ + rosidl_typesupport_introspection_c__identifier; + *rosidl_typesupport_introspection_cpp*typesupport_identifier*; + *class_loader*impl*; +}; diff --git a/ros2/launch.py.tpl b/ros2/launch.py.tpl index e0161801..b1cd2da3 100644 --- a/ros2/launch.py.tpl +++ b/ros2/launch.py.tpl @@ -1,6 +1,8 @@ import os import sys +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + from ros2cli import cli from ros2launch.command import launch diff --git a/ros2/pytest_wrapper.py.tpl b/ros2/pytest_wrapper.py.tpl index 441a0958..22392a08 100644 --- a/ros2/pytest_wrapper.py.tpl +++ b/ros2/pytest_wrapper.py.tpl @@ -5,6 +5,8 @@ import os import pathlib import sys +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + import coverage import domain_coordinator import pytest diff --git a/ros2/ros2_lifecycle.py b/ros2/ros2_lifecycle.py index 58fb3b8a..c1896736 100644 --- a/ros2/ros2_lifecycle.py +++ b/ros2/ros2_lifecycle.py @@ -11,8 +11,12 @@ # 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. +import os import sys +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + +# ruff: noqa: E402 import ros2cli.cli import ros2lifecycle.verb.get import ros2lifecycle.verb.list diff --git a/ros2/ros2_node.py b/ros2/ros2_node.py index c172802e..cae580e2 100644 --- a/ros2/ros2_node.py +++ b/ros2/ros2_node.py @@ -11,8 +11,12 @@ # 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. +import os import sys +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + +# ruff: noqa: E402 import ros2cli.cli import ros2node.verb.info import ros2node.verb.list diff --git a/ros2/ros2_param.py b/ros2/ros2_param.py index c6379fdb..27c41179 100644 --- a/ros2/ros2_param.py +++ b/ros2/ros2_param.py @@ -11,8 +11,12 @@ # 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. +import os import sys +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + +# ruff: noqa: E402 import ros2cli.cli import ros2param.verb.delete import ros2param.verb.describe diff --git a/ros2/ros2_service.py b/ros2/ros2_service.py index c5a516ba..243af5ea 100644 --- a/ros2/ros2_service.py +++ b/ros2/ros2_service.py @@ -11,8 +11,12 @@ # 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. +import os import sys +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + +# ruff: noqa: E402 import ros2cli.cli import ros2service.verb.call import ros2service.verb.find diff --git a/ros2/ros2_topic.py b/ros2/ros2_topic.py index 1d4ae38d..316ba97c 100644 --- a/ros2/ros2_topic.py +++ b/ros2/ros2_topic.py @@ -11,8 +11,12 @@ # 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. +import os import sys +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + +# ruff: noqa: E402 import ros2cli.cli import ros2topic.verb.bw import ros2topic.verb.delay diff --git a/ros2/test.py.tpl b/ros2/test.py.tpl index cd6917e4..7ed8f60a 100644 --- a/ros2/test.py.tpl +++ b/ros2/test.py.tpl @@ -2,6 +2,8 @@ import contextlib import os import sys +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + import domain_coordinator import launch_testing.launch_test import launch_testing_ros diff --git a/ros2/test/pluginlib/py_loader_tests.py b/ros2/test/pluginlib/py_loader_tests.py index dd9c5018..49270b80 100644 --- a/ros2/test/pluginlib/py_loader_tests.py +++ b/ros2/test/pluginlib/py_loader_tests.py @@ -11,6 +11,11 @@ # 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. -from ros2.test.pluginlib import py_loader +import os +import sys + +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + +from ros2.test.pluginlib import py_loader # noqa: E402 py_loader.load_plugins() diff --git a/ros2/test/rosbag/write_to_bag_tests.py b/ros2/test/rosbag/write_to_bag_tests.py index 43cc0cab..aa6f40e7 100644 --- a/ros2/test/rosbag/write_to_bag_tests.py +++ b/ros2/test/rosbag/write_to_bag_tests.py @@ -11,8 +11,13 @@ # 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. +import os import pathlib +import sys +sys.setdlopenflags(os.RTLD_GLOBAL | os.RTLD_NOW) + +# ruff: noqa: E402 import pytest import rosbag2_py