From: Walter Fetter Lages Date: Mon, 5 May 2025 05:54:31 +0000 (-0300) Subject: Change deprecated functions by current ones. X-Git-Url: http://git.ece.ufrgs.br/?a=commitdiff_plain;p=pid_plus_gravity_controller.git Change deprecated functions by current ones. --- diff --git a/include/pid_plus_gravity_controller/pid_plus_gravity_controller.hpp b/include/pid_plus_gravity_controller/pid_plus_gravity_controller.hpp index 18a4ef9..4d689f4 100644 --- a/include/pid_plus_gravity_controller/pid_plus_gravity_controller.hpp +++ b/include/pid_plus_gravity_controller/pid_plus_gravity_controller.hpp @@ -1,7 +1,7 @@ /****************************************************************************** ROS 2 pid_plus_gravity_controller Package PID+Gravity Compensation Controller - Copyright (C) 2017..2022 Walter Fetter Lages + Copyright (C) 2017..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 @@ -32,7 +32,7 @@ #include #include -#include +#include #include diff --git a/src/pid_plus_gravity_controller.cpp b/src/pid_plus_gravity_controller.cpp index 02580ab..eb4a4ba 100644 --- a/src/pid_plus_gravity_controller.cpp +++ b/src/pid_plus_gravity_controller.cpp @@ -1,7 +1,7 @@ /****************************************************************************** ROS 2 pid_plus_gravity_controller Package PID+Gravity Compensation Controller - Copyright (C) 2017..2024 Walter Fetter Lages + Copyright (C) 2017..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 @@ -84,7 +84,7 @@ namespace effort_controllers for(const auto &joint : jointNames_) { auto pid=std::make_shared(get_node(),joint); - pid->initPid(); + pid->initialize_from_ros_parameters(); 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++) - q_(i)=state_interfaces_[i].get_value(); + q_(i)=state_interfaces_[i].get_optional().value_or(q_(i)); 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++) - 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."); @@ -203,13 +203,13 @@ namespace effort_controllers 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(!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;