From: Walter Fetter Lages Date: Mon, 5 May 2025 06:03:35 +0000 (-0300) Subject: Change deprecated functions by current ones. X-Git-Url: http://git.ece.ufrgs.br/?a=commitdiff_plain;p=computed_torque_controller.git Change deprecated functions by current ones. --- diff --git a/include/computed_torque_controller/computed_torque_controller.hpp b/include/computed_torque_controller/computed_torque_controller.hpp index 7f7643c..95c7de8 100644 --- a/include/computed_torque_controller/computed_torque_controller.hpp +++ b/include/computed_torque_controller/computed_torque_controller.hpp @@ -1,7 +1,7 @@ /****************************************************************************** ROS 2 computed_torque_controller Package Computed Torque Controller - Copyright (C) 2013..2022 Walter Fetter Lages + Copyright (C) 2013..2025 Walter Fetter Lages This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -30,7 +30,7 @@ #include #include -#include +#include #include diff --git a/src/computed_torque_controller.cpp b/src/computed_torque_controller.cpp index 854e6b3..5bd0790 100644 --- a/src/computed_torque_controller.cpp +++ b/src/computed_torque_controller.cpp @@ -1,7 +1,7 @@ /****************************************************************************** ROS 2 computed_torque_controller Package Computed Torque Controller - Copyright (C) 2013..2024 Walter Fetter Lages + Copyright (C) 2013..2025 Walter Fetter Lages This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -176,8 +176,8 @@ namespace effort_controllers { for(unsigned int i=0;i < nJoints_;i++) { - q_(i)=state_interfaces_[2*i].get_value(); - dq_(i)=state_interfaces_[2*i+1].get_value(); + q_(i)=state_interfaces_[2*i].get_optional().value_or(q_(i)); + dq_(i)=state_interfaces_[2*i+1].get_optional().value_or(dq_(i)); } qr_=q_; dqr_=dq_; @@ -196,7 +196,7 @@ namespace effort_controllers controller_interface::CallbackReturn ComputedTorqueController::on_deactivate(const rclcpp_lifecycle::State &/*previous_state*/) { for(unsigned int i=0;i < nJoints_;i++) - q_(i)=state_interfaces_[2*i].get_value(); + q_(i)=state_interfaces_[2*i].get_optional().value_or(q_(i)); SetToZero(dqr_); SetToZero(ddqr_); @@ -229,8 +229,8 @@ namespace effort_controllers for(unsigned int i=0;i < nJoints_;i++) { - q_(i)=state_interfaces_[2*i].get_value(); - dq_(i)=state_interfaces_[2*i+1].get_value(); + q_(i)=state_interfaces_[2*i].get_optional().value_or(q_(i)); + dq_(i)=state_interfaces_[2*i+1].get_optional().value_or(dq_(i)); } for(auto &f : fext_) f.Zero();