/******************************************************************************
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
#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>
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;
}
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;
}