Skip to content

Commit 79473e8

Browse files
Update test cases to accomodate for both values of exported_gain_references param
1 parent ff8db06 commit 79473e8

File tree

5 files changed

+45
-18
lines changed

5 files changed

+45
-18
lines changed

pid_controller/test/pid_controller_params.yaml

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ test_pid_controller_unlimited:
2828

2929
reference_and_state_interfaces: ["position"]
3030

31-
export_gain_references: false
31+
export_gain_references: true
3232

3333
gains:
3434
joint1: {p: 1.0, i: 2.0, d: 3.0}
@@ -42,7 +42,7 @@ test_pid_controller_angle_wraparound_on:
4242

4343
reference_and_state_interfaces: ["position"]
4444

45-
export_gain_references: false
45+
export_gain_references: true
4646

4747
gains:
4848
joint1: {p: 1.0, i: 2.0, d: 3.0, angle_wraparound: true}
@@ -56,7 +56,7 @@ test_pid_controller_with_feedforward_gain:
5656

5757
reference_and_state_interfaces: ["position"]
5858

59-
export_gain_references: false
59+
export_gain_references: true
6060

6161
gains:
6262
joint1: {p: 0.5, i: 0.0, d: 0.0, feedforward_gain: 1.0}
@@ -71,7 +71,7 @@ test_pid_controller_with_feedforward_gain_dual_interface:
7171

7272
reference_and_state_interfaces: ["position", "velocity"]
7373

74-
export_gain_references: false
74+
export_gain_references: true
7575

7676
gains:
7777
joint1: {p: 0.5, i: 0.3, d: 0.4, feedforward_gain: 1.0}
@@ -100,7 +100,7 @@ test_save_i_term_on:
100100

101101
reference_and_state_interfaces: ["position"]
102102

103-
export_gain_references: false
103+
export_gain_references: true
104104

105105
gains:
106106
joint1: {p: 1.0, i: 2.0, d: 3.0, save_i_term: true}

pid_controller/test/pid_controller_preceding_params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,4 +10,4 @@ test_pid_controller:
1010
reference_and_state_dof_names:
1111
- joint1state
1212

13-
export_gain_references: false
13+
export_gain_references: true

pid_controller/test/test_pid_controller.cpp

Lines changed: 33 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,11 @@ TEST_F(PidControllerTest, check_exported_interfaces)
8585

8686
// check ref itfs
8787
auto ref_if_conf = controller_->export_reference_interfaces();
88-
ASSERT_EQ(ref_if_conf.size(), dof_state_values_.size());
88+
size_t expected_ref_size = dof_names_.size() * state_interfaces_.size() +
89+
(controller_->params_.export_gain_references
90+
? dof_names_.size() * controller_->GAIN_INTERFACES.size()
91+
: 0);
92+
ASSERT_EQ(ref_if_conf.size(), expected_ref_size);
8993
size_t ri_index = 0;
9094
for (const auto & interface : state_interfaces_)
9195
{
@@ -141,8 +145,11 @@ TEST_F(PidControllerTest, activate_success)
141145
{
142146
EXPECT_TRUE(std::isnan(cmd));
143147
}
144-
145-
EXPECT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size());
148+
size_t expected_ref_size = dof_names_.size() * state_interfaces_.size() +
149+
(controller_->params_.export_gain_references
150+
? dof_names_.size() * controller_->GAIN_INTERFACES.size()
151+
: 0);
152+
EXPECT_EQ(controller_->reference_interfaces_.size(), expected_ref_size);
146153
for (const auto & interface : controller_->reference_interfaces_)
147154
{
148155
EXPECT_TRUE(std::isnan(interface));
@@ -226,10 +233,12 @@ TEST_F(PidControllerTest, test_update_logic_zero_feedforward_gain)
226233
ASSERT_EQ(
227234
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
228235
controller_interface::return_type::OK);
229-
230-
EXPECT_EQ(
231-
controller_->reference_interfaces_.size(), dof_names_.size() * state_interfaces_.size());
232-
EXPECT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size());
236+
size_t expected_ref_size = dof_names_.size() * state_interfaces_.size() +
237+
(controller_->params_.export_gain_references
238+
? dof_names_.size() * controller_->GAIN_INTERFACES.size()
239+
: 0);
240+
EXPECT_EQ(controller_->reference_interfaces_.size(), expected_ref_size);
241+
EXPECT_EQ(controller_->reference_interfaces_.size(), expected_ref_size);
233242
for (size_t i = 0; i < dof_command_values_.size(); ++i)
234243
{
235244
EXPECT_TRUE(std::isnan(controller_->input_ref_.get().values[i]));
@@ -284,10 +293,13 @@ TEST_F(PidControllerTest, test_update_logic_chainable_not_use_subscriber_update)
284293
controller_interface::return_type::OK);
285294

286295
ASSERT_TRUE(controller_->is_in_chained_mode());
296+
size_t expected_ref_size = dof_names_.size() * state_interfaces_.size() +
297+
(controller_->params_.export_gain_references
298+
? dof_names_.size() * controller_->GAIN_INTERFACES.size()
299+
: 0);
287300

288-
EXPECT_EQ(
289-
controller_->reference_interfaces_.size(), dof_names_.size() * state_interfaces_.size());
290-
EXPECT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size());
301+
EXPECT_EQ(controller_->reference_interfaces_.size(), expected_ref_size);
302+
EXPECT_EQ(controller_->reference_interfaces_.size(), expected_ref_size);
291303

292304
// check the command value
293305
// ref = 5.0, state = 1.1, ds = 0.01, p_gain = 1.0, i_gain = 2.0, d_gain = 3.0
@@ -435,10 +447,20 @@ TEST_F(PidControllerTest, receive_message_and_publish_updated_status)
435447
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
436448
controller_interface::return_type::OK);
437449

438-
for (size_t i = 0; i < controller_->reference_interfaces_.size(); ++i)
450+
size_t num_control_references = dof_names_.size() * state_interfaces_.size();
451+
452+
for (size_t i = 0; i < num_control_references; ++i)
439453
{
440454
ASSERT_EQ(controller_->reference_interfaces_[i], 0.45);
441455
}
456+
if (controller_->params_.export_gain_references)
457+
{
458+
for (size_t i = num_control_references; i < controller_->reference_interfaces_.size(); ++i)
459+
{
460+
// Check the remaining interfaces (P, I, D gains) are NaN
461+
EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i]));
462+
}
463+
}
442464

443465
subscribe_and_get_messages(msg);
444466

pid_controller/test/test_pid_controller.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@ constexpr auto NODE_ERROR = controller_interface::CallbackReturn::ERROR;
5151
class TestablePidController : public pid_controller::PidController
5252
{
5353
FRIEND_TEST(PidControllerTest, all_parameters_set_configure_success);
54+
FRIEND_TEST(PidControllerTest, check_exported_interfaces);
5455
FRIEND_TEST(PidControllerTest, activate_success);
5556
FRIEND_TEST(PidControllerTest, reactivate_success);
5657
FRIEND_TEST(PidControllerTest, test_update_logic_zero_feedforward_gain);

pid_controller/test/test_pid_controller_preceding.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,11 @@ TEST_F(PidControllerTest, check_exported_interfaces)
7474

7575
// check ref itfs
7676
auto ref_if_conf = controller_->export_reference_interfaces();
77-
ASSERT_EQ(ref_if_conf.size(), dof_state_values_.size());
77+
size_t expected_ref_size = dof_names_.size() * state_interfaces_.size() +
78+
(controller_->params_.export_gain_references
79+
? dof_names_.size() * controller_->GAIN_INTERFACES.size()
80+
: 0);
81+
ASSERT_EQ(ref_if_conf.size(), expected_ref_size);
7882
size_t ri_index = 0;
7983
for (const auto & interface : state_interfaces_)
8084
{

0 commit comments

Comments
 (0)