Skip to content

Remove deprecated feedforward parameter+service #1753

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 2 commits into from
Jun 11, 2025
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions doc/migration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -11,3 +11,7 @@ The ``effort_controllers/GripperActionController`` and ``position_controllers/Gr
diff_drive_controller
*****************************
* Parameters ``has_velocity_limits``, ``has_acceleration_limits``, and ``has_jerk_limits`` are removed. Instead, set the respective limits to ``.NAN``. (`#1653 <https://github.com/ros-controls/ros2_controllers/pull/1653>`_).

pid_controller
*****************************
* Parameters ``enable_feedforward`` and service ``set_feedforward_control`` are removed. Instead, set the feedforward_gain to zero or a non-zero value. (`#1553 <https://github.com/ros-controls/ros2_controllers/pull/1553>`_).
12 changes: 0 additions & 12 deletions pid_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -69,14 +69,6 @@ If controller parameter ``use_external_measured_states`` is true:

- <controller_name>/measured_state [control_msgs/msg/MultiDOFCommand]

Services
,,,,,,,,,,,

- <controller_name>/set_feedforward_control [std_srvs/srv/SetBool]

.. warning::
This service is being deprecated in favour of setting the ``feedforward_gain`` parameter to a non-zero value.

Publishers
,,,,,,,,,,,
- <controller_name>/controller_state [control_msgs/msg/MultiDOFStateStamped]
Expand All @@ -88,10 +80,6 @@ The PID controller uses the `generate_parameter_library <https://github.com/Pick

List of parameters
=========================
.. warning::
The parameter ``enable_feedforward`` is being deprecated in favor of setting the ``feedforward_gain`` parameter to a non-zero value.
This might cause different behavior in the future if currently the ``feedforward_gain`` is set to a non-zero value and not activated.

.. generate_parameter_library_details:: ../src/pid_controller.yaml


Expand Down
5 changes: 0 additions & 5 deletions pid_controller/include/pid_controller/pid_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,6 @@ class PidController : public controller_interface::ChainableControllerInterface

using PidPtr = std::shared_ptr<control_toolbox::PidROS>;
std::vector<PidPtr> pids_;
// Feed-forward velocity weight factor when calculating closed loop pid adapter's command
std::vector<double> feedforward_gain_;

// Command subscribers and Controller State publisher
rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ = nullptr;
Expand All @@ -87,9 +85,6 @@ class PidController : public controller_interface::ChainableControllerInterface
rclcpp::Subscription<ControllerMeasuredStateMsg>::SharedPtr measured_state_subscriber_ = nullptr;
realtime_tools::RealtimeBuffer<std::shared_ptr<ControllerMeasuredStateMsg>> measured_state_;

rclcpp::Service<ControllerModeSrvType>::SharedPtr set_feedforward_control_service_;
realtime_tools::RealtimeBuffer<bool> feedforward_mode_enabled_;

using ControllerStatePublisher = realtime_tools::RealtimePublisher<ControllerStateMsg>;

rclcpp::Publisher<ControllerStateMsg>::SharedPtr s_publisher_;
Expand Down
54 changes: 18 additions & 36 deletions pid_controller/src/pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,6 @@ PidController::PidController() : controller_interface::ChainableControllerInterf

controller_interface::CallbackReturn PidController::on_init()
{
feedforward_mode_enabled_.initRT(false);

try
{
param_listener_ = std::make_shared<pid_controller::ParamListener>(get_node());
Expand All @@ -96,8 +94,6 @@ void PidController::update_parameters()
return;
}
params_ = param_listener_->get_params();

feedforward_mode_enabled_.writeFromNonRT(params_.enable_feedforward);
}

controller_interface::CallbackReturn PidController::configure_parameters()
Expand Down Expand Up @@ -241,24 +237,6 @@ controller_interface::CallbackReturn PidController::on_configure(
measured_state_values_.resize(
dof_ * params_.reference_and_state_interfaces.size(), std::numeric_limits<double>::quiet_NaN());

auto set_feedforward_control_callback =
[&](
const std::shared_ptr<ControllerModeSrvType::Request> request,
std::shared_ptr<ControllerModeSrvType::Response> response)
{
feedforward_mode_enabled_.writeFromNonRT(request->data);

RCLCPP_WARN(
get_node()->get_logger(),
"This service will be deprecated in favour of setting the ``feedforward_gain`` parameter to "
"a non-zero value.");

response->success = true;
};

set_feedforward_control_service_ = get_node()->create_service<ControllerModeSrvType>(
"~/set_feedforward_control", set_feedforward_control_callback, qos_services);

try
{
// State publisher
Expand Down Expand Up @@ -494,7 +472,10 @@ controller_interface::return_type PidController::update_and_write_commands(
{
for (size_t i = 0; i < measured_state_values_.size(); ++i)
{
measured_state_values_[i] = state_interfaces_[i].get_value();
const auto measured_state = state_interfaces_[i].get_optional();
measured_state_values_[i] = measured_state.has_value()
? measured_state.value()
: std::numeric_limits<double>::quiet_NaN();
}
}

Expand All @@ -512,23 +493,20 @@ controller_interface::return_type PidController::update_and_write_commands(
if (std::isfinite(reference_interfaces_[i]) && std::isfinite(measured_state_values_[i]))
{
// calculate feed-forward
if (*(feedforward_mode_enabled_.readFromRT()))
// two interfaces
if (reference_interfaces_.size() == 2 * dof_)
{
// two interfaces
if (reference_interfaces_.size() == 2 * dof_)
{
if (std::isfinite(reference_interfaces_[dof_ + i]))
{
tmp_command = reference_interfaces_[dof_ + i] *
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;
}
}
else // one interface
if (std::isfinite(reference_interfaces_[dof_ + i]))
{
tmp_command = reference_interfaces_[i] *
tmp_command = reference_interfaces_[dof_ + i] *
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;
}
}
else // one interface
{
tmp_command = reference_interfaces_[i] *
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;
}

double error = reference_interfaces_[i] - measured_state_values_[i];
if (params_.gains.dof_names_map[params_.dof_names[i]].angle_wraparound)
Expand Down Expand Up @@ -599,7 +577,11 @@ controller_interface::return_type PidController::update_and_write_commands(
state_publisher_->msg_.dof_states[i].time_step = period.seconds();
// Command can store the old calculated values. This should be obvious because at least one
// another value is NaN.
state_publisher_->msg_.dof_states[i].output = command_interfaces_[i].get_value();

const auto cmd_interface = command_interfaces_[i].get_optional();
state_publisher_->msg_.dof_states[i].output = cmd_interface.has_value()
? cmd_interface.value()
: std::numeric_limits<double>::quiet_NaN();
}
state_publisher_->unlockAndPublish();
}
Expand Down
5 changes: 0 additions & 5 deletions pid_controller/src/pid_controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,6 @@ pid_controller:
default_value: false,
description: "Use external states from a topic instead from state interfaces."
}
enable_feedforward: {
type: bool,
default_value: false,
description: "Enables feedforward gain. (Will be deprecated in favour of setting feedforward_gain to a non-zero value.)"
}
gains:
__map_dof_names:
p: {
Expand Down
Loading
Loading