Skip to content

Commit ae649a9

Browse files
authored
[pid_controller] Fix logic for feedforward_mode with single reference interface (backport #1520) (#1539)
1 parent 92c47bd commit ae649a9

File tree

4 files changed

+157
-8
lines changed

4 files changed

+157
-8
lines changed

pid_controller/src/pid_controller.cpp

+15-8
Original file line numberDiff line numberDiff line change
@@ -433,20 +433,27 @@ controller_interface::return_type PidController::update_and_write_commands(
433433

434434
for (size_t i = 0; i < dof_; ++i)
435435
{
436-
double tmp_command = std::numeric_limits<double>::quiet_NaN();
436+
double tmp_command = 0.0;
437437

438-
// Using feedforward
439438
if (!std::isnan(reference_interfaces_[i]) && !std::isnan(measured_state_values_[i]))
440439
{
441440
// calculate feed-forward
442441
if (*(control_mode_.readFromRT()) == feedforward_mode_type::ON)
443442
{
444-
tmp_command = reference_interfaces_[dof_ + i] *
445-
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;
446-
}
447-
else
448-
{
449-
tmp_command = 0.0;
443+
// two interfaces
444+
if (reference_interfaces_.size() == 2 * dof_ && measured_state_values_.size() == 2 * dof_)
445+
{
446+
if (std::isfinite(reference_interfaces_[dof_ + i]))
447+
{
448+
tmp_command = reference_interfaces_[dof_ + i] *
449+
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;
450+
}
451+
}
452+
else // one interface
453+
{
454+
tmp_command = reference_interfaces_[i] *
455+
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;
456+
}
450457
}
451458

452459
double error = reference_interfaces_[i] - measured_state_values_[i];

pid_controller/test/pid_controller_params.yaml

+13
Original file line numberDiff line numberDiff line change
@@ -9,3 +9,16 @@ test_pid_controller:
99

1010
gains:
1111
joint1: {p: 1.0, i: 2.0, d: 10.0, i_clamp_max: 5.0, i_clamp_min: -5.0}
12+
13+
14+
test_pid_controller_with_feedforward_gain:
15+
ros__parameters:
16+
dof_names:
17+
- joint1
18+
19+
command_interface: position
20+
21+
reference_and_state_interfaces: ["position"]
22+
23+
gains:
24+
joint1: {p: 0.5, i: 0.0, d: 0.0, i_clamp_max: 5.0, i_clamp_min: -5.0, feedforward_gain: 1.0}

pid_controller/test/test_pid_controller.cpp

+127
Original file line numberDiff line numberDiff line change
@@ -522,6 +522,133 @@ TEST_F(PidControllerTest, receive_message_and_publish_updated_status)
522522
}
523523
}
524524

525+
/**
526+
* @brief check chained pid controller with feedforward and gain as non-zero, single interface
527+
*/
528+
TEST_F(PidControllerTest, test_update_chained_feedforward_with_gain)
529+
{
530+
// state interface value is 1.1 as defined in test fixture
531+
// with p gain 0.5, the command value should be 0.5 * (5.0 - 1.1) = 1.95
532+
// with feedforward gain 1.0, the command value should be 1.95 + 1.0 * 5.0 = 6.95
533+
const double target_value = 5.0;
534+
const double expected_command_value = 6.95;
535+
536+
SetUpController("test_pid_controller_with_feedforward_gain");
537+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
538+
539+
// check on interfaces & pid gain parameters
540+
for (const auto & dof_name : dof_names_)
541+
{
542+
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].p, 0.5);
543+
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].feedforward_gain, 1.0);
544+
}
545+
ASSERT_EQ(controller_->params_.command_interface, command_interface_);
546+
EXPECT_THAT(
547+
controller_->params_.reference_and_state_interfaces,
548+
testing::ElementsAreArray(state_interfaces_));
549+
ASSERT_FALSE(controller_->params_.use_external_measured_states);
550+
551+
// setup executor
552+
rclcpp::executors::MultiThreadedExecutor executor;
553+
executor.add_node(controller_->get_node()->get_node_base_interface());
554+
executor.add_node(service_caller_node_->get_node_base_interface());
555+
556+
controller_->set_chained_mode(true);
557+
558+
// activate controller
559+
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
560+
ASSERT_TRUE(controller_->is_in_chained_mode());
561+
562+
// turn on feedforward
563+
controller_->control_mode_.writeFromNonRT(feedforward_mode_type::ON);
564+
ASSERT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::ON);
565+
566+
// send a message to update reference interface
567+
std::shared_ptr<ControllerCommandMsg> msg = std::make_shared<ControllerCommandMsg>();
568+
msg->dof_names = controller_->params_.dof_names;
569+
msg->values.resize(msg->dof_names.size(), 0.0);
570+
for (size_t i = 0; i < msg->dof_names.size(); ++i)
571+
{
572+
msg->values[i] = target_value;
573+
}
574+
msg->values_dot.resize(msg->dof_names.size(), std::numeric_limits<double>::quiet_NaN());
575+
controller_->input_ref_.writeFromNonRT(msg);
576+
ASSERT_EQ(
577+
controller_->update_reference_from_subscribers(), controller_interface::return_type::OK);
578+
579+
// run update
580+
ASSERT_EQ(
581+
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
582+
controller_interface::return_type::OK);
583+
584+
// check on result from update
585+
ASSERT_EQ(controller_->command_interfaces_[0].get_value(), expected_command_value);
586+
}
587+
588+
/**
589+
* @brief check chained pid controller with feedforward OFF and gain as non-zero, single interface
590+
*/
591+
TEST_F(PidControllerTest, test_update_chained_feedforward_off_with_gain)
592+
{
593+
// state interface value is 1.1 as defined in test fixture
594+
// given target value 5.0
595+
// with p gain 0.5, the command value should be 0.5 * (5.0 - 1.1) = 1.95
596+
// with feedforward off, the command value should be still 1.95 even though feedforward gain
597+
// is 1.0
598+
const double target_value = 5.0;
599+
const double expected_command_value = 1.95;
600+
601+
SetUpController("test_pid_controller_with_feedforward_gain");
602+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
603+
604+
// check on interfaces & pid gain parameters
605+
for (const auto & dof_name : dof_names_)
606+
{
607+
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].p, 0.5);
608+
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].feedforward_gain, 1.0);
609+
}
610+
ASSERT_EQ(controller_->params_.command_interface, command_interface_);
611+
EXPECT_THAT(
612+
controller_->params_.reference_and_state_interfaces,
613+
testing::ElementsAreArray(state_interfaces_));
614+
ASSERT_FALSE(controller_->params_.use_external_measured_states);
615+
616+
// setup executor
617+
rclcpp::executors::MultiThreadedExecutor executor;
618+
executor.add_node(controller_->get_node()->get_node_base_interface());
619+
executor.add_node(service_caller_node_->get_node_base_interface());
620+
621+
controller_->set_chained_mode(true);
622+
623+
// activate controller
624+
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
625+
ASSERT_TRUE(controller_->is_in_chained_mode());
626+
627+
// feedforward by default is OFF
628+
ASSERT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::OFF);
629+
630+
// send a message to update reference interface
631+
std::shared_ptr<ControllerCommandMsg> msg = std::make_shared<ControllerCommandMsg>();
632+
msg->dof_names = controller_->params_.dof_names;
633+
msg->values.resize(msg->dof_names.size(), 0.0);
634+
for (size_t i = 0; i < msg->dof_names.size(); ++i)
635+
{
636+
msg->values[i] = target_value;
637+
}
638+
msg->values_dot.resize(msg->dof_names.size(), std::numeric_limits<double>::quiet_NaN());
639+
controller_->input_ref_.writeFromNonRT(msg);
640+
ASSERT_EQ(
641+
controller_->update_reference_from_subscribers(), controller_interface::return_type::OK);
642+
643+
// run update
644+
ASSERT_EQ(
645+
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
646+
controller_interface::return_type::OK);
647+
648+
// check on result from update
649+
ASSERT_EQ(controller_->command_interfaces_[0].get_value(), expected_command_value);
650+
}
651+
525652
int main(int argc, char ** argv)
526653
{
527654
::testing::InitGoogleTest(&argc, argv);

pid_controller/test/test_pid_controller.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,8 @@ class TestablePidController : public pid_controller::PidController
6060
FRIEND_TEST(PidControllerTest, test_update_logic_chainable_feedforward_on);
6161
FRIEND_TEST(PidControllerTest, subscribe_and_get_messages_success);
6262
FRIEND_TEST(PidControllerTest, receive_message_and_publish_updated_status);
63+
FRIEND_TEST(PidControllerTest, test_update_chained_feedforward_with_gain);
64+
FRIEND_TEST(PidControllerTest, test_update_chained_feedforward_off_with_gain);
6365

6466
public:
6567
controller_interface::CallbackReturn on_configure(

0 commit comments

Comments
 (0)