Skip to content

Commit 0c03827

Browse files
Juliajchristophfroehlich
authored andcommitted
[pid_controller] Update tests (#1538)
1 parent ae649a9 commit 0c03827

File tree

6 files changed

+255
-120
lines changed

6 files changed

+255
-120
lines changed

pid_controller/CMakeLists.txt

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

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

pid_controller/src/pid_controller.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -411,6 +411,7 @@ controller_interface::return_type PidController::update_and_write_commands(
411411
// check for any parameter updates
412412
update_parameters();
413413

414+
// Update feedback either from external measured state or from state interfaces
414415
if (params_.use_external_measured_states)
415416
{
416417
const auto measured_state = *(measured_state_.readFromRT());
@@ -435,13 +436,13 @@ controller_interface::return_type PidController::update_and_write_commands(
435436
{
436437
double tmp_command = 0.0;
437438

438-
if (!std::isnan(reference_interfaces_[i]) && !std::isnan(measured_state_values_[i]))
439+
if (std::isfinite(reference_interfaces_[i]) && std::isfinite(measured_state_values_[i]))
439440
{
440441
// calculate feed-forward
441442
if (*(control_mode_.readFromRT()) == feedforward_mode_type::ON)
442443
{
443444
// two interfaces
444-
if (reference_interfaces_.size() == 2 * dof_ && measured_state_values_.size() == 2 * dof_)
445+
if (reference_interfaces_.size() == 2 * dof_)
445446
{
446447
if (std::isfinite(reference_interfaces_[dof_ + i]))
447448
{
@@ -468,8 +469,8 @@ controller_interface::return_type PidController::update_and_write_commands(
468469
if (reference_interfaces_.size() == 2 * dof_ && measured_state_values_.size() == 2 * dof_)
469470
{
470471
if (
471-
!std::isnan(reference_interfaces_[dof_ + i]) &&
472-
!std::isnan(measured_state_values_[dof_ + i]))
472+
std::isfinite(reference_interfaces_[dof_ + i]) &&
473+
std::isfinite(measured_state_values_[dof_ + i]))
473474
{
474475
// use calculation with 'error' and 'error_dot'
475476
tmp_command += pids_[i]->computeCommand(

pid_controller/test/pid_controller_params.yaml

Lines changed: 26 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,19 @@ 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_pid_controller_angle_wraparound_on:
14+
ros__parameters:
15+
dof_names:
16+
- joint1
17+
18+
command_interface: position
19+
20+
reference_and_state_interfaces: ["position"]
21+
22+
gains:
23+
joint1: {p: 1.0, i: 2.0, d: 3.0, i_clamp_max: 5.0, i_clamp_min: -5.0, angle_wraparound: true}
1324

1425
test_pid_controller_with_feedforward_gain:
1526
ros__parameters:
@@ -22,3 +33,17 @@ test_pid_controller_with_feedforward_gain:
2233

2334
gains:
2435
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}

0 commit comments

Comments
 (0)