@@ -279,7 +279,7 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_off)
279
279
// error = ref - state = 100.001, error_dot = error/ds = 10000.1,
280
280
// p_term = 100.001 * 1, i_term = 1.00001 * 2 = 2.00002, d_term = error/ds = 10000.1 * 3
281
281
// feedforward OFF -> cmd = p_term + i_term + d_term = 30102.3
282
- auto expected_command_value = 30102.30102 ;
282
+ const double expected_command_value = 30102.30102 ;
283
283
284
284
double actual_value = std::round (controller_->command_interfaces_ [0 ].get_value () * 1e5 ) / 1e5 ;
285
285
EXPECT_NEAR (actual_value, expected_command_value, 1e-5 );
@@ -346,7 +346,7 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_on_with_zero_feedforward
346
346
// p_term = 100.001 * 1, i_term = 1.00001 * 2 = 2.00002, d_term = error/ds = 10000.1 * 3
347
347
// feedforward ON, feedforward_gain = 0
348
348
// -> cmd = p_term + i_term + d_term + feedforward_gain * ref = 30102.3 + 0 * 101.101 = 30102.3
349
- auto expected_command_value = 30102.301020 ;
349
+ const double expected_command_value = 30102.301020 ;
350
350
351
351
double actual_value = std::round (controller_->command_interfaces_ [0 ].get_value () * 1e5 ) / 1e5 ;
352
352
EXPECT_NEAR (actual_value, expected_command_value, 1e-5 );
@@ -375,7 +375,7 @@ TEST_F(PidControllerTest, test_update_logic_chainable_not_use_subscriber_update)
375
375
EXPECT_EQ (*(controller_->control_mode_ .readFromRT ()), feedforward_mode_type::OFF);
376
376
377
377
// update reference interface which will be used for calculation
378
- auto ref_interface_value = 5.0 ;
378
+ const double ref_interface_value = 5.0 ;
379
379
controller_->reference_interfaces_ [0 ] = ref_interface_value;
380
380
381
381
// publish a command message which should be ignored as chain mode is on
@@ -403,7 +403,7 @@ TEST_F(PidControllerTest, test_update_logic_chainable_not_use_subscriber_update)
403
403
// i_term = error * ds * i_gain = 3.9 * 0.01 * 2.0 = 0.078,
404
404
// d_term = error_dot * d_gain = 390.0 * 3.0 = 1170.0
405
405
// feedforward OFF -> cmd = p_term + i_term + d_term = 3.9 + 0.078 + 1170.0 = 1173.978
406
- auto expected_command_value = 1173.978 ;
406
+ const double expected_command_value = 1173.978 ;
407
407
408
408
EXPECT_EQ (controller_->command_interfaces_ [0 ].get_value (), expected_command_value);
409
409
}
@@ -431,7 +431,7 @@ TEST_F(PidControllerTest, test_update_logic_angle_wraparound_off)
431
431
controller_interface::return_type::OK);
432
432
433
433
// check the result of the commands - the values are not wrapped
434
- auto expected_command_value = 2679.078 ;
434
+ const double expected_command_value = 2679.078 ;
435
435
EXPECT_NEAR (controller_->command_interfaces_ [0 ].get_value (), expected_command_value, 1e-5 );
436
436
}
437
437
@@ -462,7 +462,7 @@ TEST_F(PidControllerTest, test_update_logic_angle_wraparound_on)
462
462
controller_interface::return_type::OK);
463
463
464
464
// Check the command value
465
- auto expected_command_value = 787.713559 ;
465
+ const double expected_command_value = 787.713559 ;
466
466
EXPECT_NEAR (controller_->command_interfaces_ [0 ].get_value (), expected_command_value, 1e-5 );
467
467
}
468
468
0 commit comments