Skip to content

Commit b24b310

Browse files
authored
[pid_controller] Update tests (#1538)
1 parent 623dc5d commit b24b310

File tree

6 files changed

+277
-169
lines changed

6 files changed

+277
-169
lines changed

pid_controller/CMakeLists.txt

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,19 @@ if(BUILD_TESTING)
9292
hardware_interface
9393
)
9494

95+
add_rostest_with_parameters_gmock(
96+
test_pid_controller_dual_interface
97+
test/test_pid_controller_dual_interface.cpp
98+
${CMAKE_CURRENT_SOURCE_DIR}/test/pid_controller_params.yaml
99+
)
100+
target_include_directories(test_pid_controller_dual_interface PRIVATE include)
101+
target_link_libraries(test_pid_controller_dual_interface pid_controller)
102+
ament_target_dependencies(
103+
test_pid_controller_dual_interface
104+
controller_interface
105+
hardware_interface
106+
)
107+
95108
ament_add_gmock(test_load_pid_controller test/test_load_pid_controller.cpp)
96109
target_include_directories(test_load_pid_controller PRIVATE include)
97110
ament_target_dependencies(

pid_controller/src/pid_controller.cpp

Lines changed: 13 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -477,6 +477,7 @@ controller_interface::return_type PidController::update_and_write_commands(
477477
// check for any parameter updates
478478
update_parameters();
479479

480+
// Update feedback either from external measured state or from state interfaces
480481
if (params_.use_external_measured_states)
481482
{
482483
const auto measured_state = *(measured_state_.readFromRT());
@@ -503,17 +504,18 @@ controller_interface::return_type PidController::update_and_write_commands(
503504
state_interfaces_values_[i] = measured_state_values_[i];
504505
}
505506

507+
// Iterate through all the dofs to calculate the output command
506508
for (size_t i = 0; i < dof_; ++i)
507509
{
508510
double tmp_command = 0.0;
509511

510-
if (!std::isnan(reference_interfaces_[i]) && !std::isnan(measured_state_values_[i]))
512+
if (std::isfinite(reference_interfaces_[i]) && std::isfinite(measured_state_values_[i]))
511513
{
512514
// calculate feed-forward
513515
if (*(control_mode_.readFromRT()) == feedforward_mode_type::ON)
514516
{
515517
// two interfaces
516-
if (reference_interfaces_.size() == 2 * dof_ && measured_state_values_.size() == 2 * dof_)
518+
if (reference_interfaces_.size() == 2 * dof_)
517519
{
518520
if (std::isfinite(reference_interfaces_[dof_ + i]))
519521
{
@@ -540,8 +542,8 @@ controller_interface::return_type PidController::update_and_write_commands(
540542
if (reference_interfaces_.size() == 2 * dof_ && measured_state_values_.size() == 2 * dof_)
541543
{
542544
if (
543-
!std::isnan(reference_interfaces_[dof_ + i]) &&
544-
!std::isnan(measured_state_values_[dof_ + i]))
545+
std::isfinite(reference_interfaces_[dof_ + i]) &&
546+
std::isfinite(measured_state_values_[dof_ + i]))
545547
{
546548
// use calculation with 'error' and 'error_dot'
547549
tmp_command += pids_[i]->compute_command(
@@ -560,7 +562,13 @@ controller_interface::return_type PidController::update_and_write_commands(
560562
}
561563

562564
// write calculated values
563-
command_interfaces_[i].set_value(tmp_command);
565+
auto success = command_interfaces_[i].set_value(tmp_command);
566+
if (!success)
567+
{
568+
RCLCPP_ERROR(
569+
get_node()->get_logger(), "Failed to set command value for %s",
570+
command_interfaces_[i].get_name().c_str());
571+
}
564572
}
565573
}
566574

pid_controller/test/pid_controller_params.yaml

Lines changed: 32 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -8,9 +8,9 @@ test_pid_controller:
88
reference_and_state_interfaces: ["position"]
99

1010
gains:
11-
joint1: {p: 1.0, i: 2.0, d: 10.0, i_clamp_max: 5.0, i_clamp_min: -5.0}
11+
joint1: {p: 1.0, i: 2.0, d: 3.0, i_clamp_max: 5.0, i_clamp_min: -5.0}
1212

13-
test_save_i_term_off:
13+
test_pid_controller_angle_wraparound_on:
1414
ros__parameters:
1515
dof_names:
1616
- joint1
@@ -20,10 +20,35 @@ test_save_i_term_off:
2020
reference_and_state_interfaces: ["position"]
2121

2222
gains:
23-
joint1: {p: 1.0, i: 2.0, d: 3.0, i_clamp_max: 5.0, i_clamp_min: -5.0, save_i_term: false}
23+
joint1: {p: 1.0, i: 2.0, d: 3.0, i_clamp_max: 5.0, i_clamp_min: -5.0, angle_wraparound: true}
2424

25+
test_pid_controller_with_feedforward_gain:
26+
ros__parameters:
27+
dof_names:
28+
- joint1
2529

26-
test_save_i_term_on:
30+
command_interface: position
31+
32+
reference_and_state_interfaces: ["position"]
33+
34+
gains:
35+
joint1: {p: 0.5, i: 0.0, d: 0.0, i_clamp_max: 5.0, i_clamp_min: -5.0, feedforward_gain: 1.0}
36+
37+
test_pid_controller_with_feedforward_gain_dual_interface:
38+
ros__parameters:
39+
dof_names:
40+
- joint1
41+
- joint2
42+
43+
command_interface: velocity
44+
45+
reference_and_state_interfaces: ["position", "velocity"]
46+
47+
gains:
48+
joint1: {p: 0.5, i: 0.3, d: 0.4, i_clamp_max: 5.0, i_clamp_min: -5.0, feedforward_gain: 1.0}
49+
joint2: {p: 0.5, i: 0.3, d: 0.4, i_clamp_max: 5.0, i_clamp_min: -5.0, feedforward_gain: 1.0}
50+
51+
test_save_i_term_off:
2752
ros__parameters:
2853
dof_names:
2954
- joint1
@@ -33,9 +58,9 @@ test_save_i_term_on:
3358
reference_and_state_interfaces: ["position"]
3459

3560
gains:
36-
joint1: {p: 1.0, i: 2.0, d: 3.0, i_clamp_max: 5.0, i_clamp_min: -5.0, save_i_term: true}
61+
joint1: {p: 1.0, i: 2.0, d: 3.0, i_clamp_max: 5.0, i_clamp_min: -5.0, save_i_term: false}
3762

38-
test_pid_controller_with_feedforward_gain:
63+
test_save_i_term_on:
3964
ros__parameters:
4065
dof_names:
4166
- joint1
@@ -45,4 +70,4 @@ test_pid_controller_with_feedforward_gain:
4570
reference_and_state_interfaces: ["position"]
4671

4772
gains:
48-
joint1: {p: 0.5, i: 0.0, d: 0.0, i_clamp_max: 5.0, i_clamp_min: -5.0, feedforward_gain: 1.0}
73+
joint1: {p: 1.0, i: 2.0, d: 3.0, i_clamp_max: 5.0, i_clamp_min: -5.0, save_i_term: true}

0 commit comments

Comments
 (0)