APM_Control: params always use set method

This commit is contained in:
Iampete1 2022-07-05 04:08:56 +01:00 committed by Peter Hall
parent ac1b8ab7be
commit 6875ef17a0
2 changed files with 2 additions and 2 deletions

View File

@ -235,7 +235,7 @@ int32_t AP_SteerController::get_steering_out_lat_accel(float desired_accel)
int32_t AP_SteerController::get_steering_out_angle_error(int32_t angle_err)
{
if (_tau < 0.1f) {
_tau = 0.1f;
_tau.set(0.1f);
}
// Calculate the desired steering rate (deg/sec) from the angle error

View File

@ -354,7 +354,7 @@ void AP_YawController::autotune_start(void)
{
if (autotune == nullptr && rate_control_enabled()) {
// the autotuner needs a time constant. Use an assumed tconst of 0.5
gains.tau = 0.5;
gains.tau.set(0.5);
gains.rmax_pos.set(90);
autotune = new AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_YAW, aparm, rate_pid);