Skip to content

Commit 53dce5c

Browse files
Use explicit type const double instead of auto
1 parent 45fdcd5 commit 53dce5c

File tree

1 file changed

+3
-4
lines changed

1 file changed

+3
-4
lines changed

pid_controller/test/test_pid_controller.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -675,7 +675,7 @@ TEST_F(PidControllerTest, test_save_i_term_off)
675675
// error = ref - state = 100.001, error_dot = error/ds = 10000.1,
676676
// p_term = 100.001 * 1, i_term = 1.00001 * 2 = 2.00002, d_term = error/ds = 10000.1 * 3
677677
// feedforward OFF -> cmd = p_term + i_term + d_term = 30102.3
678-
auto expected_command_value = 30102.30102;
678+
const double expected_command_value = 30102.30102;
679679

680680
double actual_value = std::round(controller_->command_interfaces_[0].get_value() * 1e5) / 1e5;
681681
EXPECT_NEAR(actual_value, expected_command_value, 1e-5);
@@ -725,7 +725,7 @@ TEST_F(PidControllerTest, test_save_i_term_on)
725725
// error = ref - state = 100.001, error_dot = error/ds = 10000.1,
726726
// p_term = 100.001 * 1, i_term = 1.00001 * 2 = 2.00002, d_term = error/ds = 10000.1 * 3
727727
// feedforward OFF -> cmd = p_term + i_term + d_term = 30102.3
728-
auto expected_command_value = 30102.30102;
728+
const double expected_command_value = 30102.30102;
729729

730730
double actual_value = std::round(controller_->command_interfaces_[0].get_value() * 1e5) / 1e5;
731731
EXPECT_NEAR(actual_value, expected_command_value, 1e-5);
@@ -740,9 +740,8 @@ TEST_F(PidControllerTest, test_save_i_term_on)
740740
ASSERT_EQ(
741741
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
742742
controller_interface::return_type::OK);
743-
expected_command_value = 2.00002; // i_term from above
744743
actual_value = std::round(controller_->command_interfaces_[0].get_value() * 1e5) / 1e5;
745-
EXPECT_NEAR(actual_value, expected_command_value, 1e-5);
744+
EXPECT_NEAR(actual_value, 2.00002, 1e-5); // i_term from above
746745
}
747746

748747
int main(int argc, char ** argv)

0 commit comments

Comments
 (0)