/******************************************************************************
ROS 2 nonsmooth_backstep_controller Package
Non-Smooth Backstepping Controller
- Copyright (C) 2014..2022 Walter Fetter Lages <w.fetter@ieee.org>
+ Copyright (C) 2014..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
#include <tf2_msgs/msg/tf_message.hpp>
#include <controller_interface/controller_interface.hpp>
-#include <realtime_tools/realtime_buffer.h>
-#include <realtime_tools/realtime_publisher.h>
+#include <realtime_tools/realtime_buffer.hpp>
+#include <realtime_tools/realtime_publisher.hpp>
#include <arc_odometry/diff_odometry.hpp>
#include <nonsmooth_backstep_controller_msgs/msg/non_smooth_backstep_controller_status.hpp>
/******************************************************************************
ROS 2 nonsmooth_backstep_controller Package
Non-Smooth Backstepping Controller
- Copyright (C) 2014..2022 Walter Fetter Lages <w.fetter@ieee.org>
+ Copyright (C) 2014..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
eta_.setZero();
lastSamplingTime_=get_node()->get_clock()->now();
for(unsigned int i=0;i < joints_.size();i++)
- phi_[i]=state_interfaces_[i].get_value();
+ phi_[i]=state_interfaces_[i].get_optional().value_or(phi_[i]);
struct sched_param param;
param.sched_priority=priority_;
CallbackReturn NonSmoothBackstepController::on_deactivate(const rclcpp_lifecycle::State &/*previous_state*/)
{
for(unsigned int i=0;i < joints_.size();i++)
- command_interfaces_[i].set_value(0);
+ if(!command_interfaces_[i].set_value(0.0))
+ RCLCPP_WARN(get_node()->get_logger(),"Failed to set value to command interface.");
return CallbackReturn::SUCCESS;
}
// phi[1] is the right wheel angular displacement
Eigen::Vector2d deltaPhi=-phi_;
for(unsigned int i=0;i < joints_.size();i++)
- phi_[i]=state_interfaces_[i].get_value();
+ phi_[i]=state_interfaces_[i].get_optional().value_or(phi_[i]);
deltaPhi+=phi_;
odom_.update(deltaPhi,dt);
// Apply torques
for(unsigned int i=0;i < joints_.size();i++)
- command_interfaces_[i].set_value(torque[i]);
+ if(!command_interfaces_[i].set_value(torque[i]))
+ RCLCPP_WARN(get_node()->get_logger(),"Failed to set value to command interface.");
if(rt_status_publisher_ && rt_status_publisher_->trylock())
{