Skip to content

Commit 1adbeed

Browse files
authored
[PID Controllers] Set first set point to current measurement (backport #2205) (#2210)
1 parent 9c610fd commit 1adbeed

File tree

6 files changed

+137
-15
lines changed

6 files changed

+137
-15
lines changed

doc/release_notes.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -103,6 +103,7 @@ pid_controller
103103
* The legacy ``antiwindup`` boolean and integral clamp parameters ``i_clamp_max``/``i_clamp_min`` have been deprecated in favor of the new ``antiwindup_strategy`` parameter. A ``tracking_time_constant`` parameter has also been introduced to configure the back-calculation strategy.
104104
* A new ``error_deadband`` parameter stops integration when the error is within a specified range.
105105
* PID state publisher can be turned off or on by using ``activate_state_publisher`` parameter. (`#1823 <https://github.com/ros-controls/ros2_controllers/pull/1823>`_).
106+
* Added parameter ``set_current_state_as_first_setpoint`` (default: true) to set the current state as the first setpoint when the controller is activated, helping to avoid large initial errors and sudden jumps in control output (`#2205 <https://github.com/ros-controls/ros2_controllers/pull/2205>`_).
106107

107108
steering_controllers_library
108109
********************************

pid_controller/src/pid_controller.cpp

Lines changed: 40 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -442,11 +442,49 @@ controller_interface::CallbackReturn PidController::on_activate(
442442
measured_state_.try_set(current_state_);
443443
}
444444

445-
reference_interfaces_.assign(
446-
reference_interfaces_.size(), std::numeric_limits<double>::quiet_NaN());
447445
measured_state_values_.assign(
448446
measured_state_values_.size(), std::numeric_limits<double>::quiet_NaN());
449447

448+
// Initialize reference interfaces from current state so initial reference equals current state
449+
reference_interfaces_.assign(
450+
reference_interfaces_.size(), std::numeric_limits<double>::quiet_NaN());
451+
452+
if (params_.set_current_state_as_first_setpoint)
453+
{
454+
if (params_.use_external_measured_states)
455+
{
456+
auto measured_state_opt = measured_state_.try_get();
457+
if (measured_state_opt.has_value())
458+
{
459+
const auto & state = measured_state_opt.value();
460+
for (size_t i = 0; i < dof_; ++i)
461+
{
462+
if (i < state.values.size() && !std::isnan(state.values[i]))
463+
{
464+
reference_interfaces_[i] = state.values[i];
465+
}
466+
if (
467+
reference_interfaces_.size() == 2 * dof_ && i < state.values_dot.size() &&
468+
!std::isnan(state.values_dot[i]))
469+
{
470+
reference_interfaces_[dof_ + i] = state.values_dot[i];
471+
}
472+
}
473+
}
474+
}
475+
else
476+
{
477+
for (size_t i = 0; i < measured_state_values_.size(); ++i)
478+
{
479+
const auto state_interface_value_op = state_interfaces_[i].get_optional();
480+
if (state_interface_value_op.has_value())
481+
{
482+
reference_interfaces_[i] = state_interface_value_op.value();
483+
}
484+
}
485+
}
486+
}
487+
450488
// prefixed save_i_term parameter is read from ROS parameters
451489
for (auto & pid : pids_)
452490
{

pid_controller/src/pid_controller.yaml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,12 @@ pid_controller:
3838
size_lt<>: 3,
3939
}
4040
}
41+
set_current_state_as_first_setpoint: {
42+
type: bool,
43+
default_value: true,
44+
read_only: true,
45+
description: "When true, the controller will set the current state as the first setpoint when the controller is activated. This can help to avoid large initial errors and sudden jumps in the control output when the controller starts."
46+
}
4147
use_external_measured_states: {
4248
type: bool,
4349
default_value: false,

pid_controller/test/pid_controller_params.yaml

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@ test_pid_controller:
1414

1515
reference_and_state_interfaces: ["position"]
1616

17+
set_current_state_as_first_setpoint: true
18+
1719
gains:
1820
joint1: {p: 1.0, i: 2.0, d: 3.0, u_clamp_max: 5.0, u_clamp_min: -5.0}
1921

@@ -26,6 +28,8 @@ test_pid_controller_unlimited:
2628

2729
reference_and_state_interfaces: ["position"]
2830

31+
set_current_state_as_first_setpoint: true
32+
2933
gains:
3034
joint1: {p: 1.0, i: 2.0, d: 3.0}
3135

@@ -38,6 +42,8 @@ test_pid_controller_angle_wraparound_on:
3842

3943
reference_and_state_interfaces: ["position"]
4044

45+
set_current_state_as_first_setpoint: true
46+
4147
gains:
4248
joint1: {p: 1.0, i: 2.0, d: 3.0, angle_wraparound: true}
4349

@@ -50,6 +56,8 @@ test_pid_controller_with_feedforward_gain:
5056

5157
reference_and_state_interfaces: ["position"]
5258

59+
set_current_state_as_first_setpoint: true
60+
5361
gains:
5462
joint1: {p: 0.5, i: 0.0, d: 0.0, feedforward_gain: 1.0}
5563

@@ -63,6 +71,8 @@ test_pid_controller_with_feedforward_gain_dual_interface:
6371

6472
reference_and_state_interfaces: ["position", "velocity"]
6573

74+
set_current_state_as_first_setpoint: true
75+
6676
gains:
6777
joint1: {p: 0.5, i: 0.3, d: 0.4, feedforward_gain: 1.0}
6878
joint2: {p: 0.5, i: 0.3, d: 0.4, feedforward_gain: 1.0}
@@ -76,6 +86,8 @@ test_save_i_term_off:
7686

7787
reference_and_state_interfaces: ["position"]
7888

89+
set_current_state_as_first_setpoint: true
90+
7991
gains:
8092
joint1: {p: 1.0, i: 2.0, d: 3.0, save_i_term: false}
8193

@@ -88,5 +100,21 @@ test_save_i_term_on:
88100

89101
reference_and_state_interfaces: ["position"]
90102

103+
set_current_state_as_first_setpoint: true
104+
91105
gains:
92106
joint1: {p: 1.0, i: 2.0, d: 3.0, save_i_term: true}
107+
108+
test_pid_controller_no_first_setpoint:
109+
ros__parameters:
110+
dof_names:
111+
- joint1
112+
113+
command_interface: position
114+
115+
reference_and_state_interfaces: ["position"]
116+
117+
set_current_state_as_first_setpoint: false
118+
119+
gains:
120+
joint1: {p: 1.0, i: 2.0, d: 3.0, u_clamp_max: 5.0, u_clamp_min: -5.0}

pid_controller/test/test_pid_controller.cpp

Lines changed: 60 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -143,10 +143,12 @@ TEST_F(PidControllerTest, activate_success)
143143
EXPECT_TRUE(std::isnan(cmd));
144144
}
145145

146+
// With set_current_state_as_first_setpoint=true (default), reference interfaces are initialized
147+
// to the current state values on activation
146148
EXPECT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size());
147-
for (const auto & interface : controller_->reference_interfaces_)
149+
for (size_t i = 0; i < controller_->reference_interfaces_.size(); ++i)
148150
{
149-
EXPECT_TRUE(std::isnan(interface));
151+
EXPECT_EQ(controller_->reference_interfaces_[i], dof_state_values_[i]);
150152
}
151153
}
152154

@@ -176,16 +178,18 @@ TEST_F(PidControllerTest, reactivate_success)
176178
SetUpController();
177179

178180
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
181+
// With set_current_state_as_first_setpoint=true (default), reference interfaces are set to
182+
// current state values (dof_state_values_[0] = 1.1) on each activation
179183
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
180-
ASSERT_TRUE(std::isnan(controller_->reference_interfaces_[0]));
184+
ASSERT_EQ(controller_->reference_interfaces_[0], dof_state_values_[0]);
181185
ASSERT_TRUE(std::isnan(controller_->measured_state_values_[0]));
182186
ASSERT_EQ(controller_->command_interfaces_[0].get_optional().value(), 101.101);
183187
ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
184-
ASSERT_TRUE(std::isnan(controller_->reference_interfaces_[0]));
188+
ASSERT_EQ(controller_->reference_interfaces_[0], dof_state_values_[0]);
185189
ASSERT_TRUE(std::isnan(controller_->measured_state_values_[0]));
186190
ASSERT_EQ(controller_->command_interfaces_[0].get_optional().value(), 101.101);
187191
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
188-
ASSERT_TRUE(std::isnan(controller_->reference_interfaces_[0]));
192+
ASSERT_EQ(controller_->reference_interfaces_[0], dof_state_values_[0]);
189193
ASSERT_TRUE(std::isnan(controller_->measured_state_values_[0]));
190194
ASSERT_EQ(controller_->command_interfaces_[0].get_optional().value(), 101.101);
191195

@@ -287,7 +291,7 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_off)
287291
EXPECT_EQ(*(controller_->feedforward_mode_enabled_.readFromRT()), false);
288292
for (const auto & interface : controller_->reference_interfaces_)
289293
{
290-
EXPECT_TRUE(std::isnan(interface));
294+
EXPECT_TRUE(std::isfinite(interface));
291295
}
292296

293297
controller_->set_reference(dof_command_values_);
@@ -296,7 +300,7 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_off)
296300
{
297301
EXPECT_FALSE(std::isnan(controller_->input_ref_.get().values[i]));
298302
EXPECT_EQ(controller_->input_ref_.get().values[i], dof_command_values_[i]);
299-
EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i]));
303+
EXPECT_TRUE(std::isfinite(controller_->reference_interfaces_[i]));
300304
}
301305

302306
ASSERT_EQ(
@@ -344,7 +348,7 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_on_with_zero_feedforward
344348
EXPECT_EQ(*(controller_->feedforward_mode_enabled_.readFromRT()), false);
345349
for (const auto & interface : controller_->reference_interfaces_)
346350
{
347-
EXPECT_TRUE(std::isnan(interface));
351+
EXPECT_TRUE(std::isfinite(interface));
348352
}
349353

350354
controller_->set_reference(dof_command_values_);
@@ -357,7 +361,7 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_on_with_zero_feedforward
357361
{
358362
EXPECT_FALSE(std::isnan(controller_->input_ref_.get().values[i]));
359363
EXPECT_EQ(controller_->input_ref_.get().values[i], dof_command_values_[i]);
360-
EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i]));
364+
EXPECT_TRUE(std::isfinite(controller_->reference_interfaces_[i]));
361365
}
362366

363367
ASSERT_EQ(
@@ -530,7 +534,7 @@ TEST_F(PidControllerTest, subscribe_and_get_messages_success)
530534
for (size_t i = 0; i < dof_names_.size(); ++i)
531535
{
532536
ASSERT_EQ(msg.dof_states[i].name, dof_names_[i]);
533-
EXPECT_TRUE(std::isnan(msg.dof_states[i].reference));
537+
EXPECT_TRUE(std::isfinite(msg.dof_states[i].reference));
534538
ASSERT_EQ(msg.dof_states[i].output, dof_command_values_[i]);
535539
}
536540
}
@@ -555,21 +559,21 @@ TEST_F(PidControllerTest, receive_message_and_publish_updated_status)
555559
for (size_t i = 0; i < dof_names_.size(); ++i)
556560
{
557561
ASSERT_EQ(msg.dof_states[i].name, dof_names_[i]);
558-
EXPECT_TRUE(std::isnan(msg.dof_states[i].reference));
562+
EXPECT_TRUE(std::isfinite(msg.dof_states[i].reference));
559563
ASSERT_EQ(msg.dof_states[i].output, dof_command_values_[i]);
560564
}
561565

562566
for (size_t i = 0; i < controller_->reference_interfaces_.size(); ++i)
563567
{
564-
EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i]));
568+
EXPECT_TRUE(std::isfinite(controller_->reference_interfaces_[i]));
565569
}
566570

567571
publish_commands();
568572
controller_->wait_for_commands(executor);
569573

570574
for (size_t i = 0; i < controller_->reference_interfaces_.size(); ++i)
571575
{
572-
EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i]));
576+
EXPECT_TRUE(std::isfinite(controller_->reference_interfaces_[i]));
573577
}
574578

575579
ASSERT_EQ(
@@ -810,6 +814,49 @@ TEST_F(PidControllerTest, test_save_i_term_on)
810814
EXPECT_NEAR(actual_value, 2.00002, 1e-5); // i_term from above
811815
}
812816

817+
/**
818+
* @brief Test that reference interfaces are initialized to current state on activation when
819+
* set_current_state_as_first_setpoint is true (default).
820+
*/
821+
TEST_F(PidControllerTest, test_activate_set_current_state_as_first_setpoint_true)
822+
{
823+
SetUpController(); // uses test_pid_controller: set_current_state_as_first_setpoint defaults to
824+
// true
825+
826+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
827+
ASSERT_TRUE(controller_->params_.set_current_state_as_first_setpoint);
828+
829+
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
830+
831+
// reference interfaces must be initialized to the current state values (dof_state_values_)
832+
ASSERT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size());
833+
for (size_t i = 0; i < controller_->reference_interfaces_.size(); ++i)
834+
{
835+
EXPECT_EQ(controller_->reference_interfaces_[i], dof_state_values_[i]);
836+
}
837+
}
838+
839+
/**
840+
* @brief Test that reference interfaces remain NaN on activation when
841+
* set_current_state_as_first_setpoint is false.
842+
*/
843+
TEST_F(PidControllerTest, test_activate_set_current_state_as_first_setpoint_false)
844+
{
845+
SetUpController("test_pid_controller_no_first_setpoint");
846+
847+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
848+
ASSERT_FALSE(controller_->params_.set_current_state_as_first_setpoint);
849+
850+
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
851+
852+
// reference interfaces must remain NaN since set_current_state_as_first_setpoint is false
853+
ASSERT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size());
854+
for (const auto & interface : controller_->reference_interfaces_)
855+
{
856+
EXPECT_TRUE(std::isnan(interface));
857+
}
858+
}
859+
813860
int main(int argc, char ** argv)
814861
{
815862
::testing::InitGoogleTest(&argc, argv);

pid_controller/test/test_pid_controller.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,8 @@ class TestablePidController : public pid_controller::PidController
6767
FRIEND_TEST(PidControllerDualInterfaceTest, test_chained_feedforward_with_gain_dual_interface);
6868
FRIEND_TEST(PidControllerTest, test_save_i_term_on);
6969
FRIEND_TEST(PidControllerTest, test_save_i_term_off);
70+
FRIEND_TEST(PidControllerTest, test_activate_set_current_state_as_first_setpoint_true);
71+
FRIEND_TEST(PidControllerTest, test_activate_set_current_state_as_first_setpoint_false);
7072

7173
public:
7274
controller_interface::CallbackReturn on_configure(

0 commit comments

Comments
 (0)