Port to Jazzy.
authorWalter Fetter Lages <w.fetter@ieee.org>
Sun, 15 Dec 2024 06:03:15 +0000 (03:03 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Sun, 15 Dec 2024 06:03:15 +0000 (03:03 -0300)
src/computed_torque_controller.cpp

index b02be6d..854e6b3 100644 (file)
@@ -1,7 +1,7 @@
 /******************************************************************************
                    ROS 2 computed_torque_controller Package
                            Computed Torque  Controller
-          Copyright (C) 2013..2022 Walter Fetter Lages <w.fetter@ieee.org>
+          Copyright (C) 2013..2024 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
@@ -21,6 +21,7 @@
 
 #include <sys/mman.h>
 
+#include <rclcpp/rclcpp.hpp>
 #include <rclcpp/logging.hpp>
 #include <hardware_interface/types/hardware_interface_type_values.hpp>
 #include <pluginlib/class_list_macros.hpp>
@@ -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;
        }