AP_WindVane: params always use set method

This commit is contained in:
Iampete1 2022-07-05 04:08:57 +01:00 committed by Peter Hall
parent 0ef78c2f8b
commit 5893df9d9e
1 changed files with 2 additions and 2 deletions

View File

@ -383,7 +383,7 @@ void AP_WindVane::record_home_heading()
bool AP_WindVane::start_direction_calibration() bool AP_WindVane::start_direction_calibration()
{ {
if (enabled() && (_calibration == 0)) { if (enabled() && (_calibration == 0)) {
_calibration = 1; _calibration.set(1);
return true; return true;
} }
return false; return false;
@ -393,7 +393,7 @@ bool AP_WindVane::start_direction_calibration()
bool AP_WindVane::start_speed_calibration() bool AP_WindVane::start_speed_calibration()
{ {
if (enabled() && (_calibration == 0)) { if (enabled() && (_calibration == 0)) {
_calibration = 2; _calibration.set(2);
return true; return true;
} }
return false; return false;