From efd4c99edd9cfab1ac375311a4fdb3ba7f2d7304 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sat, 28 Dec 2024 11:16:08 +0100 Subject: [PATCH 1/5] Move test_utils module from demos repo (#1955) --- .../controller_manager/test_utils.py | 129 ++++++++++++++++++ controller_manager/package.xml | 8 +- .../test/test_ros2_control_node.yaml | 5 +- .../test/test_ros2_control_node_launch.py | 89 +++++++++--- doc/release_notes.rst | 1 + ros2_control_test_assets/CMakeLists.txt | 4 + .../urdf}/test_hardware_components.urdf | 36 +---- 7 files changed, 215 insertions(+), 57 deletions(-) create mode 100644 controller_manager/controller_manager/test_utils.py rename {hardware_interface/test/test_hardware_components => ros2_control_test_assets/urdf}/test_hardware_components.urdf (65%) diff --git a/controller_manager/controller_manager/test_utils.py b/controller_manager/controller_manager/test_utils.py new file mode 100644 index 0000000000..8fb4ef8d97 --- /dev/null +++ b/controller_manager/controller_manager/test_utils.py @@ -0,0 +1,129 @@ +# Copyright (c) 2024 AIT - Austrian Institute of Technology GmbH +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the {copyright_holder} nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Christoph Froehlich + +import time + +from launch_testing_ros import WaitForTopics +from sensor_msgs.msg import JointState +from controller_manager.controller_manager_services import list_controllers + + +def check_node_running(node, node_name, timeout=5.0): + + start = time.time() + found = False + while time.time() - start < timeout and not found: + found = node_name in node.get_node_names() + time.sleep(0.1) + assert found, f"{node_name} not found!" + + +def check_controllers_running(node, cnames, namespace="", state="active"): + """ + Check if the specified controllers are running on the given node. + + Args: + node (Node): The ROS2 node instance to check for controllers. + cnames (list of str): List of controller names to check. + namespace (str, optional): The namespace in which to look for controllers. Defaults to "". + state (str, optional): The desired state of the controllers. Defaults to "active". + + Raises: + AssertionError: If any of the specified controllers are not found or not in the desired state within the timeout period. + """ + + # wait for controller to be loaded before we call the CM services + found = {cname: False for cname in cnames} # Define 'found' as a dictionary + start = time.time() + # namespace is either "/" (empty) or "/ns" if set + if namespace: + namespace_api = namespace + if not namespace_api.startswith("/"): + namespace_api = "/" + namespace_api + if namespace.endswith("/"): + namespace_api = namespace_api[:-1] + else: + namespace_api = "/" + + while time.time() - start < 10.0 and not all(found.values()): + node_names_namespaces = node.get_node_names_and_namespaces() + for cname in cnames: + if any(name == cname and ns == namespace_api for name, ns in node_names_namespaces): + found[cname] = True + time.sleep(0.1) + assert all( + found.values() + ), f"Controller node(s) not found: {', '.join(['ns: ' + namespace_api + ', ctrl:' + cname for cname, is_found in found.items() if not is_found])}, but seeing {node.get_node_names_and_namespaces()}" + + found = {cname: False for cname in cnames} # Define 'found' as a dictionary + start = time.time() + # namespace is either "/" (empty) or "/ns" if set + if not namespace: + cm = "controller_manager" + else: + if namespace.endswith("/"): + cm = namespace + "controller_manager" + else: + cm = namespace + "/controller_manager" + while time.time() - start < 10.0 and not all(found.values()): + controllers = list_controllers(node, cm, 5.0).controller + assert controllers, "No controllers found!" + for c in controllers: + for cname in cnames: + if c.name == cname and c.state == state: + found[cname] = True + break + time.sleep(0.1) + + assert all( + found.values() + ), f"Controller(s) not found or not {state}: {', '.join([cname for cname, is_found in found.items() if not is_found])}" + + +def check_if_js_published(topic, joint_names): + """ + Check if a JointState message is published on a given topic with the expected joint names. + + Args: + topic (str): The name of the topic to check. + joint_names (list of str): The expected joint names in the JointState message. + + Raises: + AssertionError: If the topic is not found, the number of joints in the message is incorrect, + or the joint names do not match the expected names. + """ + wait_for_topics = WaitForTopics([(topic, JointState)], timeout=20.0) + assert wait_for_topics.wait(), f"Topic '{topic}' not found!" + msgs = wait_for_topics.received_messages(topic) + msg = msgs[0] + assert len(msg.name) == len(joint_names), "Wrong number of joints in message" + # use a set to compare the joint names, as the order might be different + assert set(msg.name) == set(joint_names), "Wrong joint names" + wait_for_topics.shutdown() diff --git a/controller_manager/package.xml b/controller_manager/package.xml index b23ca17d4b..f917922fd3 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -33,9 +33,15 @@ ament_cmake_gmock ament_cmake_pytest - python3-coverage hardware_interface_testing + launch_testing_ros + launch_testing + launch + python3-coverage + rclpy + robot_state_publisher ros2_control_test_assets + sensor_msgs example_interfaces diff --git a/controller_manager/test/test_ros2_control_node.yaml b/controller_manager/test/test_ros2_control_node.yaml index ce0602d6b3..74f6cf8504 100644 --- a/controller_manager/test/test_ros2_control_node.yaml +++ b/controller_manager/test/test_ros2_control_node.yaml @@ -5,7 +5,4 @@ controller_manager: ctrl_with_parameters_and_type: ros__parameters: type: "controller_manager/test_controller" - joint_names: ["joint0"] - -joint_state_broadcaster: - type: joint_state_broadcaster/JointStateBroadcaster + joint_names: ["joint1"] diff --git a/controller_manager/test/test_ros2_control_node_launch.py b/controller_manager/test/test_ros2_control_node_launch.py index c8c1136849..b382d3b09d 100644 --- a/controller_manager/test/test_ros2_control_node_launch.py +++ b/controller_manager/test/test_ros2_control_node_launch.py @@ -30,29 +30,31 @@ import pytest import unittest -import time +import os +from ament_index_python.packages import get_package_share_directory, get_package_prefix from launch import LaunchDescription -from launch.substitutions import PathJoinSubstitution -from launch_ros.substitutions import FindPackageShare from launch_testing.actions import ReadyToTest - import launch_testing.markers -import rclpy import launch_ros.actions -from rclpy.node import Node +from sensor_msgs.msg import JointState + +import rclpy +from controller_manager.test_utils import ( + check_controllers_running, + check_if_js_published, + check_node_running, +) +from controller_manager.launch_utils import generate_controllers_spawner_launch_description +import threading # Executes the given launch file and checks if all nodes can be started @pytest.mark.launch_test def generate_test_description(): - robot_controllers = PathJoinSubstitution( - [ - FindPackageShare("controller_manager"), - "test", - "test_ros2_control_node.yaml", - ] + robot_controllers = os.path.join( + get_package_prefix("controller_manager"), "test", "test_ros2_control_node.yaml" ) control_node = launch_ros.actions.Node( @@ -61,29 +63,72 @@ def generate_test_description(): parameters=[robot_controllers], output="both", ) + # Get URDF, without involving xacro + urdf = os.path.join( + get_package_share_directory("ros2_control_test_assets"), + "urdf", + "test_hardware_components.urdf", + ) + with open(urdf) as infp: + robot_description_content = infp.read() + robot_description = {"robot_description": robot_description_content} - return LaunchDescription([control_node, ReadyToTest()]) + robot_state_pub_node = launch_ros.actions.Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + ) + ctrl_spawner = generate_controllers_spawner_launch_description( + [ + "ctrl_with_parameters_and_type", + ], + controller_params_files=[robot_controllers], + ) + return LaunchDescription([robot_state_pub_node, control_node, ctrl_spawner, ReadyToTest()]) # This is our test fixture. Each method is a test case. # These run alongside the processes specified in generate_test_description() class TestFixture(unittest.TestCase): + @classmethod + def setUpClass(cls): + rclpy.init() + + @classmethod + def tearDownClass(cls): + rclpy.shutdown() def setUp(self): - rclpy.init() - self.node = Node("test_node") + self.node = rclpy.create_node("test_node") def tearDown(self): self.node.destroy_node() - rclpy.shutdown() + + def timer_callback(self): + js_msg = JointState() + js_msg.name = ["joint0"] + js_msg.position = [0.0] + self.pub.publish(js_msg) + + def publish_joint_states(self): + self.pub = self.node.create_publisher(JointState, "/joint_states", 10) + self.timer = self.node.create_timer(1.0, self.timer_callback) + rclpy.spin(self.node) def test_node_start(self): - start = time.time() - found = False - while time.time() - start < 2.0 and not found: - found = "controller_manager" in self.node.get_node_names() - time.sleep(0.1) - assert found, "controller_manager not found!" + check_node_running(self.node, "controller_manager") + + def test_controllers_start(self): + cnames = ["ctrl_with_parameters_and_type"] + check_controllers_running(self.node, cnames, state="active") + + def test_check_if_msgs_published(self): + # we don't have a joint_state_broadcaster in this repo, + # publish joint states manually to test check_if_js_published + thread = threading.Thread(target=self.publish_joint_states) + thread.start() + check_if_js_published("/joint_states", ["joint0"]) @launch_testing.post_shutdown_test() diff --git a/doc/release_notes.rst b/doc/release_notes.rst index 69c282b051..58930ec6c4 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -85,6 +85,7 @@ controller_manager * The ``ros2_control_node`` node has a new ``cpu_affinity`` parameter to bind the process to a specific CPU core. By default, this is not enabled. (`#1852 `_). * The ``--service-call-timeout`` was added as parameter to the helper scripts ``spawner.py``. Useful when the CPU load is high at startup and the service call does not return immediately (`#1808 `_). * The ``cpu_affinity`` parameter can now accept of types ``int`` or ``int_array`` to bind the process to a specific CPU core or multiple CPU cores. (`#1915 `_). +* A python module ``test_utils`` was added to the ``controller_manager`` package to help with integration testing (`#1955 `_). hardware_interface ****************** diff --git a/ros2_control_test_assets/CMakeLists.txt b/ros2_control_test_assets/CMakeLists.txt index d1bb895eed..d63fb52c86 100644 --- a/ros2_control_test_assets/CMakeLists.txt +++ b/ros2_control_test_assets/CMakeLists.txt @@ -14,6 +14,10 @@ install( DIRECTORY include/ DESTINATION include/ros2_control_test_assets ) +install( + FILES urdf/test_hardware_components.urdf + DESTINATION share/ros2_control_test_assets/urdf +) install(TARGETS ros2_control_test_assets EXPORT export_ros2_control_test_assets ARCHIVE DESTINATION lib diff --git a/hardware_interface/test/test_hardware_components/test_hardware_components.urdf b/ros2_control_test_assets/urdf/test_hardware_components.urdf similarity index 65% rename from hardware_interface/test/test_hardware_components/test_hardware_components.urdf rename to ros2_control_test_assets/urdf/test_hardware_components.urdf index e61b2d1c4c..c49c79bf55 100644 --- a/hardware_interface/test/test_hardware_components/test_hardware_components.urdf +++ b/ros2_control_test_assets/urdf/test_hardware_components.urdf @@ -1,5 +1,6 @@ + @@ -46,18 +47,11 @@ - - - test_robot_hardware/TestSingleJointActuator - - - - - - + + - test_robot_hardware/TestForceTorqueSensor + test_hardware_components/TestForceTorqueSensor @@ -68,36 +62,18 @@ + - test_robot_hardware/TestTwoJointSystem - - - - - - - - - - - - - test_robot_hardware/TestSystemCommandModes + test_hardware_components/TestTwoJointSystem - - - - - - From 283f6c67dfa31564646da17d2cb746b929f9a6af Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Sun, 29 Dec 2024 17:58:25 +0000 Subject: [PATCH 2/5] Remove boilerplate visibility macros (#1972) --- controller_interface/CMakeLists.txt | 7 +-- ...terface_configure_controller_library.cmake | 46 ----------------- .../chainable_controller_interface.hpp | 9 ---- .../controller_interface.hpp | 8 --- .../controller_interface_base.hpp | 25 ---------- .../controller_interface/visibility_control.h | 49 ------------------- controller_manager/CMakeLists.txt | 12 ++--- .../controller_manager/controller_manager.hpp | 38 +------------- .../controller_manager/visibility_control.h | 49 ------------------- .../test_chainable_controller.hpp | 15 ------ .../test/test_controller/test_controller.hpp | 10 ---- .../test_controller_failed_init.hpp | 5 -- .../test_controller_with_interfaces.hpp | 7 --- hardware_interface/CMakeLists.txt | 10 ++-- .../include/hardware_interface/actuator.hpp | 22 --------- .../hardware_interface/component_parser.hpp | 6 --- .../hardware_interface/lexical_casts.hpp | 4 -- .../hardware_interface/resource_manager.hpp | 2 +- .../include/hardware_interface/sensor.hpp | 18 ------- .../include/hardware_interface/system.hpp | 22 --------- .../hardware_interface/visibility_control.h | 49 ------------------- .../mock_components/generic_system.hpp | 3 +- .../mock_components/visibility_control.h | 49 ------------------- joint_limits/CMakeLists.txt | 11 ++--- .../joint_limits/joint_limiter_interface.hpp | 26 +++++----- .../joint_limits/joint_saturation_limiter.hpp | 12 ++--- .../include/joint_limits/visibility_control.h | 49 ------------------- transmission_interface/CMakeLists.txt | 4 ++ .../visibility_control.h | 49 ------------------- 29 files changed, 41 insertions(+), 575 deletions(-) delete mode 100644 controller_interface/cmake/controller_interface_configure_controller_library.cmake delete mode 100644 controller_interface/include/controller_interface/visibility_control.h delete mode 100644 controller_manager/include/controller_manager/visibility_control.h delete mode 100644 hardware_interface/include/hardware_interface/visibility_control.h delete mode 100644 hardware_interface/include/mock_components/visibility_control.h delete mode 100644 joint_limits/include/joint_limits/visibility_control.h delete mode 100644 transmission_interface/include/transmission_interface/visibility_control.h diff --git a/controller_interface/CMakeLists.txt b/controller_interface/CMakeLists.txt index 85294c68d1..60b213cd57 100644 --- a/controller_interface/CMakeLists.txt +++ b/controller_interface/CMakeLists.txt @@ -6,6 +6,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") -Werror=missing-braces) endif() +# using this instead of visibility macros +# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + set(THIS_PACKAGE_INCLUDE_DEPENDS hardware_interface rclcpp_lifecycle @@ -29,9 +33,6 @@ target_include_directories(controller_interface PUBLIC $ ) ament_target_dependencies(controller_interface PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) -# Causes the visibility macros to use dllexport rather than dllimport, -# which is appropriate when building the dll but not consuming it. -target_compile_definitions(controller_interface PRIVATE "CONTROLLER_INTERFACE_BUILDING_DLL") if(BUILD_TESTING) find_package(ament_cmake_gmock REQUIRED) diff --git a/controller_interface/cmake/controller_interface_configure_controller_library.cmake b/controller_interface/cmake/controller_interface_configure_controller_library.cmake deleted file mode 100644 index b154202329..0000000000 --- a/controller_interface/cmake/controller_interface_configure_controller_library.cmake +++ /dev/null @@ -1,46 +0,0 @@ -# Copyright 2017 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. - -# -# Configures a controller library which implements the controller_interface. -# -# This should be called on any library which is built to implement the rmw API. -# The custom settings are all related to library symbol visibility, see: -# -# https://gcc.gnu.org/wiki/Visibility -# http://www.ibm.com/developerworks/aix/library/au-aix-symbol-visibility/ -# -# Thought about using: -# -# http://www.cmake.org/cmake/help/v2.8.8/cmake.html#module:GenerateExportHeader -# -# But it doesn't seem to set the compiler flags correctly on clang and -# also doesn't work very well when the headers and library are in -# different projects like this. -# -# Effectively, using this macro results in the -# CONTROLLER_INTERFACE_BUILDING_DLL definition -# being set on Windows, and the -fvisibility* flags being passed to gcc and -# clang. -# -# @public -# -macro(controller_interface_configure_controller_library library_target) - if(WIN32) - # Causes the visibility macros to use dllexport rather than dllimport - # which is appropriate when building the dll but not consuming it. - target_compile_definitions(${library_target} - PRIVATE "CONTROLLER_INTERFACE_BUILDING_DLL") - endif() -endmacro() diff --git a/controller_interface/include/controller_interface/chainable_controller_interface.hpp b/controller_interface/include/controller_interface/chainable_controller_interface.hpp index 6775724bfa..52aa47d0fd 100644 --- a/controller_interface/include/controller_interface/chainable_controller_interface.hpp +++ b/controller_interface/include/controller_interface/chainable_controller_interface.hpp @@ -21,7 +21,6 @@ #include #include "controller_interface/controller_interface_base.hpp" -#include "controller_interface/visibility_control.h" #include "hardware_interface/handle.hpp" namespace controller_interface @@ -37,10 +36,8 @@ namespace controller_interface class ChainableControllerInterface : public ControllerInterfaceBase { public: - CONTROLLER_INTERFACE_PUBLIC ChainableControllerInterface(); - CONTROLLER_INTERFACE_PUBLIC virtual ~ChainableControllerInterface() = default; /** @@ -52,22 +49,16 @@ class ChainableControllerInterface : public ControllerInterfaceBase * \param[in] period The measured time taken by the last control loop iteration * \returns return_type::OK if update is successfully, otherwise return_type::ERROR. */ - CONTROLLER_INTERFACE_PUBLIC return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) final; - CONTROLLER_INTERFACE_PUBLIC bool is_chainable() const final; - CONTROLLER_INTERFACE_PUBLIC std::vector export_state_interfaces() final; - CONTROLLER_INTERFACE_PUBLIC std::vector export_reference_interfaces() final; - CONTROLLER_INTERFACE_PUBLIC bool set_chained_mode(bool chained_mode) final; - CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode() const final; protected: diff --git a/controller_interface/include/controller_interface/controller_interface.hpp b/controller_interface/include/controller_interface/controller_interface.hpp index 3455227e1d..a6158ea6b3 100644 --- a/controller_interface/include/controller_interface/controller_interface.hpp +++ b/controller_interface/include/controller_interface/controller_interface.hpp @@ -19,7 +19,6 @@ #include #include "controller_interface/controller_interface_base.hpp" -#include "controller_interface/visibility_control.h" #include "hardware_interface/handle.hpp" namespace controller_interface @@ -27,10 +26,8 @@ namespace controller_interface class ControllerInterface : public controller_interface::ControllerInterfaceBase { public: - CONTROLLER_INTERFACE_PUBLIC ControllerInterface(); - CONTROLLER_INTERFACE_PUBLIC virtual ~ControllerInterface() = default; /** @@ -38,7 +35,6 @@ class ControllerInterface : public controller_interface::ControllerInterfaceBase * * \returns false. */ - CONTROLLER_INTERFACE_PUBLIC bool is_chainable() const final; /** @@ -46,7 +42,6 @@ class ControllerInterface : public controller_interface::ControllerInterfaceBase * * \returns empty list. */ - CONTROLLER_INTERFACE_PUBLIC std::vector export_state_interfaces() final; /** @@ -54,7 +49,6 @@ class ControllerInterface : public controller_interface::ControllerInterfaceBase * * \returns empty list. */ - CONTROLLER_INTERFACE_PUBLIC std::vector export_reference_interfaces() final; /** @@ -62,7 +56,6 @@ class ControllerInterface : public controller_interface::ControllerInterfaceBase * * \returns false. */ - CONTROLLER_INTERFACE_PUBLIC bool set_chained_mode(bool chained_mode) final; /** @@ -70,7 +63,6 @@ class ControllerInterface : public controller_interface::ControllerInterfaceBase * * \returns false. */ - CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode() const final; }; diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index b47027bb31..9dee4528a3 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -20,7 +20,6 @@ #include #include -#include "controller_interface/visibility_control.h" #include "realtime_tools/async_function_handler.hpp" #include "hardware_interface/handle.hpp" @@ -98,10 +97,8 @@ struct ControllerUpdateStatus class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface { public: - CONTROLLER_INTERFACE_PUBLIC ControllerInterfaceBase() = default; - CONTROLLER_INTERFACE_PUBLIC virtual ~ControllerInterfaceBase() = default; /// Get configuration for controller's required command interfaces. @@ -116,7 +113,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * * \returns configuration of command interfaces. */ - CONTROLLER_INTERFACE_PUBLIC virtual InterfaceConfiguration command_interface_configuration() const = 0; /// Get configuration for controller's required state interfaces. @@ -133,7 +129,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * * \returns configuration of state interfaces. */ - CONTROLLER_INTERFACE_PUBLIC virtual InterfaceConfiguration state_interface_configuration() const = 0; /// Method that assigns the Loaned interfaces to the controller. @@ -145,7 +140,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * \param[in] command_interfaces vector of command interfaces to be assigned to the controller. * \param[in] state_interfaces vector of state interfaces to be assigned to the controller. */ - CONTROLLER_INTERFACE_PUBLIC virtual void assign_interfaces( std::vector && command_interfaces, std::vector && state_interfaces); @@ -154,10 +148,8 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy /** * Method used by the controller_manager to release the interfaces from the controller. */ - CONTROLLER_INTERFACE_PUBLIC virtual void release_interfaces(); - CONTROLLER_INTERFACE_PUBLIC return_type init( const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate, const std::string & node_namespace, const rclcpp::NodeOptions & node_options); @@ -166,11 +158,9 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy /* * Override default implementation for configure of LifecycleNode to get parameters. */ - CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure(); /// Extending interface with initialization method which is individual for each controller - CONTROLLER_INTERFACE_PUBLIC virtual CallbackReturn on_init() = 0; /** @@ -182,7 +172,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * \param[in] period The measured time since the last control loop iteration * \returns return_type::OK if update is successfully, otherwise return_type::ERROR. */ - CONTROLLER_INTERFACE_PUBLIC virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0; /** @@ -197,25 +186,18 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * \returns ControllerUpdateStatus. The status contains information if the update was triggered * successfully, the result of the update method and the execution duration of the update method. */ - CONTROLLER_INTERFACE_PUBLIC ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period); - CONTROLLER_INTERFACE_PUBLIC std::shared_ptr get_node(); - CONTROLLER_INTERFACE_PUBLIC std::shared_ptr get_node() const; - CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state() const; - CONTROLLER_INTERFACE_PUBLIC unsigned int get_update_rate() const; - CONTROLLER_INTERFACE_PUBLIC bool is_async() const; - CONTROLLER_INTERFACE_PUBLIC const std::string & get_robot_description() const; /** @@ -229,7 +211,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * * @returns NodeOptions required for the configuration of the controller lifecycle node */ - CONTROLLER_INTERFACE_PUBLIC virtual rclcpp::NodeOptions define_custom_node_options() const { rclcpp::NodeOptions node_options; @@ -272,7 +253,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * * \returns true is controller is chainable and false if it is not. */ - CONTROLLER_INTERFACE_PUBLIC virtual bool is_chainable() const = 0; /** @@ -281,7 +261,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * * \returns list of command interfaces for preceding controllers. */ - CONTROLLER_INTERFACE_PUBLIC virtual std::vector export_reference_interfaces() = 0; @@ -291,7 +270,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * * \returns list of state interfaces for preceding controllers. */ - CONTROLLER_INTERFACE_PUBLIC virtual std::vector export_state_interfaces() = 0; @@ -303,7 +281,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * * \returns true if mode is switched successfully and false if not. */ - CONTROLLER_INTERFACE_PUBLIC virtual bool set_chained_mode(bool chained_mode) = 0; /// Get information if a controller is currently in chained mode. @@ -314,7 +291,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * * \returns true is controller is in chained mode and false if it is not. */ - CONTROLLER_INTERFACE_PUBLIC virtual bool is_in_chained_mode() const = 0; /** @@ -327,7 +303,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * If the controller is running in async mode, the method will wait for the current async update * to finish. If the controller is not running in async mode, the method will do nothing. */ - CONTROLLER_INTERFACE_PUBLIC void wait_for_trigger_update_to_finish(); protected: diff --git a/controller_interface/include/controller_interface/visibility_control.h b/controller_interface/include/controller_interface/visibility_control.h deleted file mode 100644 index 478fa7e320..0000000000 --- a/controller_interface/include/controller_interface/visibility_control.h +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright 2017 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. - -#ifndef CONTROLLER_INTERFACE__VISIBILITY_CONTROL_H_ -#define CONTROLLER_INTERFACE__VISIBILITY_CONTROL_H_ - -// This logic was borrowed (then namespaced) from the examples on the gcc wiki: -// https://gcc.gnu.org/wiki/Visibility - -#if defined _WIN32 || defined __CYGWIN__ -#ifdef __GNUC__ -#define CONTROLLER_INTERFACE_EXPORT __attribute__((dllexport)) -#define CONTROLLER_INTERFACE_IMPORT __attribute__((dllimport)) -#else -#define CONTROLLER_INTERFACE_EXPORT __declspec(dllexport) -#define CONTROLLER_INTERFACE_IMPORT __declspec(dllimport) -#endif -#ifdef CONTROLLER_INTERFACE_BUILDING_DLL -#define CONTROLLER_INTERFACE_PUBLIC CONTROLLER_INTERFACE_EXPORT -#else -#define CONTROLLER_INTERFACE_PUBLIC CONTROLLER_INTERFACE_IMPORT -#endif -#define CONTROLLER_INTERFACE_PUBLIC_TYPE CONTROLLER_INTERFACE_PUBLIC -#define CONTROLLER_INTERFACE_LOCAL -#else -#define CONTROLLER_INTERFACE_EXPORT __attribute__((visibility("default"))) -#define CONTROLLER_INTERFACE_IMPORT -#if __GNUC__ >= 4 -#define CONTROLLER_INTERFACE_PUBLIC __attribute__((visibility("default"))) -#define CONTROLLER_INTERFACE_LOCAL __attribute__((visibility("hidden"))) -#else -#define CONTROLLER_INTERFACE_PUBLIC -#define CONTROLLER_INTERFACE_LOCAL -#endif -#define CONTROLLER_INTERFACE_PUBLIC_TYPE -#endif - -#endif // CONTROLLER_INTERFACE__VISIBILITY_CONTROL_H_ diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index 69f6ef24df..5d91604cec 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -6,6 +6,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") -Werror=missing-braces) endif() +# using this instead of visibility macros +# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + set(THIS_PACKAGE_INCLUDE_DEPENDS ament_index_cpp controller_interface @@ -46,10 +50,6 @@ target_link_libraries(controller_manager PUBLIC ) ament_target_dependencies(controller_manager PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) -# Causes the visibility macros to use dllexport rather than dllimport, -# which is appropriate when building the dll but not consuming it. -target_compile_definitions(controller_manager PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL") - add_executable(ros2_control_node src/ros2_control_node.cpp) target_link_libraries(ros2_control_node PRIVATE controller_manager @@ -64,7 +64,6 @@ if(BUILD_TESTING) add_library(test_controller SHARED test/test_controller/test_controller.cpp) target_link_libraries(test_controller PUBLIC controller_manager) ament_target_dependencies(test_controller PUBLIC example_interfaces) - target_compile_definitions(test_controller PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL") pluginlib_export_plugin_description_file(controller_interface test/test_controller/test_controller.xml) install( TARGETS test_controller @@ -75,7 +74,6 @@ if(BUILD_TESTING) test/test_controller_failed_init/test_controller_failed_init.cpp ) target_link_libraries(test_controller_failed_init PUBLIC controller_manager) - target_compile_definitions(test_controller_failed_init PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL") pluginlib_export_plugin_description_file( controller_interface test/test_controller_failed_init/test_controller_failed_init.xml) install( @@ -88,7 +86,6 @@ if(BUILD_TESTING) ) ament_target_dependencies(test_chainable_controller PUBLIC realtime_tools) target_link_libraries(test_chainable_controller PUBLIC controller_manager) - target_compile_definitions(test_chainable_controller PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL") pluginlib_export_plugin_description_file( controller_interface test/test_chainable_controller/test_chainable_controller.xml) install( @@ -178,7 +175,6 @@ if(BUILD_TESTING) target_link_libraries(test_controller_with_interfaces PUBLIC controller_manager ) - target_compile_definitions(test_controller_with_interfaces PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL") pluginlib_export_plugin_description_file( controller_interface test/test_controller_with_interfaces/test_controller_with_interfaces.xml) install( diff --git a/controller_manager/include/controller_manager/controller_manager.hpp b/controller_manager/include/controller_manager/controller_manager.hpp index d33b167997..7acbe20166 100644 --- a/controller_manager/include/controller_manager/controller_manager.hpp +++ b/controller_manager/include/controller_manager/controller_manager.hpp @@ -27,7 +27,6 @@ #include "controller_interface/controller_interface_base.hpp" #include "controller_manager/controller_spec.hpp" -#include "controller_manager/visibility_control.h" #include "controller_manager_msgs/srv/configure_controller.hpp" #include "controller_manager_msgs/srv/list_controller_types.hpp" #include "controller_manager_msgs/srv/list_controllers.hpp" @@ -54,7 +53,7 @@ class ParamListener; class Params; using ControllersListIterator = std::vector::const_iterator; -CONTROLLER_MANAGER_PUBLIC rclcpp::NodeOptions get_cm_node_options(); +rclcpp::NodeOptions get_cm_node_options(); class ControllerManager : public rclcpp::Node { @@ -62,7 +61,6 @@ class ControllerManager : public rclcpp::Node static constexpr bool kWaitForAllResources = false; static constexpr auto kInfiniteTimeout = 0; - CONTROLLER_MANAGER_PUBLIC ControllerManager( std::unique_ptr resource_manager, std::shared_ptr executor, @@ -70,30 +68,24 @@ class ControllerManager : public rclcpp::Node const std::string & node_namespace = "", const rclcpp::NodeOptions & options = get_cm_node_options()); - CONTROLLER_MANAGER_PUBLIC ControllerManager( std::shared_ptr executor, const std::string & manager_node_name = "controller_manager", const std::string & node_namespace = "", const rclcpp::NodeOptions & options = get_cm_node_options()); - CONTROLLER_MANAGER_PUBLIC ControllerManager( std::shared_ptr executor, const std::string & urdf, bool activate_all_hw_components, const std::string & manager_node_name = "controller_manager", const std::string & node_namespace = "", const rclcpp::NodeOptions & options = get_cm_node_options()); - CONTROLLER_MANAGER_PUBLIC virtual ~ControllerManager() = default; - CONTROLLER_MANAGER_PUBLIC void robot_description_callback(const std_msgs::msg::String & msg); - CONTROLLER_MANAGER_PUBLIC void init_resource_manager(const std::string & robot_description); - CONTROLLER_MANAGER_PUBLIC controller_interface::ControllerInterfaceBaseSharedPtr load_controller( const std::string & controller_name, const std::string & controller_type); @@ -103,14 +95,11 @@ class ControllerManager : public rclcpp::Node * \return controller * \see Documentation in controller_manager_msgs/LoadController.srv */ - CONTROLLER_MANAGER_PUBLIC controller_interface::ControllerInterfaceBaseSharedPtr load_controller( const std::string & controller_name); - CONTROLLER_MANAGER_PUBLIC controller_interface::return_type unload_controller(const std::string & controller_name); - CONTROLLER_MANAGER_PUBLIC std::vector get_loaded_controllers() const; template < @@ -141,7 +130,6 @@ class ControllerManager : public rclcpp::Node * \return configure controller response * \see Documentation in controller_manager_msgs/ConfigureController.srv */ - CONTROLLER_MANAGER_PUBLIC controller_interface::return_type configure_controller(const std::string & controller_name); /// switch_controller Deactivates some controllers and activates others. @@ -151,7 +139,6 @@ class ControllerManager : public rclcpp::Node * \param[in] set level of strictness (BEST_EFFORT or STRICT) * \see Documentation in controller_manager_msgs/SwitchController.srv */ - CONTROLLER_MANAGER_PUBLIC controller_interface::return_type switch_controller( const std::vector & activate_controllers, const std::vector & deactivate_controllers, int strictness, @@ -166,7 +153,6 @@ class ControllerManager : public rclcpp::Node * \param[in] time The time at the start of this control loop iteration * \param[in] period The measured period of the last control loop iteration */ - CONTROLLER_MANAGER_PUBLIC void read(const rclcpp::Time & time, const rclcpp::Duration & period); /// Run update on controllers @@ -177,7 +163,6 @@ class ControllerManager : public rclcpp::Node * \param[in] time The time at the start of this control loop iteration * \param[in] period The measured period of the last control loop iteration */ - CONTROLLER_MANAGER_PUBLIC controller_interface::return_type update( const rclcpp::Time & time, const rclcpp::Duration & period); @@ -189,7 +174,6 @@ class ControllerManager : public rclcpp::Node * \param[in] time The time at the start of this control loop iteration * \param[in] period The measured period of the last control loop iteration */ - CONTROLLER_MANAGER_PUBLIC void write(const rclcpp::Time & time, const rclcpp::Duration & period); /// Deterministic (real-time safe) callback group, e.g., update function. @@ -206,7 +190,6 @@ class ControllerManager : public rclcpp::Node * Checks if components in Resource Manager are loaded and initialized. * \returns true if they are initialized, false otherwise. */ - CONTROLLER_MANAGER_PUBLIC bool is_resource_manager_initialized() const { return resource_manager_ && resource_manager_->are_components_initialized(); @@ -219,18 +202,14 @@ class ControllerManager : public rclcpp::Node * * \returns update rate of the controller manager. */ - CONTROLLER_MANAGER_PUBLIC unsigned int get_update_rate() const; protected: - CONTROLLER_MANAGER_PUBLIC void init_services(); - CONTROLLER_MANAGER_PUBLIC controller_interface::ControllerInterfaceBaseSharedPtr add_controller_impl( const ControllerSpec & controller); - CONTROLLER_MANAGER_PUBLIC void manage_switch(); /// Deactivate chosen controllers from real-time controller list. @@ -241,7 +220,6 @@ class ControllerManager : public rclcpp::Node * \param[in] rt_controller_list controllers in the real-time list. * \param[in] controllers_to_deactivate names of the controller that have to be deactivated. */ - CONTROLLER_MANAGER_PUBLIC void deactivate_controllers( const std::vector & rt_controller_list, const std::vector controllers_to_deactivate); @@ -254,7 +232,6 @@ class ControllerManager : public rclcpp::Node * \param[in] chained_mode_switch_list list of controller to switch chained mode. * \param[in] to_chained_mode flag if controller should be switched *to* or *from* chained mode. */ - CONTROLLER_MANAGER_PUBLIC void switch_chained_mode( const std::vector & chained_mode_switch_list, bool to_chained_mode); @@ -266,7 +243,6 @@ class ControllerManager : public rclcpp::Node * \param[in] rt_controller_list controllers in the real-time list. * \param[in] controllers_to_activate names of the controller that have to be activated. */ - CONTROLLER_MANAGER_PUBLIC void activate_controllers( const std::vector & rt_controller_list, const std::vector controllers_to_activate); @@ -282,57 +258,46 @@ class ControllerManager : public rclcpp::Node * \param[in] rt_controller_list controllers in the real-time list. * \param[in] controllers_to_activate names of the controller that have to be activated. */ - CONTROLLER_MANAGER_PUBLIC void activate_controllers_asap( const std::vector & rt_controller_list, const std::vector controllers_to_activate); - CONTROLLER_MANAGER_PUBLIC void list_controllers_srv_cb( const std::shared_ptr request, std::shared_ptr response); - CONTROLLER_MANAGER_PUBLIC void list_hardware_interfaces_srv_cb( const std::shared_ptr request, std::shared_ptr response); - CONTROLLER_MANAGER_PUBLIC void load_controller_service_cb( const std::shared_ptr request, std::shared_ptr response); - CONTROLLER_MANAGER_PUBLIC void configure_controller_service_cb( const std::shared_ptr request, std::shared_ptr response); - CONTROLLER_MANAGER_PUBLIC void reload_controller_libraries_service_cb( const std::shared_ptr request, std::shared_ptr response); - CONTROLLER_MANAGER_PUBLIC void switch_controller_service_cb( const std::shared_ptr request, std::shared_ptr response); - CONTROLLER_MANAGER_PUBLIC void unload_controller_service_cb( const std::shared_ptr request, std::shared_ptr response); - CONTROLLER_MANAGER_PUBLIC void list_controller_types_srv_cb( const std::shared_ptr request, std::shared_ptr response); - CONTROLLER_MANAGER_PUBLIC void list_hardware_components_srv_cb( const std::shared_ptr request, std::shared_ptr response); - CONTROLLER_MANAGER_PUBLIC void set_hardware_component_state_srv_cb( const std::shared_ptr request, std::shared_ptr response); @@ -426,7 +391,6 @@ class ControllerManager : public rclcpp::Node * \return return_type::OK if all fallback controllers are in the right state, otherwise * return_type::ERROR. */ - CONTROLLER_MANAGER_PUBLIC controller_interface::return_type check_fallback_controllers_state_pre_activation( const std::vector & controllers, const ControllersListIterator controller_it); diff --git a/controller_manager/include/controller_manager/visibility_control.h b/controller_manager/include/controller_manager/visibility_control.h deleted file mode 100644 index 5009b9cb33..0000000000 --- a/controller_manager/include/controller_manager/visibility_control.h +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright 2020 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. - -#ifndef CONTROLLER_MANAGER__VISIBILITY_CONTROL_H_ -#define CONTROLLER_MANAGER__VISIBILITY_CONTROL_H_ - -// This logic was borrowed (then namespaced) from the examples on the gcc wiki: -// https://gcc.gnu.org/wiki/Visibility - -#if defined _WIN32 || defined __CYGWIN__ -#ifdef __GNUC__ -#define CONTROLLER_MANAGER_EXPORT __attribute__((dllexport)) -#define CONTROLLER_MANAGER_IMPORT __attribute__((dllimport)) -#else -#define CONTROLLER_MANAGER_EXPORT __declspec(dllexport) -#define CONTROLLER_MANAGER_IMPORT __declspec(dllimport) -#endif -#ifdef CONTROLLER_MANAGER_BUILDING_DLL -#define CONTROLLER_MANAGER_PUBLIC CONTROLLER_MANAGER_EXPORT -#else -#define CONTROLLER_MANAGER_PUBLIC CONTROLLER_MANAGER_IMPORT -#endif -#define CONTROLLER_MANAGER_PUBLIC_TYPE CONTROLLER_MANAGER_PUBLIC -#define CONTROLLER_MANAGER_LOCAL -#else -#define CONTROLLER_MANAGER_EXPORT __attribute__((visibility("default"))) -#define CONTROLLER_MANAGER_IMPORT -#if __GNUC__ >= 4 -#define CONTROLLER_MANAGER_PUBLIC __attribute__((visibility("default"))) -#define CONTROLLER_MANAGER_LOCAL __attribute__((visibility("hidden"))) -#else -#define CONTROLLER_MANAGER_PUBLIC -#define CONTROLLER_MANAGER_LOCAL -#endif -#define CONTROLLER_MANAGER_PUBLIC_TYPE -#endif - -#endif // CONTROLLER_MANAGER__VISIBILITY_CONTROL_H_ diff --git a/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp b/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp index 018f78b457..aa6a313acd 100644 --- a/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp +++ b/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp @@ -20,7 +20,6 @@ #include #include "controller_interface/chainable_controller_interface.hpp" -#include "controller_manager/visibility_control.h" #include "rclcpp/subscription.hpp" #include "realtime_tools/realtime_buffer.hpp" #include "semantic_components/imu_sensor.hpp" @@ -40,32 +39,24 @@ constexpr double CONTROLLER_DT = 0.001; class TestChainableController : public controller_interface::ChainableControllerInterface { public: - CONTROLLER_MANAGER_PUBLIC TestChainableController(); - CONTROLLER_MANAGER_PUBLIC virtual ~TestChainableController() = default; controller_interface::InterfaceConfiguration command_interface_configuration() const override; controller_interface::InterfaceConfiguration state_interface_configuration() const override; - CONTROLLER_MANAGER_PUBLIC CallbackReturn on_init() override; - CONTROLLER_MANAGER_PUBLIC CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override; - CONTROLLER_MANAGER_PUBLIC CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override; - CONTROLLER_MANAGER_PUBLIC CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override; - CONTROLLER_MANAGER_PUBLIC std::vector on_export_state_interfaces() override; - CONTROLLER_MANAGER_PUBLIC std::vector on_export_reference_interfaces() override; controller_interface::return_type update_reference_from_subscribers( @@ -75,23 +66,17 @@ class TestChainableController : public controller_interface::ChainableController const rclcpp::Time & time, const rclcpp::Duration & period) override; // Testing-relevant methods - CONTROLLER_MANAGER_PUBLIC void set_command_interface_configuration( const controller_interface::InterfaceConfiguration & cfg); - CONTROLLER_MANAGER_PUBLIC void set_state_interface_configuration(const controller_interface::InterfaceConfiguration & cfg); - CONTROLLER_MANAGER_PUBLIC void set_reference_interface_names(const std::vector & reference_interface_names); - CONTROLLER_MANAGER_PUBLIC void set_exported_state_interface_names(const std::vector & state_interface_names); - CONTROLLER_MANAGER_PUBLIC void set_imu_sensor_name(const std::string & name); - CONTROLLER_MANAGER_PUBLIC std::vector get_state_interface_data() const; size_t internal_counter; diff --git a/controller_manager/test/test_controller/test_controller.hpp b/controller_manager/test/test_controller/test_controller.hpp index ee9e668cfa..0728be877b 100644 --- a/controller_manager/test/test_controller/test_controller.hpp +++ b/controller_manager/test/test_controller/test_controller.hpp @@ -20,7 +20,6 @@ #include #include "controller_interface/controller_interface.hpp" -#include "controller_manager/visibility_control.h" #include "example_interfaces/srv/set_bool.hpp" #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" @@ -38,37 +37,28 @@ constexpr char TEST_CONTROLLER_CLASS_NAME[] = "controller_manager/test_controlle class TestController : public controller_interface::ControllerInterface { public: - CONTROLLER_MANAGER_PUBLIC TestController(); - CONTROLLER_MANAGER_PUBLIC virtual ~TestController() = default; controller_interface::InterfaceConfiguration command_interface_configuration() const override; controller_interface::InterfaceConfiguration state_interface_configuration() const override; - CONTROLLER_MANAGER_PUBLIC controller_interface::return_type update( const rclcpp::Time & time, const rclcpp::Duration & period) override; - CONTROLLER_MANAGER_PUBLIC CallbackReturn on_init() override; - CONTROLLER_MANAGER_PUBLIC CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override; - CONTROLLER_MANAGER_PUBLIC CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override; - CONTROLLER_MANAGER_PUBLIC void set_command_interface_configuration( const controller_interface::InterfaceConfiguration & cfg); - CONTROLLER_MANAGER_PUBLIC void set_state_interface_configuration(const controller_interface::InterfaceConfiguration & cfg); - CONTROLLER_MANAGER_PUBLIC std::vector get_state_interface_data() const; void set_external_commands_for_testing(const std::vector & commands); diff --git a/controller_manager/test/test_controller_failed_init/test_controller_failed_init.hpp b/controller_manager/test/test_controller_failed_init/test_controller_failed_init.hpp index bd17e0ead4..7f508ad24c 100644 --- a/controller_manager/test/test_controller_failed_init/test_controller_failed_init.hpp +++ b/controller_manager/test/test_controller_failed_init/test_controller_failed_init.hpp @@ -16,7 +16,6 @@ #define TEST_CONTROLLER_FAILED_INIT__TEST_CONTROLLER_FAILED_INIT_HPP_ #include "controller_interface/controller_interface.hpp" -#include "controller_manager/visibility_control.h" namespace test_controller_failed_init { @@ -29,10 +28,8 @@ constexpr char TEST_CONTROLLER_FAILED_INIT_CLASS_NAME[] = class TestControllerFailedInit : public controller_interface::ControllerInterface { public: - CONTROLLER_MANAGER_PUBLIC TestControllerFailedInit(); - CONTROLLER_MANAGER_PUBLIC virtual ~TestControllerFailedInit() = default; controller_interface::InterfaceConfiguration command_interface_configuration() const override @@ -54,11 +51,9 @@ class TestControllerFailedInit : public controller_interface::ControllerInterfac controller_interface::interface_configuration_type::NONE}; } - CONTROLLER_MANAGER_PUBLIC controller_interface::return_type update( const rclcpp::Time & time, const rclcpp::Duration & period) override; - CONTROLLER_MANAGER_PUBLIC rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_init() override; }; diff --git a/controller_manager/test/test_controller_with_interfaces/test_controller_with_interfaces.hpp b/controller_manager/test/test_controller_with_interfaces/test_controller_with_interfaces.hpp index ed083c17cb..751cb4f3a8 100644 --- a/controller_manager/test/test_controller_with_interfaces/test_controller_with_interfaces.hpp +++ b/controller_manager/test/test_controller_with_interfaces/test_controller_with_interfaces.hpp @@ -16,7 +16,6 @@ #define TEST_CONTROLLER_WITH_INTERFACES__TEST_CONTROLLER_WITH_INTERFACES_HPP_ #include "controller_interface/controller_interface.hpp" -#include "controller_manager/visibility_control.h" namespace test_controller_with_interfaces { @@ -28,10 +27,8 @@ constexpr char TEST_CONTROLLER_COMMAND_INTERFACE[] = "joint2/velocity"; class TestControllerWithInterfaces : public controller_interface::ControllerInterface { public: - CONTROLLER_MANAGER_PUBLIC TestControllerWithInterfaces(); - CONTROLLER_MANAGER_PUBLIC virtual ~TestControllerWithInterfaces() = default; controller_interface::InterfaceConfiguration command_interface_configuration() const override @@ -47,18 +44,14 @@ class TestControllerWithInterfaces : public controller_interface::ControllerInte controller_interface::interface_configuration_type::NONE}; } - CONTROLLER_MANAGER_PUBLIC controller_interface::return_type update( const rclcpp::Time & time, const rclcpp::Duration & period) override; - CONTROLLER_MANAGER_PUBLIC rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_init() override; - CONTROLLER_MANAGER_PUBLIC rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure( const rclcpp_lifecycle::State & previous_state) override; - CONTROLLER_MANAGER_PUBLIC rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup( const rclcpp_lifecycle::State & previous_state) override; }; diff --git a/hardware_interface/CMakeLists.txt b/hardware_interface/CMakeLists.txt index 4e3fe6a9ae..b4e0f6cab0 100644 --- a/hardware_interface/CMakeLists.txt +++ b/hardware_interface/CMakeLists.txt @@ -6,6 +6,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") -Werror=missing-braces) endif() +# using this instead of visibility macros +# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + set(THIS_PACKAGE_INCLUDE_DEPENDS control_msgs lifecycle_msgs @@ -41,9 +45,6 @@ target_include_directories(hardware_interface PUBLIC $ ) ament_target_dependencies(hardware_interface PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) -# Causes the visibility macros to use dllexport rather than dllimport, -# which is appropriate when building the dll but not consuming it. -target_compile_definitions(hardware_interface PRIVATE "HARDWARE_INTERFACE_BUILDING_DLL") add_library(mock_components SHARED src/mock_components/generic_system.cpp @@ -54,9 +55,6 @@ target_include_directories(mock_components PUBLIC $ ) ament_target_dependencies(mock_components PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) -# Causes the visibility macros to use dllexport rather than dllimport, -# which is appropriate when building the dll but not consuming it. -target_compile_definitions(mock_components PRIVATE "HARDWARE_INTERFACE_BUILDING_DLL") pluginlib_export_plugin_description_file( hardware_interface mock_components_plugin_description.xml) diff --git a/hardware_interface/include/hardware_interface/actuator.hpp b/hardware_interface/include/hardware_interface/actuator.hpp index bfeb5d969d..e5c23a68d3 100644 --- a/hardware_interface/include/hardware_interface/actuator.hpp +++ b/hardware_interface/include/hardware_interface/actuator.hpp @@ -23,7 +23,6 @@ #include "hardware_interface/handle.hpp" #include "hardware_interface/hardware_info.hpp" #include "hardware_interface/types/hardware_interface_return_values.hpp" -#include "hardware_interface/visibility_control.h" #include "rclcpp/duration.hpp" #include "rclcpp/logger.hpp" #include "rclcpp/node_interfaces/node_clock_interface.hpp" @@ -39,75 +38,54 @@ class Actuator final public: Actuator() = default; - HARDWARE_INTERFACE_PUBLIC explicit Actuator(std::unique_ptr impl); - HARDWARE_INTERFACE_PUBLIC explicit Actuator(Actuator && other) noexcept; ~Actuator() = default; - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & initialize( const HardwareInfo & actuator_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & cleanup(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & shutdown(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & activate(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & deactivate(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & error(); - HARDWARE_INTERFACE_PUBLIC std::vector export_state_interfaces(); - HARDWARE_INTERFACE_PUBLIC std::vector export_command_interfaces(); - HARDWARE_INTERFACE_PUBLIC return_type prepare_command_mode_switch( const std::vector & start_interfaces, const std::vector & stop_interfaces); - HARDWARE_INTERFACE_PUBLIC return_type perform_command_mode_switch( const std::vector & start_interfaces, const std::vector & stop_interfaces); - HARDWARE_INTERFACE_PUBLIC std::string get_name() const; - HARDWARE_INTERFACE_PUBLIC std::string get_group_name() const; - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state() const; - HARDWARE_INTERFACE_PUBLIC const rclcpp::Time & get_last_read_time() const; - HARDWARE_INTERFACE_PUBLIC const rclcpp::Time & get_last_write_time() const; - HARDWARE_INTERFACE_PUBLIC return_type read(const rclcpp::Time & time, const rclcpp::Duration & period); - HARDWARE_INTERFACE_PUBLIC return_type write(const rclcpp::Time & time, const rclcpp::Duration & period); - HARDWARE_INTERFACE_PUBLIC std::recursive_mutex & get_mutex(); private: diff --git a/hardware_interface/include/hardware_interface/component_parser.hpp b/hardware_interface/include/hardware_interface/component_parser.hpp index fc195d0a65..9de1813577 100644 --- a/hardware_interface/include/hardware_interface/component_parser.hpp +++ b/hardware_interface/include/hardware_interface/component_parser.hpp @@ -20,7 +20,6 @@ #include #include "hardware_interface/hardware_info.hpp" -#include "hardware_interface/visibility_control.h" namespace hardware_interface { @@ -30,7 +29,6 @@ namespace hardware_interface * \return vector filled with information about robot's control resources * \throws std::runtime_error if a robot attribute or tag is not found */ -HARDWARE_INTERFACE_PUBLIC std::vector parse_control_resources_from_urdf(const std::string & urdf); /** @@ -38,7 +36,6 @@ std::vector parse_control_resources_from_urdf(const std::string & * \return vector filled with information about hardware's StateInterfaces for the component * which are exported */ -HARDWARE_INTERFACE_PUBLIC std::vector parse_state_interface_descriptions( const std::vector & component_info); @@ -47,7 +44,6 @@ std::vector parse_state_interface_descriptions( * \param[out] state_interfaces_map unordered_map filled with information about hardware's * StateInterfaces for the component which are exported */ -HARDWARE_INTERFACE_PUBLIC void parse_state_interface_descriptions( const std::vector & component_info, std::unordered_map & state_interfaces_map); @@ -57,7 +53,6 @@ void parse_state_interface_descriptions( * \return vector filled with information about hardware's CommandInterfaces for the component * which are exported */ -HARDWARE_INTERFACE_PUBLIC std::vector parse_command_interface_descriptions( const std::vector & component_info); @@ -66,7 +61,6 @@ std::vector parse_command_interface_descriptions( * \param[out] command_interfaces_map unordered_map filled with information about hardware's * CommandInterfaces for the component which are exported */ -HARDWARE_INTERFACE_PUBLIC void parse_command_interface_descriptions( const std::vector & component_info, std::unordered_map & command_interfaces_map); diff --git a/hardware_interface/include/hardware_interface/lexical_casts.hpp b/hardware_interface/include/hardware_interface/lexical_casts.hpp index dd69dad7a6..ba9fd6c4ab 100644 --- a/hardware_interface/include/hardware_interface/lexical_casts.hpp +++ b/hardware_interface/include/hardware_interface/lexical_casts.hpp @@ -17,8 +17,6 @@ #include -#include "hardware_interface/visibility_control.h" - namespace hardware_interface { @@ -27,10 +25,8 @@ namespace hardware_interface * from https://github.com/ros-planning/srdfdom/blob/ad17b8d25812f752c397a6011cec64aeff090c46/src/model.cpp#L53 */ -HARDWARE_INTERFACE_PUBLIC double stod(const std::string & s); -HARDWARE_INTERFACE_PUBLIC bool parse_bool(const std::string & bool_string); } // namespace hardware_interface diff --git a/hardware_interface/include/hardware_interface/resource_manager.hpp b/hardware_interface/include/hardware_interface/resource_manager.hpp index cdde7550d3..b67aba088d 100644 --- a/hardware_interface/include/hardware_interface/resource_manager.hpp +++ b/hardware_interface/include/hardware_interface/resource_manager.hpp @@ -44,7 +44,7 @@ struct HardwareReadWriteStatus std::vector failed_hardware_names; }; -class HARDWARE_INTERFACE_PUBLIC ResourceManager +class ResourceManager { public: /// Default constructor for the Resource Manager. diff --git a/hardware_interface/include/hardware_interface/sensor.hpp b/hardware_interface/include/hardware_interface/sensor.hpp index ac7f3f6f6a..26e99f032a 100644 --- a/hardware_interface/include/hardware_interface/sensor.hpp +++ b/hardware_interface/include/hardware_interface/sensor.hpp @@ -23,7 +23,6 @@ #include "hardware_interface/hardware_info.hpp" #include "hardware_interface/sensor_interface.hpp" #include "hardware_interface/types/hardware_interface_return_values.hpp" -#include "hardware_interface/visibility_control.h" #include "rclcpp/duration.hpp" #include "rclcpp/logger.hpp" #include "rclcpp/node_interfaces/node_clock_interface.hpp" @@ -39,59 +38,42 @@ class Sensor final public: Sensor() = default; - HARDWARE_INTERFACE_PUBLIC explicit Sensor(std::unique_ptr impl); - HARDWARE_INTERFACE_PUBLIC explicit Sensor(Sensor && other) noexcept; ~Sensor() = default; - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & initialize( const HardwareInfo & sensor_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & cleanup(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & shutdown(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & activate(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & deactivate(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & error(); - HARDWARE_INTERFACE_PUBLIC std::vector export_state_interfaces(); - HARDWARE_INTERFACE_PUBLIC std::string get_name() const; - HARDWARE_INTERFACE_PUBLIC std::string get_group_name() const; - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state() const; - HARDWARE_INTERFACE_PUBLIC const rclcpp::Time & get_last_read_time() const; - HARDWARE_INTERFACE_PUBLIC return_type read(const rclcpp::Time & time, const rclcpp::Duration & period); - HARDWARE_INTERFACE_PUBLIC return_type write(const rclcpp::Time &, const rclcpp::Duration &) { return return_type::OK; } - HARDWARE_INTERFACE_PUBLIC std::recursive_mutex & get_mutex(); private: diff --git a/hardware_interface/include/hardware_interface/system.hpp b/hardware_interface/include/hardware_interface/system.hpp index 749e10d5e4..fc482d8106 100644 --- a/hardware_interface/include/hardware_interface/system.hpp +++ b/hardware_interface/include/hardware_interface/system.hpp @@ -23,7 +23,6 @@ #include "hardware_interface/hardware_info.hpp" #include "hardware_interface/system_interface.hpp" #include "hardware_interface/types/hardware_interface_return_values.hpp" -#include "hardware_interface/visibility_control.h" #include "rclcpp/duration.hpp" #include "rclcpp/logger.hpp" #include "rclcpp/node_interfaces/node_clock_interface.hpp" @@ -39,75 +38,54 @@ class System final public: System() = default; - HARDWARE_INTERFACE_PUBLIC explicit System(std::unique_ptr impl); - HARDWARE_INTERFACE_PUBLIC explicit System(System && other) noexcept; ~System() = default; - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & initialize( const HardwareInfo & system_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & cleanup(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & shutdown(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & activate(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & deactivate(); - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & error(); - HARDWARE_INTERFACE_PUBLIC std::vector export_state_interfaces(); - HARDWARE_INTERFACE_PUBLIC std::vector export_command_interfaces(); - HARDWARE_INTERFACE_PUBLIC return_type prepare_command_mode_switch( const std::vector & start_interfaces, const std::vector & stop_interfaces); - HARDWARE_INTERFACE_PUBLIC return_type perform_command_mode_switch( const std::vector & start_interfaces, const std::vector & stop_interfaces); - HARDWARE_INTERFACE_PUBLIC std::string get_name() const; - HARDWARE_INTERFACE_PUBLIC std::string get_group_name() const; - HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state() const; - HARDWARE_INTERFACE_PUBLIC const rclcpp::Time & get_last_read_time() const; - HARDWARE_INTERFACE_PUBLIC const rclcpp::Time & get_last_write_time() const; - HARDWARE_INTERFACE_PUBLIC return_type read(const rclcpp::Time & time, const rclcpp::Duration & period); - HARDWARE_INTERFACE_PUBLIC return_type write(const rclcpp::Time & time, const rclcpp::Duration & period); - HARDWARE_INTERFACE_PUBLIC std::recursive_mutex & get_mutex(); private: diff --git a/hardware_interface/include/hardware_interface/visibility_control.h b/hardware_interface/include/hardware_interface/visibility_control.h deleted file mode 100644 index cba6c347f2..0000000000 --- a/hardware_interface/include/hardware_interface/visibility_control.h +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright 2017 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. - -#ifndef HARDWARE_INTERFACE__VISIBILITY_CONTROL_H_ -#define HARDWARE_INTERFACE__VISIBILITY_CONTROL_H_ - -// This logic was borrowed (then namespaced) from the examples on the gcc wiki: -// https://gcc.gnu.org/wiki/Visibility - -#if defined _WIN32 || defined __CYGWIN__ -#ifdef __GNUC__ -#define HARDWARE_INTERFACE_EXPORT __attribute__((dllexport)) -#define HARDWARE_INTERFACE_IMPORT __attribute__((dllimport)) -#else -#define HARDWARE_INTERFACE_EXPORT __declspec(dllexport) -#define HARDWARE_INTERFACE_IMPORT __declspec(dllimport) -#endif -#ifdef HARDWARE_INTERFACE_BUILDING_DLL -#define HARDWARE_INTERFACE_PUBLIC HARDWARE_INTERFACE_EXPORT -#else -#define HARDWARE_INTERFACE_PUBLIC HARDWARE_INTERFACE_IMPORT -#endif -#define HARDWARE_INTERFACE_PUBLIC_TYPE HARDWARE_INTERFACE_PUBLIC -#define HARDWARE_INTERFACE_LOCAL -#else -#define HARDWARE_INTERFACE_EXPORT __attribute__((visibility("default"))) -#define HARDWARE_INTERFACE_IMPORT -#if __GNUC__ >= 4 -#define HARDWARE_INTERFACE_PUBLIC __attribute__((visibility("default"))) -#define HARDWARE_INTERFACE_LOCAL __attribute__((visibility("hidden"))) -#else -#define HARDWARE_INTERFACE_PUBLIC -#define HARDWARE_INTERFACE_LOCAL -#endif -#define HARDWARE_INTERFACE_PUBLIC_TYPE -#endif - -#endif // HARDWARE_INTERFACE__VISIBILITY_CONTROL_H_ diff --git a/hardware_interface/include/mock_components/generic_system.hpp b/hardware_interface/include/mock_components/generic_system.hpp index 7987780ba0..418924c007 100644 --- a/hardware_interface/include/mock_components/generic_system.hpp +++ b/hardware_interface/include/mock_components/generic_system.hpp @@ -25,7 +25,6 @@ #include "hardware_interface/system_interface.hpp" #include "hardware_interface/types/hardware_interface_return_values.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" -#include "hardware_interface/visibility_control.h" using hardware_interface::return_type; @@ -37,7 +36,7 @@ static constexpr size_t POSITION_INTERFACE_INDEX = 0; static constexpr size_t VELOCITY_INTERFACE_INDEX = 1; static constexpr size_t ACCELERATION_INTERFACE_INDEX = 2; -class HARDWARE_INTERFACE_PUBLIC GenericSystem : public hardware_interface::SystemInterface +class GenericSystem : public hardware_interface::SystemInterface { public: CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; diff --git a/hardware_interface/include/mock_components/visibility_control.h b/hardware_interface/include/mock_components/visibility_control.h deleted file mode 100644 index ccc695456e..0000000000 --- a/hardware_interface/include/mock_components/visibility_control.h +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright (c) 2021 PickNik, 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. - -#ifndef MOCK_COMPONENTS__VISIBILITY_CONTROL_H_ -#define MOCK_COMPONENTS__VISIBILITY_CONTROL_H_ - -// This logic was borrowed (then namespaced) from the examples on the gcc wiki: -// https://gcc.gnu.org/wiki/Visibility - -#if defined _WIN32 || defined __CYGWIN__ -#ifdef __GNUC__ -#define MOCK_COMPONENTS_EXPORT __attribute__((dllexport)) -#define MOCK_COMPONENTS_IMPORT __attribute__((dllimport)) -#else -#define MOCK_COMPONENTS_EXPORT __declspec(dllexport) -#define MOCK_COMPONENTS_IMPORT __declspec(dllimport) -#endif -#ifdef MOCK_COMPONENTS_BUILDING_DLL -#define MOCK_COMPONENTS_PUBLIC MOCK_COMPONENTS_EXPORT -#else -#define MOCK_COMPONENTS_PUBLIC MOCK_COMPONENTS_IMPORT -#endif -#define MOCK_COMPONENTS_PUBLIC_TYPE MOCK_COMPONENTS_PUBLIC -#define MOCK_COMPONENTS_LOCAL -#else -#define MOCK_COMPONENTS_EXPORT __attribute__((visibility("default"))) -#define MOCK_COMPONENTS_IMPORT -#if __GNUC__ >= 4 -#define MOCK_COMPONENTS_PUBLIC __attribute__((visibility("default"))) -#define MOCK_COMPONENTS_LOCAL __attribute__((visibility("hidden"))) -#else -#define MOCK_COMPONENTS_PUBLIC -#define MOCK_COMPONENTS_LOCAL -#endif -#define MOCK_COMPONENTS_PUBLIC_TYPE -#endif - -#endif // MOCK_COMPONENTS__VISIBILITY_CONTROL_H_ diff --git a/joint_limits/CMakeLists.txt b/joint_limits/CMakeLists.txt index 8be804fa23..444842313e 100644 --- a/joint_limits/CMakeLists.txt +++ b/joint_limits/CMakeLists.txt @@ -6,6 +6,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") -Werror=missing-braces) endif() +# using this instead of visibility macros +# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + set(THIS_PACKAGE_INCLUDE_DEPENDS pluginlib realtime_tools @@ -39,10 +43,6 @@ target_include_directories(joint_limiter_interface PUBLIC $ ) ament_target_dependencies(joint_limiter_interface PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) -# Causes the visibility macros to use dllexport rather than dllimport, -# which is appropriate when building the dll but not consuming it. -target_compile_definitions(joint_limiter_interface PRIVATE "JOINT_LIMITS_BUILDING_DLL") - add_library(joint_saturation_limiter SHARED src/joint_saturation_limiter.cpp @@ -53,9 +53,6 @@ target_include_directories(joint_saturation_limiter PUBLIC $ ) ament_target_dependencies(joint_saturation_limiter PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) -# Causes the visibility macros to use dllexport rather than dllimport, -# which is appropriate when building the dll but not consuming it. -target_compile_definitions(joint_saturation_limiter PRIVATE "JOINT_LIMITS_BUILDING_DLL") pluginlib_export_plugin_description_file(joint_limits joint_limiters.xml) diff --git a/joint_limits/include/joint_limits/joint_limiter_interface.hpp b/joint_limits/include/joint_limits/joint_limiter_interface.hpp index 17bffed021..af054634fa 100644 --- a/joint_limits/include/joint_limits/joint_limiter_interface.hpp +++ b/joint_limits/include/joint_limits/joint_limiter_interface.hpp @@ -21,7 +21,6 @@ #include #include "joint_limits/joint_limits_rosparam.hpp" -#include "joint_limits/visibility_control.h" #include "rclcpp/node.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "realtime_tools/realtime_buffer.hpp" @@ -35,9 +34,9 @@ template class JointLimiterInterface { public: - JOINT_LIMITS_PUBLIC JointLimiterInterface() = default; + JointLimiterInterface() = default; - JOINT_LIMITS_PUBLIC virtual ~JointLimiterInterface() = default; + virtual ~JointLimiterInterface() = default; /// Initialization of every JointLimiter. /** @@ -52,7 +51,7 @@ class JointLimiterInterface * \param[in] logging_itf node logging interface to log if error happens. * \param[in] robot_description_topic string of a topic where robot description is accessible. */ - JOINT_LIMITS_PUBLIC virtual bool init( + virtual bool init( const std::vector & joint_names, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf, @@ -133,7 +132,7 @@ class JointLimiterInterface * Wrapper init method that accepts pointer to the Node. * For details see other init method. */ - JOINT_LIMITS_PUBLIC virtual bool init( + virtual bool init( const std::vector & joint_names, const rclcpp::Node::SharedPtr & node, const std::string & robot_description_topic = "/robot_description") { @@ -146,7 +145,7 @@ class JointLimiterInterface * Wrapper init method that accepts pointer to the LifecycleNode. * For details see other init method. */ - JOINT_LIMITS_PUBLIC virtual bool init( + virtual bool init( const std::vector & joint_names, const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node, const std::string & robot_description_topic = "/robot_description") @@ -156,7 +155,7 @@ class JointLimiterInterface lifecycle_node->get_node_logging_interface(), robot_description_topic); } - JOINT_LIMITS_PUBLIC virtual bool configure(const JointLimitsStateDataType & current_joint_states) + virtual bool configure(const JointLimitsStateDataType & current_joint_states) { return on_configure(current_joint_states); } @@ -170,7 +169,7 @@ class JointLimiterInterface * \param[in] dt time delta to calculate missing integrals and derivation in joint limits. * \returns true if limits are enforced, otherwise false. */ - JOINT_LIMITS_PUBLIC virtual bool enforce( + virtual bool enforce( JointLimitsStateDataType & current_joint_states, JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt) { @@ -185,7 +184,7 @@ class JointLimiterInterface * \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits. * \returns true if limits are enforced, otherwise false. */ - JOINT_LIMITS_PUBLIC virtual bool enforce(std::vector & desired_joint_states) + virtual bool enforce(std::vector & desired_joint_states) { joint_limits_ = *(updated_limits_.readFromRT()); return on_enforce(desired_joint_states); @@ -197,15 +196,14 @@ class JointLimiterInterface * Implementation-specific initialization of limiter's internal states and libraries. * \returns true if initialization was successful, otherwise false. */ - JOINT_LIMITS_PUBLIC virtual bool on_init() = 0; + virtual bool on_init() = 0; /** \brief Method is realized by an implementation. * * Implementation-specific configuration of limiter's internal states and libraries. * \returns true if initialization was successful, otherwise false. */ - JOINT_LIMITS_PUBLIC virtual bool on_configure( - const JointLimitsStateDataType & current_joint_states) = 0; + virtual bool on_configure(const JointLimitsStateDataType & current_joint_states) = 0; /** \brief Method is realized by an implementation. * @@ -217,7 +215,7 @@ class JointLimiterInterface * \param[in] dt time delta to calculate missing integrals and derivation in joint limits. * \returns true if limits are enforced, otherwise false. */ - JOINT_LIMITS_PUBLIC virtual bool on_enforce( + virtual bool on_enforce( JointLimitsStateDataType & current_joint_states, JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt) = 0; @@ -231,7 +229,7 @@ class JointLimiterInterface * \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits. * \returns true if limits are enforced, otherwise false. */ - JOINT_LIMITS_PUBLIC virtual bool on_enforce(std::vector & desired_joint_states) = 0; + virtual bool on_enforce(std::vector & desired_joint_states) = 0; size_t number_of_joints_; std::vector joint_names_; diff --git a/joint_limits/include/joint_limits/joint_saturation_limiter.hpp b/joint_limits/include/joint_limits/joint_saturation_limiter.hpp index a69cc2791c..4ebdfbc5ad 100644 --- a/joint_limits/include/joint_limits/joint_saturation_limiter.hpp +++ b/joint_limits/include/joint_limits/joint_saturation_limiter.hpp @@ -38,14 +38,14 @@ class JointSaturationLimiter : public JointLimiterInterface { public: /** \brief Constructor */ - JOINT_LIMITS_PUBLIC JointSaturationLimiter(); + JointSaturationLimiter(); /** \brief Destructor */ - JOINT_LIMITS_PUBLIC ~JointSaturationLimiter(); + ~JointSaturationLimiter(); - JOINT_LIMITS_PUBLIC bool on_init() override { return true; } + bool on_init() override { return true; } - JOINT_LIMITS_PUBLIC bool on_configure( + bool on_configure( const trajectory_msgs::msg::JointTrajectoryPoint & /*current_joint_states*/) override { return true; @@ -66,7 +66,7 @@ class JointSaturationLimiter : public JointLimiterInterface * \param[in] dt time delta to calculate missing integrals and derivation in joint limits. * \returns true if limits are enforced, otherwise false. */ - JOINT_LIMITS_PUBLIC bool on_enforce( + bool on_enforce( trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states, trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states, const rclcpp::Duration & dt) override; @@ -80,7 +80,7 @@ class JointSaturationLimiter : public JointLimiterInterface * \param[in,out] desired_joint_states physical quantity that should be adjusted to obey the * limits. \returns true if limits are enforced, otherwise false. */ - JOINT_LIMITS_PUBLIC bool on_enforce(std::vector & desired_joint_states) override; + bool on_enforce(std::vector & desired_joint_states) override; private: rclcpp::Clock::SharedPtr clock_; diff --git a/joint_limits/include/joint_limits/visibility_control.h b/joint_limits/include/joint_limits/visibility_control.h deleted file mode 100644 index 54edbc15f3..0000000000 --- a/joint_limits/include/joint_limits/visibility_control.h +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt) -// -// 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. - -#ifndef JOINT_LIMITS__VISIBILITY_CONTROL_H_ -#define JOINT_LIMITS__VISIBILITY_CONTROL_H_ - -// This logic was borrowed (then namespaced) from the examples on the gcc wiki: -// https://gcc.gnu.org/wiki/Visibility - -#if defined _WIN32 || defined __CYGWIN__ -#ifdef __GNUC__ -#define JOINT_LIMITS_EXPORT __attribute__((dllexport)) -#define JOINT_LIMITS_IMPORT __attribute__((dllimport)) -#else -#define JOINT_LIMITS_EXPORT __declspec(dllexport) -#define JOINT_LIMITS_IMPORT __declspec(dllimport) -#endif -#ifdef JOINT_LIMITS_BUILDING_DLL -#define JOINT_LIMITS_PUBLIC JOINT_LIMITS_EXPORT -#else -#define JOINT_LIMITS_PUBLIC JOINT_LIMITS_IMPORT -#endif -#define JOINT_LIMITS_PUBLIC_TYPE JOINT_LIMITS_PUBLIC -#define JOINT_LIMITS_LOCAL -#else -#define JOINT_LIMITS_EXPORT __attribute__((visibility("default"))) -#define JOINT_LIMITS_IMPORT -#if __GNUC__ >= 4 -#define JOINT_LIMITS_PUBLIC __attribute__((visibility("default"))) -#define JOINT_LIMITS_LOCAL __attribute__((visibility("hidden"))) -#else -#define JOINT_LIMITS_PUBLIC -#define JOINT_LIMITS_LOCAL -#endif -#define JOINT_LIMITS_PUBLIC_TYPE -#endif - -#endif // JOINT_LIMITS__VISIBILITY_CONTROL_H_ diff --git a/transmission_interface/CMakeLists.txt b/transmission_interface/CMakeLists.txt index 185fb32d3a..7a45856245 100644 --- a/transmission_interface/CMakeLists.txt +++ b/transmission_interface/CMakeLists.txt @@ -6,6 +6,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") -Werror=missing-braces) endif() +# using this instead of visibility macros +# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + set(THIS_PACKAGE_INCLUDE_DEPENDS hardware_interface pluginlib diff --git a/transmission_interface/include/transmission_interface/visibility_control.h b/transmission_interface/include/transmission_interface/visibility_control.h deleted file mode 100644 index 97852ea58e..0000000000 --- a/transmission_interface/include/transmission_interface/visibility_control.h +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright 2020 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. - -#ifndef TRANSMISSION_INTERFACE__VISIBILITY_CONTROL_H_ -#define TRANSMISSION_INTERFACE__VISIBILITY_CONTROL_H_ - -// This logic was borrowed (then namespaced) from the examples on the gcc wiki: -// https://gcc.gnu.org/wiki/Visibility - -#if defined _WIN32 || defined __CYGWIN__ -#ifdef __GNUC__ -#define TRANSMISSION_INTERFACE_EXPORT __attribute__((dllexport)) -#define TRANSMISSION_INTERFACE_IMPORT __attribute__((dllimport)) -#else -#define TRANSMISSION_INTERFACE_EXPORT __declspec(dllexport) -#define TRANSMISSION_INTERFACE_IMPORT __declspec(dllimport) -#endif -#ifdef TRANSMISSION_INTERFACE_BUILDING_DLL -#define TRANSMISSION_INTERFACE_PUBLIC TRANSMISSION_INTERFACE_EXPORT -#else -#define TRANSMISSION_INTERFACE_PUBLIC TRANSMISSION_INTERFACE_IMPORT -#endif -#define TRANSMISSION_INTERFACE_PUBLIC_TYPE TRANSMISSION_INTERFACE_PUBLIC -#define TRANSMISSION_INTERFACE_LOCAL -#else -#define TRANSMISSION_INTERFACE_EXPORT __attribute__((visibility("default"))) -#define TRANSMISSION_INTERFACE_IMPORT -#if __GNUC__ >= 4 -#define TRANSMISSION_INTERFACE_PUBLIC __attribute__((visibility("default"))) -#define TRANSMISSION_INTERFACE_LOCAL __attribute__((visibility("hidden"))) -#else -#define TRANSMISSION_INTERFACE_PUBLIC -#define TRANSMISSION_INTERFACE_LOCAL -#endif -#define TRANSMISSION_INTERFACE_PUBLIC_TYPE -#endif - -#endif // TRANSMISSION_INTERFACE__VISIBILITY_CONTROL_H_ From 606193911fbdeb7fb0c3eb3f60ba00b89bcf3930 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Sun, 29 Dec 2024 20:27:12 +0000 Subject: [PATCH 3/5] Update changelogs --- controller_interface/CHANGELOG.rst | 6 ++++++ controller_manager/CHANGELOG.rst | 8 ++++++++ controller_manager_msgs/CHANGELOG.rst | 3 +++ hardware_interface/CHANGELOG.rst | 8 ++++++++ hardware_interface_testing/CHANGELOG.rst | 3 +++ joint_limits/CHANGELOG.rst | 5 +++++ ros2_control/CHANGELOG.rst | 3 +++ ros2_control_test_assets/CHANGELOG.rst | 5 +++++ ros2controlcli/CHANGELOG.rst | 3 +++ rqt_controller_manager/CHANGELOG.rst | 3 +++ transmission_interface/CHANGELOG.rst | 5 +++++ 11 files changed, 52 insertions(+) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index 32795abf9d..6c0b27a4db 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Remove boilerplate visibility macros (`#1972 `_) +* Semantic components cleanup (`#1940 `_) +* Contributors: Bence Magyar, Wiktor Bajor + 4.22.0 (2024-12-20) ------------------- * Fixed typo. Added s to state_interfaces\_ (`#1930 `_) diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index 64b1567dd2..c5a4173128 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Remove boilerplate visibility macros (`#1972 `_) +* Move test_utils module from demos repo (`#1955 `_) +* Fix deprecated usage of lock_memory API (`#1970 `_) +* Fix spawner behaviour on failing controller activation or deactivation (`#1941 `_) +* Contributors: Bence Magyar, Christoph Fröhlich, Sai Kishor Kothakota, Sudip Roy + 4.22.0 (2024-12-20) ------------------- * Async Hardware Components (`#1567 `_) diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index fc92596273..072b4ab7e0 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.22.0 (2024-12-20) ------------------- diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index df05cb39e3..4e0a0f96f1 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Remove boilerplate visibility macros (`#1972 `_) +* Add asynchronous hardware components documentation (`#1961 `_) +* Reuse `TriggerType` enum in hardware components (`#1962 `_) +* Fix pre-commit clang changes (`#1963 `_) +* Contributors: Bence Magyar, Sai Kishor Kothakota, Sanjeev + 4.22.0 (2024-12-20) ------------------- * Propagate read/write rate to the HardwareInfo properly (`#1928 `_) diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index 2bdadd883a..cd4c9cc6bc 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.22.0 (2024-12-20) ------------------- * Propagate read/write rate to the HardwareInfo properly (`#1928 `_) diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index 1fa0b3a392..fbaa12308c 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Remove boilerplate visibility macros (`#1972 `_) +* Contributors: Bence Magyar + 4.22.0 (2024-12-20) ------------------- diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index 231aa395c6..d383a6e432 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.22.0 (2024-12-20) ------------------- diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index bfa3c5aae0..513824c259 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Move test_utils module from demos repo (`#1955 `_) +* Contributors: Christoph Fröhlich + 4.22.0 (2024-12-20) ------------------- * Async Hardware Components (`#1567 `_) diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index cb70f08797..caf3910580 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.22.0 (2024-12-20) ------------------- diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 3ae6a8a682..5c18afad25 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.22.0 (2024-12-20) ------------------- diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index 6e94d7d826..a070d098e8 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Remove boilerplate visibility macros (`#1972 `_) +* Contributors: Bence Magyar + 4.22.0 (2024-12-20) ------------------- From 4ad5709cfc3b24bd667ae1a550fbc33344c7abc8 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Sun, 29 Dec 2024 20:27:35 +0000 Subject: [PATCH 4/5] 4.23.0 --- controller_interface/CHANGELOG.rst | 4 ++-- controller_interface/package.xml | 2 +- controller_manager/CHANGELOG.rst | 4 ++-- controller_manager/package.xml | 2 +- controller_manager_msgs/CHANGELOG.rst | 4 ++-- controller_manager_msgs/package.xml | 2 +- hardware_interface/CHANGELOG.rst | 4 ++-- hardware_interface/package.xml | 2 +- hardware_interface_testing/CHANGELOG.rst | 4 ++-- hardware_interface_testing/package.xml | 2 +- joint_limits/CHANGELOG.rst | 4 ++-- joint_limits/package.xml | 2 +- ros2_control/CHANGELOG.rst | 4 ++-- ros2_control/package.xml | 2 +- ros2_control_test_assets/CHANGELOG.rst | 4 ++-- ros2_control_test_assets/package.xml | 2 +- ros2controlcli/CHANGELOG.rst | 4 ++-- ros2controlcli/package.xml | 2 +- ros2controlcli/setup.py | 2 +- rqt_controller_manager/CHANGELOG.rst | 4 ++-- rqt_controller_manager/package.xml | 2 +- rqt_controller_manager/setup.py | 2 +- transmission_interface/CHANGELOG.rst | 4 ++-- transmission_interface/package.xml | 2 +- 24 files changed, 35 insertions(+), 35 deletions(-) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index 6c0b27a4db..6843cd925a 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- * Remove boilerplate visibility macros (`#1972 `_) * Semantic components cleanup (`#1940 `_) * Contributors: Bence Magyar, Wiktor Bajor diff --git a/controller_interface/package.xml b/controller_interface/package.xml index d3a40a227c..2074c6a38b 100644 --- a/controller_interface/package.xml +++ b/controller_interface/package.xml @@ -2,7 +2,7 @@ controller_interface - 4.22.0 + 4.23.0 Description of controller_interface Bence Magyar Denis Štogl diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index c5a4173128..4e1469f776 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- * Remove boilerplate visibility macros (`#1972 `_) * Move test_utils module from demos repo (`#1955 `_) * Fix deprecated usage of lock_memory API (`#1970 `_) diff --git a/controller_manager/package.xml b/controller_manager/package.xml index f917922fd3..b7355bba23 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -2,7 +2,7 @@ controller_manager - 4.22.0 + 4.23.0 Description of controller_manager Bence Magyar Denis Štogl diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index 072b4ab7e0..75cfa45226 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- 4.22.0 (2024-12-20) ------------------- diff --git a/controller_manager_msgs/package.xml b/controller_manager_msgs/package.xml index 703feeccc7..300b114a3f 100644 --- a/controller_manager_msgs/package.xml +++ b/controller_manager_msgs/package.xml @@ -2,7 +2,7 @@ controller_manager_msgs - 4.22.0 + 4.23.0 Messages and services for the controller manager. Bence Magyar Denis Štogl diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index 4e0a0f96f1..233145fef4 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- * Remove boilerplate visibility macros (`#1972 `_) * Add asynchronous hardware components documentation (`#1961 `_) * Reuse `TriggerType` enum in hardware components (`#1962 `_) diff --git a/hardware_interface/package.xml b/hardware_interface/package.xml index 5f748e5680..647032b586 100644 --- a/hardware_interface/package.xml +++ b/hardware_interface/package.xml @@ -1,7 +1,7 @@ hardware_interface - 4.22.0 + 4.23.0 ros2_control hardware interface Bence Magyar Denis Štogl diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index cd4c9cc6bc..3c79b93829 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- 4.22.0 (2024-12-20) ------------------- diff --git a/hardware_interface_testing/package.xml b/hardware_interface_testing/package.xml index 8c03aafda8..5e2fc5a493 100644 --- a/hardware_interface_testing/package.xml +++ b/hardware_interface_testing/package.xml @@ -1,7 +1,7 @@ hardware_interface_testing - 4.22.0 + 4.23.0 ros2_control hardware interface testing Bence Magyar Denis Štogl diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index fbaa12308c..28ed558bf5 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- * Remove boilerplate visibility macros (`#1972 `_) * Contributors: Bence Magyar diff --git a/joint_limits/package.xml b/joint_limits/package.xml index 44ce8f5c50..22523e4c4b 100644 --- a/joint_limits/package.xml +++ b/joint_limits/package.xml @@ -1,6 +1,6 @@ joint_limits - 4.22.0 + 4.23.0 Package with interfaces for handling of joint limits in controllers or in hardware. The package also implements Saturation Joint Limiter for position-velocity-acceleration set and other individual interfaces. Bence Magyar diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index d383a6e432..38058cdcda 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- 4.22.0 (2024-12-20) ------------------- diff --git a/ros2_control/package.xml b/ros2_control/package.xml index 7cc5192743..ee914dee74 100644 --- a/ros2_control/package.xml +++ b/ros2_control/package.xml @@ -1,7 +1,7 @@ ros2_control - 4.22.0 + 4.23.0 Metapackage for ROS2 control related packages Bence Magyar Denis Štogl diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index 513824c259..62fa5f070f 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- * Move test_utils module from demos repo (`#1955 `_) * Contributors: Christoph Fröhlich diff --git a/ros2_control_test_assets/package.xml b/ros2_control_test_assets/package.xml index 27ecd415c7..aadd51c6ea 100644 --- a/ros2_control_test_assets/package.xml +++ b/ros2_control_test_assets/package.xml @@ -2,7 +2,7 @@ ros2_control_test_assets - 4.22.0 + 4.23.0 The package provides shared test resources for ros2_control stack Bence Magyar diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index caf3910580..57ad8d12d8 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- 4.22.0 (2024-12-20) ------------------- diff --git a/ros2controlcli/package.xml b/ros2controlcli/package.xml index 4c2a9cb99f..e32a82ea0f 100644 --- a/ros2controlcli/package.xml +++ b/ros2controlcli/package.xml @@ -2,7 +2,7 @@ ros2controlcli - 4.22.0 + 4.23.0 The ROS 2 command line tools for ROS2 Control. diff --git a/ros2controlcli/setup.py b/ros2controlcli/setup.py index 66c614b3ab..c4a3f9caef 100644 --- a/ros2controlcli/setup.py +++ b/ros2controlcli/setup.py @@ -19,7 +19,7 @@ setup( name=package_name, - version="4.22.0", + version="4.23.0", packages=find_packages(exclude=["test"]), data_files=[ ("share/" + package_name, ["package.xml"]), diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 5c18afad25..da18a01092 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- 4.22.0 (2024-12-20) ------------------- diff --git a/rqt_controller_manager/package.xml b/rqt_controller_manager/package.xml index cd944cf445..0b4a438957 100644 --- a/rqt_controller_manager/package.xml +++ b/rqt_controller_manager/package.xml @@ -2,7 +2,7 @@ rqt_controller_manager - 4.22.0 + 4.23.0 Graphical frontend for interacting with the controller manager. Bence Magyar Denis Štogl diff --git a/rqt_controller_manager/setup.py b/rqt_controller_manager/setup.py index 1d65fcef86..98685ee621 100644 --- a/rqt_controller_manager/setup.py +++ b/rqt_controller_manager/setup.py @@ -20,7 +20,7 @@ setup( name=package_name, - version="4.22.0", + version="4.23.0", packages=[package_name], data_files=[ ("share/ament_index/resource_index/packages", ["resource/" + package_name]), diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index a070d098e8..20aaf7d0a6 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.23.0 (2024-12-29) +------------------- * Remove boilerplate visibility macros (`#1972 `_) * Contributors: Bence Magyar diff --git a/transmission_interface/package.xml b/transmission_interface/package.xml index 035e6f0370..e1e721e0e1 100644 --- a/transmission_interface/package.xml +++ b/transmission_interface/package.xml @@ -2,7 +2,7 @@ transmission_interface - 4.22.0 + 4.23.0 transmission_interface contains data structures for representing mechanical transmissions, methods for propagating values between actuator and joint spaces and tooling to support this. Bence Magyar Denis Štogl From 53656e4636ba0472a5ee20d3a29f096ff50f6f5d Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 1 Jan 2025 10:21:08 +0100 Subject: [PATCH 5/5] Bump version of pre-commit hooks (#1973) Co-authored-by: christophfroehlich <3367244+christophfroehlich@users.noreply.github.com> --- .pre-commit-config.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 75c5402ffe..feefcc317d 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -37,7 +37,7 @@ repos: # Python hooks - repo: https://github.com/asottile/pyupgrade - rev: v3.19.0 + rev: v3.19.1 hooks: - id: pyupgrade args: [--py36-plus] @@ -63,7 +63,7 @@ repos: # CPP hooks - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v19.1.4 + rev: v19.1.5 hooks: - id: clang-format args: ['-fallback-style=none', '-i']