Skip to content

Commit 63448a3

Browse files
authored
Remove deprecated feedforward parameter+service (#1753)
Co-authored-by: pascalau <pascalau>
1 parent e3cc6d8 commit 63448a3

File tree

8 files changed

+59
-254
lines changed

8 files changed

+59
-254
lines changed

doc/migration.rst

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,3 +11,7 @@ The ``effort_controllers/GripperActionController`` and ``position_controllers/Gr
1111
diff_drive_controller
1212
*****************************
1313
* 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>`_).
14+
15+
pid_controller
16+
*****************************
17+
* 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>`_).

pid_controller/doc/userdoc.rst

Lines changed: 0 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -69,14 +69,6 @@ If controller parameter ``use_external_measured_states`` is true:
6969

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

72-
Services
73-
,,,,,,,,,,,
74-
75-
- <controller_name>/set_feedforward_control [std_srvs/srv/SetBool]
76-
77-
.. warning::
78-
This service is being deprecated in favour of setting the ``feedforward_gain`` parameter to a non-zero value.
79-
8072
Publishers
8173
,,,,,,,,,,,
8274
- <controller_name>/controller_state [control_msgs/msg/MultiDOFStateStamped]
@@ -88,10 +80,6 @@ The PID controller uses the `generate_parameter_library <https://github.com/Pick
8880

8981
List of parameters
9082
=========================
91-
.. warning::
92-
The parameter ``enable_feedforward`` is being deprecated in favor of setting the ``feedforward_gain`` parameter to a non-zero value.
93-
This might cause different behavior in the future if currently the ``feedforward_gain`` is set to a non-zero value and not activated.
94-
9583
.. generate_parameter_library_details:: ../src/pid_controller.yaml
9684

9785

pid_controller/include/pid_controller/pid_controller.hpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -77,8 +77,6 @@ class PidController : public controller_interface::ChainableControllerInterface
7777

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

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

90-
rclcpp::Service<ControllerModeSrvType>::SharedPtr set_feedforward_control_service_;
91-
realtime_tools::RealtimeBuffer<bool> feedforward_mode_enabled_;
92-
9388
using ControllerStatePublisher = realtime_tools::RealtimePublisher<ControllerStateMsg>;
9489

9590
rclcpp::Publisher<ControllerStateMsg>::SharedPtr s_publisher_;

pid_controller/src/pid_controller.cpp

Lines changed: 9 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -74,8 +74,6 @@ PidController::PidController() : controller_interface::ChainableControllerInterf
7474

7575
controller_interface::CallbackReturn PidController::on_init()
7676
{
77-
feedforward_mode_enabled_.initRT(false);
78-
7977
try
8078
{
8179
param_listener_ = std::make_shared<pid_controller::ParamListener>(get_node());
@@ -96,8 +94,6 @@ void PidController::update_parameters()
9694
return;
9795
}
9896
params_ = param_listener_->get_params();
99-
100-
feedforward_mode_enabled_.writeFromNonRT(params_.enable_feedforward);
10197
}
10298

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

244-
auto set_feedforward_control_callback =
245-
[&](
246-
const std::shared_ptr<ControllerModeSrvType::Request> request,
247-
std::shared_ptr<ControllerModeSrvType::Response> response)
248-
{
249-
feedforward_mode_enabled_.writeFromNonRT(request->data);
250-
251-
RCLCPP_WARN(
252-
get_node()->get_logger(),
253-
"This service will be deprecated in favour of setting the ``feedforward_gain`` parameter to "
254-
"a non-zero value.");
255-
256-
response->success = true;
257-
};
258-
259-
set_feedforward_control_service_ = get_node()->create_service<ControllerModeSrvType>(
260-
"~/set_feedforward_control", set_feedforward_control_callback, qos_services);
261-
262240
try
263241
{
264242
// State publisher
@@ -512,23 +490,20 @@ controller_interface::return_type PidController::update_and_write_commands(
512490
if (std::isfinite(reference_interfaces_[i]) && std::isfinite(measured_state_values_[i]))
513491
{
514492
// calculate feed-forward
515-
if (*(feedforward_mode_enabled_.readFromRT()))
493+
// two interfaces
494+
if (reference_interfaces_.size() == 2 * dof_)
516495
{
517-
// two interfaces
518-
if (reference_interfaces_.size() == 2 * dof_)
519-
{
520-
if (std::isfinite(reference_interfaces_[dof_ + i]))
521-
{
522-
tmp_command = reference_interfaces_[dof_ + i] *
523-
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;
524-
}
525-
}
526-
else // one interface
496+
if (std::isfinite(reference_interfaces_[dof_ + i]))
527497
{
528-
tmp_command = reference_interfaces_[i] *
498+
tmp_command = reference_interfaces_[dof_ + i] *
529499
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;
530500
}
531501
}
502+
else // one interface
503+
{
504+
tmp_command = reference_interfaces_[i] *
505+
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;
506+
}
532507

533508
double error = reference_interfaces_[i] - measured_state_values_[i];
534509
if (params_.gains.dof_names_map[params_.dof_names[i]].angle_wraparound)

pid_controller/src/pid_controller.yaml

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -43,11 +43,6 @@ pid_controller:
4343
default_value: false,
4444
description: "Use external states from a topic instead from state interfaces."
4545
}
46-
enable_feedforward: {
47-
type: bool,
48-
default_value: false,
49-
description: "Enables feedforward gain. (Will be deprecated in favour of setting feedforward_gain to a non-zero value.)"
50-
}
5146
gains:
5247
__map_dof_names:
5348
p: {

0 commit comments

Comments
 (0)