Skip to content

Commit 5b70746

Browse files
Add gain references inside new key to pass abi check
1 parent 7304887 commit 5b70746

File tree

6 files changed

+32
-23
lines changed

6 files changed

+32
-23
lines changed

pid_controller/src/pid_controller.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -349,7 +349,7 @@ std::vector<hardware_interface::CommandInterface> PidController::on_export_refer
349349
const size_t dof_reference_size = dof_ * params_.reference_and_state_interfaces.size();
350350

351351
size_t total_reference_size = dof_reference_size;
352-
if (params_.export_gain_references)
352+
if (params_.export_params.gain_references)
353353
{
354354
total_reference_size += dof_ * GAIN_INTERFACES.size();
355355
}
@@ -370,7 +370,7 @@ std::vector<hardware_interface::CommandInterface> PidController::on_export_refer
370370
}
371371
}
372372

373-
if (params_.export_gain_references)
373+
if (params_.export_params.gain_references)
374374
{
375375
size_t gains_start_index = dof_reference_size;
376376
for (const auto & gain_name : GAIN_INTERFACES)
@@ -520,7 +520,7 @@ controller_interface::return_type PidController::update_and_write_commands(
520520
// Calculate size of DOF references for indexing
521521
const size_t dof_reference_size = dof_ * params_.reference_and_state_interfaces.size();
522522

523-
if (params_.export_gain_references)
523+
if (params_.export_params.gain_references)
524524
{
525525
size_t gains_start_index = dof_reference_size;
526526
for (size_t i = 0; i < dof_; ++i)

pid_controller/src/pid_controller.yaml

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -126,9 +126,10 @@ pid_controller:
126126
default_value: false,
127127
description: "Individual state publisher activation for each DOF. If true, the controller will publish the state of each DOF to the topic `/<controller_name>/<dof_name>/pid_state`."
128128
}
129-
export_gain_references: {
130-
type: bool,
131-
default_value: false,
132-
description: "If true, exports P, I, D gains as reference interfaces to be claimed by preceding controllers",
133-
read_only: true
134-
}
129+
export_params:
130+
gain_references: {
131+
type: bool,
132+
default_value: false,
133+
description: "If true, exports P, I, D gains as reference interfaces to be claimed by preceding controllers",
134+
read_only: true
135+
}

pid_controller/test/pid_controller_params.yaml

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

1515
reference_and_state_interfaces: ["position"]
1616

17-
export_gain_references: false
17+
export_params:
18+
gain_references: true
1819

1920
gains:
2021
joint1: {p: 1.0, i: 2.0, d: 3.0, u_clamp_max: 5.0, u_clamp_min: -5.0}
@@ -28,7 +29,8 @@ test_pid_controller_unlimited:
2829

2930
reference_and_state_interfaces: ["position"]
3031

31-
export_gain_references: true
32+
export_params:
33+
gain_references: true
3234

3335
gains:
3436
joint1: {p: 1.0, i: 2.0, d: 3.0}
@@ -42,7 +44,8 @@ test_pid_controller_angle_wraparound_on:
4244

4345
reference_and_state_interfaces: ["position"]
4446

45-
export_gain_references: true
47+
export_params:
48+
gain_references: false
4649

4750
gains:
4851
joint1: {p: 1.0, i: 2.0, d: 3.0, angle_wraparound: true}
@@ -56,7 +59,8 @@ test_pid_controller_with_feedforward_gain:
5659

5760
reference_and_state_interfaces: ["position"]
5861

59-
export_gain_references: true
62+
export_params:
63+
gain_references: true
6064

6165
gains:
6266
joint1: {p: 0.5, i: 0.0, d: 0.0, feedforward_gain: 1.0}
@@ -71,7 +75,8 @@ test_pid_controller_with_feedforward_gain_dual_interface:
7175

7276
reference_and_state_interfaces: ["position", "velocity"]
7377

74-
export_gain_references: true
78+
export_params:
79+
gain_references: true
7580

7681
gains:
7782
joint1: {p: 0.5, i: 0.3, d: 0.4, feedforward_gain: 1.0}
@@ -86,7 +91,8 @@ test_save_i_term_off:
8691

8792
reference_and_state_interfaces: ["position"]
8893

89-
export_gain_references: false
94+
export_params:
95+
gain_references: false
9096

9197
gains:
9298
joint1: {p: 1.0, i: 2.0, d: 3.0, save_i_term: false}
@@ -100,7 +106,8 @@ test_save_i_term_on:
100106

101107
reference_and_state_interfaces: ["position"]
102108

103-
export_gain_references: true
109+
export_params:
110+
gain_references: true
104111

105112
gains:
106113
joint1: {p: 1.0, i: 2.0, d: 3.0, save_i_term: true}

pid_controller/test/pid_controller_preceding_params.yaml

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

13-
export_gain_references: true
13+
export_params:
14+
gain_references: true

pid_controller/test/test_pid_controller.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ TEST_F(PidControllerTest, check_exported_interfaces)
8686
// check ref itfs
8787
auto ref_if_conf = controller_->export_reference_interfaces();
8888
size_t expected_ref_size = dof_names_.size() * state_interfaces_.size() +
89-
(controller_->params_.export_gain_references
89+
(controller_->params_.export_params.gain_references
9090
? dof_names_.size() * controller_->GAIN_INTERFACES.size()
9191
: 0);
9292
ASSERT_EQ(ref_if_conf.size(), expected_ref_size);
@@ -146,7 +146,7 @@ TEST_F(PidControllerTest, activate_success)
146146
EXPECT_TRUE(std::isnan(cmd));
147147
}
148148
size_t expected_ref_size = dof_names_.size() * state_interfaces_.size() +
149-
(controller_->params_.export_gain_references
149+
(controller_->params_.export_params.gain_references
150150
? dof_names_.size() * controller_->GAIN_INTERFACES.size()
151151
: 0);
152152
EXPECT_EQ(controller_->reference_interfaces_.size(), expected_ref_size);
@@ -234,7 +234,7 @@ TEST_F(PidControllerTest, test_update_logic_zero_feedforward_gain)
234234
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
235235
controller_interface::return_type::OK);
236236
size_t expected_ref_size = dof_names_.size() * state_interfaces_.size() +
237-
(controller_->params_.export_gain_references
237+
(controller_->params_.export_params.gain_references
238238
? dof_names_.size() * controller_->GAIN_INTERFACES.size()
239239
: 0);
240240
EXPECT_EQ(controller_->reference_interfaces_.size(), expected_ref_size);
@@ -294,7 +294,7 @@ TEST_F(PidControllerTest, test_update_logic_chainable_not_use_subscriber_update)
294294

295295
ASSERT_TRUE(controller_->is_in_chained_mode());
296296
size_t expected_ref_size = dof_names_.size() * state_interfaces_.size() +
297-
(controller_->params_.export_gain_references
297+
(controller_->params_.export_params.gain_references
298298
? dof_names_.size() * controller_->GAIN_INTERFACES.size()
299299
: 0);
300300

@@ -453,7 +453,7 @@ TEST_F(PidControllerTest, receive_message_and_publish_updated_status)
453453
{
454454
ASSERT_EQ(controller_->reference_interfaces_[i], 0.45);
455455
}
456-
if (controller_->params_.export_gain_references)
456+
if (controller_->params_.export_params.gain_references)
457457
{
458458
for (size_t i = num_control_references; i < controller_->reference_interfaces_.size(); ++i)
459459
{

pid_controller/test/test_pid_controller_preceding.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ TEST_F(PidControllerTest, check_exported_interfaces)
7575
// check ref itfs
7676
auto ref_if_conf = controller_->export_reference_interfaces();
7777
size_t expected_ref_size = dof_names_.size() * state_interfaces_.size() +
78-
(controller_->params_.export_gain_references
78+
(controller_->params_.export_params.gain_references
7979
? dof_names_.size() * controller_->GAIN_INTERFACES.size()
8080
: 0);
8181
ASSERT_EQ(ref_if_conf.size(), expected_ref_size);

0 commit comments

Comments
 (0)