diff --git a/thruster_allocation_matrix_controller/include/thruster_allocation_matrix_controller/thruster_allocation_matrix_controller.hpp b/thruster_allocation_matrix_controller/include/thruster_allocation_matrix_controller/thruster_allocation_matrix_controller.hpp index b1e0aac..cb01113 100644 --- a/thruster_allocation_matrix_controller/include/thruster_allocation_matrix_controller/thruster_allocation_matrix_controller.hpp +++ b/thruster_allocation_matrix_controller/include/thruster_allocation_matrix_controller/thruster_allocation_matrix_controller.hpp @@ -85,8 +85,7 @@ class ThrusterAllocationMatrixController : public controller_interface::Chainabl protected: std::vector on_export_reference_interfaces() override; - controller_interface::return_type update_reference_from_subscribers( - const rclcpp::Time & time, const rclcpp::Duration & period) override; + controller_interface::return_type update_reference_from_subscribers() override; void update_parameters(); diff --git a/thruster_allocation_matrix_controller/src/thruster_allocation_matrix_controller.cpp b/thruster_allocation_matrix_controller/src/thruster_allocation_matrix_controller.cpp index 3f68d6b..1dad712 100644 --- a/thruster_allocation_matrix_controller/src/thruster_allocation_matrix_controller.cpp +++ b/thruster_allocation_matrix_controller/src/thruster_allocation_matrix_controller.cpp @@ -206,8 +206,7 @@ std::vector ThrusterAllocationMatrixContro return reference_interfaces; } -controller_interface::return_type ThrusterAllocationMatrixController::update_reference_from_subscribers( - const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) +controller_interface::return_type ThrusterAllocationMatrixController::update_reference_from_subscribers() { auto * current_reference = reference_.readFromNonRT(); diff --git a/velocity_controllers/include/velocity_controllers/integral_sliding_mode_controller.hpp b/velocity_controllers/include/velocity_controllers/integral_sliding_mode_controller.hpp index 9e4fe1e..32d41ac 100644 --- a/velocity_controllers/include/velocity_controllers/integral_sliding_mode_controller.hpp +++ b/velocity_controllers/include/velocity_controllers/integral_sliding_mode_controller.hpp @@ -86,8 +86,7 @@ class IntegralSlidingModeController : public controller_interface::ChainableCont protected: std::vector on_export_reference_interfaces() override; - controller_interface::return_type update_reference_from_subscribers( - const rclcpp::Time & time, const rclcpp::Duration & period) override; + controller_interface::return_type update_reference_from_subscribers() override; controller_interface::return_type update_system_state_values(); diff --git a/velocity_controllers/src/integral_sliding_mode_controller.cpp b/velocity_controllers/src/integral_sliding_mode_controller.cpp index 412ee2c..ec0c488 100644 --- a/velocity_controllers/src/integral_sliding_mode_controller.cpp +++ b/velocity_controllers/src/integral_sliding_mode_controller.cpp @@ -241,8 +241,7 @@ controller_interface::CallbackReturn IntegralSlidingModeController::on_deactivat bool IntegralSlidingModeController::on_set_chained_mode(bool /*chained_mode*/) { return true; } -controller_interface::return_type IntegralSlidingModeController::update_reference_from_subscribers( - const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) +controller_interface::return_type IntegralSlidingModeController::update_reference_from_subscribers() { auto * current_reference = reference_.readFromNonRT();