Skip to content

Commit db7433c

Browse files
committed
Add test case for chained pid controller with non zero feedforward gain
1 parent b1450e7 commit db7433c

File tree

4 files changed

+80
-4
lines changed

4 files changed

+80
-4
lines changed

pid_controller/src/pid_controller.cpp

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -500,7 +500,6 @@ controller_interface::return_type PidController::update_and_write_commands(
500500
{
501501
double tmp_command = 0.0;
502502

503-
// Using feedforward
504503
if (!std::isnan(reference_interfaces_[i]) && !std::isnan(measured_state_values_[i]))
505504
{
506505
// calculate feed-forward
@@ -509,9 +508,7 @@ controller_interface::return_type PidController::update_and_write_commands(
509508
// two interfaces
510509
if (reference_interfaces_.size() == 2 * dof_ && measured_state_values_.size() == 2 * dof_)
511510
{
512-
if (
513-
std::isfinite(reference_interfaces_[dof_ + i]) &&
514-
std::isfinite(measured_state_values_[dof_ + i]))
511+
if (std::isfinite(reference_interfaces_[dof_ + i]))
515512
{
516513
tmp_command = reference_interfaces_[dof_ + i] *
517514
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;

pid_controller/test/pid_controller_params.yaml

Lines changed: 13 additions & 0 deletions
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

Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -521,6 +521,71 @@ TEST_F(PidControllerTest, receive_message_and_publish_updated_status)
521521
}
522522
}
523523

524+
/**
525+
* @brief check chained pid controller with feedforward and gain as non-zero, single interface
526+
*/
527+
TEST_F(PidControllerTest, test_update_chained_feedforward_with_gain)
528+
{
529+
// state interface value is 1.1 as defined in test fixture
530+
// with p gain 0.5, the command value should be 0.5 * (5.0 - 1.1) = 1.95
531+
// with feedforward gain 1.0, the command value should be 1.95 + 1.0 * 5.0 = 6.95
532+
auto target_value = 5.0;
533+
auto exepected_command_value = 6.95;
534+
535+
SetUpController("test_pid_controller_with_feedforward_gain");
536+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
537+
538+
// check on interfaces & pid gain parameters
539+
for (const auto & dof_name : dof_names_)
540+
{
541+
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].p, 0.5);
542+
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].feedforward_gain, 1.0);
543+
}
544+
ASSERT_EQ(controller_->params_.command_interface, command_interface_);
545+
EXPECT_THAT(
546+
controller_->params_.reference_and_state_interfaces,
547+
testing::ElementsAreArray(state_interfaces_));
548+
ASSERT_FALSE(controller_->params_.use_external_measured_states);
549+
550+
// setup executor
551+
rclcpp::executors::MultiThreadedExecutor executor;
552+
executor.add_node(controller_->get_node()->get_node_base_interface());
553+
executor.add_node(service_caller_node_->get_node_base_interface());
554+
555+
controller_->set_chained_mode(true);
556+
557+
// activate controller
558+
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
559+
ASSERT_TRUE(controller_->is_in_chained_mode());
560+
561+
// turn on feedforward
562+
controller_->control_mode_.writeFromNonRT(feedforward_mode_type::ON);
563+
ASSERT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::ON);
564+
565+
// send a message to update reference interface
566+
std::shared_ptr<ControllerCommandMsg> msg = std::make_shared<ControllerCommandMsg>();
567+
msg->dof_names = controller_->params_.dof_names;
568+
msg->values.resize(msg->dof_names.size(), 0.0);
569+
for (size_t i = 0; i < msg->dof_names.size(); ++i)
570+
{
571+
msg->values[i] = target_value;
572+
}
573+
msg->values_dot.resize(msg->dof_names.size(), std::numeric_limits<double>::quiet_NaN());
574+
controller_->input_ref_.writeFromNonRT(msg);
575+
ASSERT_EQ(
576+
controller_->update_reference_from_subscribers(
577+
rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
578+
controller_interface::return_type::OK);
579+
580+
// run update
581+
ASSERT_EQ(
582+
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
583+
controller_interface::return_type::OK);
584+
585+
// check on result from update
586+
ASSERT_EQ(controller_->command_interfaces_[0].get_value(), exepected_command_value);
587+
}
588+
524589
int main(int argc, char ** argv)
525590
{
526591
::testing::InitGoogleTest(&argc, argv);

pid_controller/test/test_pid_controller.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,7 @@ class TestablePidController : public pid_controller::PidController
5959
FRIEND_TEST(PidControllerTest, test_update_logic_chainable_feedforward_on);
6060
FRIEND_TEST(PidControllerTest, subscribe_and_get_messages_success);
6161
FRIEND_TEST(PidControllerTest, receive_message_and_publish_updated_status);
62+
FRIEND_TEST(PidControllerTest, test_update_chained_feedforward_with_gain);
6263

6364
public:
6465
controller_interface::CallbackReturn on_configure(

0 commit comments

Comments
 (0)