Change deprecated functions by current ones. jazzy
authorWalter Fetter Lages <w.fetter@ieee.org>
Mon, 5 May 2025 06:03:35 +0000 (03:03 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Mon, 5 May 2025 06:03:35 +0000 (03:03 -0300)
include/computed_torque_controller/computed_torque_controller.hpp
src/computed_torque_controller.cpp

index 7f7643c..95c7de8 100644 (file)
@@ -1,7 +1,7 @@
 /******************************************************************************
                       ROS 2 computed_torque_controller Package
                            Computed Torque  Controller
 /******************************************************************************
                       ROS 2 computed_torque_controller Package
                            Computed Torque  Controller
-          Copyright (C) 2013..2022 Walter Fetter Lages <w.fetter@ieee.org>
+          Copyright (C) 2013..2025 Walter Fetter Lages <w.fetter@ieee.org>
 
         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
 
         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 <kdl_parser/kdl_parser.hpp>
 #include <kdl/chainidsolver_recursive_newton_euler.hpp>
 
 #include <kdl_parser/kdl_parser.hpp>
 #include <kdl/chainidsolver_recursive_newton_euler.hpp>
 
-#include <realtime_tools/realtime_buffer.h>
+#include <realtime_tools/realtime_buffer.hpp>
 
 #include <computed_torque_controller/visibility_control.h>
 
 
 #include <computed_torque_controller/visibility_control.h>
 
index 854e6b3..5bd0790 100644 (file)
@@ -1,7 +1,7 @@
 /******************************************************************************
                    ROS 2 computed_torque_controller Package
                            Computed Torque  Controller
 /******************************************************************************
                    ROS 2 computed_torque_controller Package
                            Computed Torque  Controller
-          Copyright (C) 2013..2024 Walter Fetter Lages <w.fetter@ieee.org>
+          Copyright (C) 2013..2025 Walter Fetter Lages <w.fetter@ieee.org>
 
         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
 
         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++)
                {
        {
                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_;
                }
                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++)
        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_);
 
                SetToZero(dqr_);
                SetToZero(ddqr_);
 
@@ -229,8 +229,8 @@ namespace effort_controllers
 
                for(unsigned int i=0;i < nJoints_;i++)
                {
 
                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();
 
                }
                for(auto &f : fext_) f.Zero();