From 5893df9d9eccb63699489663cdb1fb07c58da746 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 5 Jul 2022 04:08:57 +0100 Subject: [PATCH] AP_WindVane: params always use set method --- libraries/AP_WindVane/AP_WindVane.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_WindVane/AP_WindVane.cpp b/libraries/AP_WindVane/AP_WindVane.cpp index e92edc5381..8b5bfa10bf 100644 --- a/libraries/AP_WindVane/AP_WindVane.cpp +++ b/libraries/AP_WindVane/AP_WindVane.cpp @@ -383,7 +383,7 @@ void AP_WindVane::record_home_heading() bool AP_WindVane::start_direction_calibration() { if (enabled() && (_calibration == 0)) { - _calibration = 1; + _calibration.set(1); return true; } return false; @@ -393,7 +393,7 @@ bool AP_WindVane::start_direction_calibration() bool AP_WindVane::start_speed_calibration() { if (enabled() && (_calibration == 0)) { - _calibration = 2; + _calibration.set(2); return true; } return false;