From 4fa0bcaa91ce22d5b5357237af02422ca054fa21 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 5 Jul 2022 04:08:56 +0100 Subject: [PATCH] AP_Baro: params always use set method --- libraries/AP_Baro/AP_Baro.cpp | 2 +- libraries/AP_Baro/AP_Baro.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 47d366bd70..c0120c8a8e 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -885,7 +885,7 @@ void AP_Baro::update(void) // update altitude calculation float ground_pressure = sensors[i].ground_pressure; if (!is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) { - sensors[i].ground_pressure = sensors[i].pressure; + sensors[i].ground_pressure.set(sensors[i].pressure); } float altitude = sensors[i].altitude; float corrected_pressure = sensors[i].pressure + sensors[i].p_correction; diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index 2aba959055..e94fa07d92 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -173,7 +173,7 @@ public: uint8_t num_instances(void) const { return _num_sensors; } // set baro drift amount - void set_baro_drift_altitude(float alt) { _alt_offset = alt; } + void set_baro_drift_altitude(float alt) { _alt_offset.set(alt); } // get baro drift amount float get_baro_drift_offset(void) const { return _alt_offset_active; }