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

index 18a4ef9..4d689f4 100644 (file)
@@ -1,7 +1,7 @@
 /******************************************************************************
                    ROS 2 pid_plus_gravity_controller Package
                         PID+Gravity Compensation Controller
 /******************************************************************************
                    ROS 2 pid_plus_gravity_controller Package
                         PID+Gravity Compensation Controller
-          Copyright (C) 2017..2022 Walter Fetter Lages <w.fetter@ieee.org>
+          Copyright (C) 2017..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
@@ -32,7 +32,7 @@
 #include <kdl_parser/kdl_parser.hpp>
 #include <kdl/chaindynparam.hpp>
 
 #include <kdl_parser/kdl_parser.hpp>
 #include <kdl/chaindynparam.hpp>
 
-#include <realtime_tools/realtime_buffer.h>
+#include <realtime_tools/realtime_buffer.hpp>
 
 #include <pid_plus_gravity_controller/visibility_control.h>
 
 
 #include <pid_plus_gravity_controller/visibility_control.h>
 
index 02580ab..eb4a4ba 100644 (file)
@@ -1,7 +1,7 @@
 /******************************************************************************
                     ROS 2 pid_plus_gravity_controller Package
                         PID+Gravity Compensation Controller
 /******************************************************************************
                     ROS 2 pid_plus_gravity_controller Package
                         PID+Gravity Compensation Controller
-          Copyright (C) 2017..2024 Walter Fetter Lages <w.fetter@ieee.org>
+          Copyright (C) 2017..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
@@ -84,7 +84,7 @@ namespace effort_controllers
                        for(const auto &joint : jointNames_)
                        {
                                auto pid=std::make_shared<control_toolbox::PidROS>(get_node(),joint);
                        for(const auto &joint : jointNames_)
                        {
                                auto pid=std::make_shared<control_toolbox::PidROS>(get_node(),joint);
-                               pid->initPid();
+                               pid->initialize_from_ros_parameters();
                                pid_.push_back(pid);
                        }
                }
                                pid_.push_back(pid);
                        }
                }
@@ -166,7 +166,7 @@ namespace effort_controllers
        controller_interface::CallbackReturn PidPlusGravityController::on_activate(const rclcpp_lifecycle::State & /*previous_state*/)
        {
                for(unsigned int i=0;i < nJoints_;i++)
        controller_interface::CallbackReturn PidPlusGravityController::on_activate(const rclcpp_lifecycle::State & /*previous_state*/)
        {
                for(unsigned int i=0;i < nJoints_;i++)
-                       q_(i)=state_interfaces_[i].get_value();
+                       q_(i)=state_interfaces_[i].get_optional().value_or(q_(i));
                 qr_=q_;
 
                 struct sched_param param;
                 qr_=q_;
 
                 struct sched_param param;
@@ -182,7 +182,7 @@ namespace effort_controllers
        controller_interface::CallbackReturn PidPlusGravityController::on_deactivate(const rclcpp_lifecycle::State &/*previous_state*/)
        {
                for(unsigned int i=0;i < nJoints_;i++)
        controller_interface::CallbackReturn PidPlusGravityController::on_deactivate(const rclcpp_lifecycle::State &/*previous_state*/)
        {
                for(unsigned int i=0;i < nJoints_;i++)
-                       q_(i)=state_interfaces_[i].get_value();
+                       q_(i)=state_interfaces_[i].get_optional().value_or(q_(i));
 
                if(chainParam_->JntToGravity(q_,gravity_) < 0)
                        RCLCPP_ERROR(get_node()->get_logger(),"KDL dynamics solver failed.");
 
                if(chainParam_->JntToGravity(q_,gravity_) < 0)
                        RCLCPP_ERROR(get_node()->get_logger(),"KDL dynamics solver failed.");
@@ -203,13 +203,13 @@ namespace effort_controllers
                                qr_.data=Eigen::VectorXd::Map((*referencePoint)->positions.data(),nJoints_);
 
                for(unsigned int i=0;i < nJoints_;i++)
                                qr_.data=Eigen::VectorXd::Map((*referencePoint)->positions.data(),nJoints_);
 
                for(unsigned int i=0;i < nJoints_;i++)
-                       q_(i)=state_interfaces_[i].get_value();
+                       q_(i)=state_interfaces_[i].get_optional().value_or(q_(i));
 
                if(chainParam_->JntToGravity(q_,gravity_) < 0)
                        RCLCPP_ERROR(get_node()->get_logger(),"KDL dynamics solver failed.");
 
                for(unsigned int i=0;i < nJoints_;i++)
 
                if(chainParam_->JntToGravity(q_,gravity_) < 0)
                        RCLCPP_ERROR(get_node()->get_logger(),"KDL dynamics solver failed.");
 
                for(unsigned int i=0;i < nJoints_;i++)
-                       if(!command_interfaces_[i].set_value(gravity_(i)+pid_[i]->computeCommand(qr_(i)-q_(i),period)))
+                       if(!command_interfaces_[i].set_value(gravity_(i)+pid_[i]->compute_command(qr_(i)-q_(i),period)))
                                RCLCPP_ERROR(get_node()->get_logger(),"Can't set command value.");
 
                return controller_interface::return_type::OK;
                                RCLCPP_ERROR(get_node()->get_logger(),"Can't set command value.");
 
                return controller_interface::return_type::OK;