From fea2d8a398c317cd49b103ed4f716440536db5d6 Mon Sep 17 00:00:00 2001 From: Robotgir <47585672+Robotgir@users.noreply.github.com> Date: Tue, 28 Mar 2023 19:40:48 +0200 Subject: [PATCH] [Controller Interface] Add time and period paramters to update_reference_from_subscribers() (#846) #API-break MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Add Migration file for API breaking changes. Co-authored-by: Denis Štogl --- MIGRATION.md | 12 ++++++++++++ .../chainable_controller_interface.hpp | 3 ++- .../src/chainable_controller_interface.cpp | 2 +- .../test/test_chainable_controller_interface.hpp | 3 ++- .../test_chainable_controller.cpp | 3 ++- .../test_chainable_controller.hpp | 3 ++- 6 files changed, 21 insertions(+), 5 deletions(-) create mode 100644 MIGRATION.md diff --git a/MIGRATION.md b/MIGRATION.md new file mode 100644 index 0000000000..f84fc7aa6f --- /dev/null +++ b/MIGRATION.md @@ -0,0 +1,12 @@ +# Migration Notes + +API changes in ros2_control releases + +## ROS Rolling + +#### Controller Interface + +`update_reference_from_subscribers()` method got parameters and now has the following signature: +``` +update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & /*period*/) +``` diff --git a/controller_interface/include/controller_interface/chainable_controller_interface.hpp b/controller_interface/include/controller_interface/chainable_controller_interface.hpp index 5008a1b5bf..37b784011c 100644 --- a/controller_interface/include/controller_interface/chainable_controller_interface.hpp +++ b/controller_interface/include/controller_interface/chainable_controller_interface.hpp @@ -94,7 +94,8 @@ class ChainableControllerInterface : public ControllerInterfaceBase * * \returns return_type::OK if update is successfully, otherwise return_type::ERROR. */ - virtual return_type update_reference_from_subscribers() = 0; + virtual return_type update_reference_from_subscribers( + const rclcpp::Time & time, const rclcpp::Duration & period) = 0; /// Execute calculations of the controller and update command interfaces. /** diff --git a/controller_interface/src/chainable_controller_interface.cpp b/controller_interface/src/chainable_controller_interface.cpp index 45e2f1a32e..2f7c67741e 100644 --- a/controller_interface/src/chainable_controller_interface.cpp +++ b/controller_interface/src/chainable_controller_interface.cpp @@ -32,7 +32,7 @@ return_type ChainableControllerInterface::update( if (!is_in_chained_mode()) { - ret = update_reference_from_subscribers(); + ret = update_reference_from_subscribers(time, period); if (ret != return_type::OK) { return ret; diff --git a/controller_interface/test/test_chainable_controller_interface.hpp b/controller_interface/test/test_chainable_controller_interface.hpp index 38ce124582..28401f13d5 100644 --- a/controller_interface/test/test_chainable_controller_interface.hpp +++ b/controller_interface/test/test_chainable_controller_interface.hpp @@ -86,7 +86,8 @@ class TestableChainableControllerInterface } } - controller_interface::return_type update_reference_from_subscribers() override + controller_interface::return_type update_reference_from_subscribers( + const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override { if (reference_interface_value_ == INTERFACE_VALUE_SUBSCRIBER_ERROR) { diff --git a/controller_manager/test/test_chainable_controller/test_chainable_controller.cpp b/controller_manager/test/test_chainable_controller/test_chainable_controller.cpp index ba1132e68b..d21957a0b4 100644 --- a/controller_manager/test/test_chainable_controller/test_chainable_controller.cpp +++ b/controller_manager/test/test_chainable_controller/test_chainable_controller.cpp @@ -61,7 +61,8 @@ TestChainableController::state_interface_configuration() const } } -controller_interface::return_type TestChainableController::update_reference_from_subscribers() +controller_interface::return_type TestChainableController::update_reference_from_subscribers( + const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) { for (size_t i = 0; i < reference_interfaces_.size(); ++i) { 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 a7205d3024..5925ed8d11 100644 --- a/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp +++ b/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp @@ -63,7 +63,8 @@ class TestChainableController : public controller_interface::ChainableController CONTROLLER_MANAGER_PUBLIC std::vector on_export_reference_interfaces() override; - controller_interface::return_type update_reference_from_subscribers() override; + controller_interface::return_type update_reference_from_subscribers( + const rclcpp::Time & time, const rclcpp::Duration & period) override; controller_interface::return_type update_and_write_commands( const rclcpp::Time & time, const rclcpp::Duration & period) override;