From: Walter Fetter Lages Date: Sun, 15 Dec 2024 06:03:15 +0000 (-0300) Subject: Port to Jazzy. X-Git-Url: http://git.ece.ufrgs.br/?a=commitdiff_plain;h=bcc35602508e7ed63feeecbe7b8980adfe721051;p=computed_torque_controller.git Port to Jazzy. --- diff --git a/src/computed_torque_controller.cpp b/src/computed_torque_controller.cpp index b02be6d..854e6b3 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..2022 Walter Fetter Lages + Copyright (C) 2013..2024 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 @@ -21,6 +21,7 @@ #include +#include #include #include #include @@ -205,7 +206,8 @@ namespace effort_controllers RCLCPP_ERROR(get_node()->get_logger(),"KDL inverse dynamics solver failed."); for(unsigned int i=0;i < nJoints_;i++) - command_interfaces_[i].set_value(torque_(i)); + if(!command_interfaces_[i].set_value(torque_(i))) + RCLCPP_ERROR(get_node()->get_logger(),"Can't set command value.."); return controller_interface::CallbackReturn::SUCCESS; } @@ -238,7 +240,8 @@ namespace effort_controllers RCLCPP_ERROR(get_node()->get_logger(),"KDL inverse dynamics solver failed."); for(unsigned int i=0;i < nJoints_;i++) - command_interfaces_[i].set_value(torque_(i)); + if(!command_interfaces_[i].set_value(torque_(i))) + RCLCPP_ERROR(get_node()->get_logger(),"Can't set command value.."); return controller_interface::return_type::OK; }