diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 10daf11fe4..9d00830af0 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -118,6 +118,17 @@ void AP_Baro::calibrate() _ground_temperature.set_and_save(ground_temperature); } +/** + update the barometer calibration + this updates the baro ground calibration to the current values. It + can be used before arming to keep the baro well calibrated +*/ +void AP_Baro::update_calibration() +{ + _ground_pressure.set(get_pressure()); + _ground_temperature.set(get_temperature()); +} + // return current altitude estimate relative to time that calibrate() // was called. Returns altitude in meters // note that this relies on read() being called regularly to get new data diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index eb62514a4d..7943d135af 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -33,6 +33,10 @@ public: // the callback is a delay() like routine void calibrate(); + // update the barometer calibration to the current pressure. Can + // be used for incremental preflight update of baro + void update_calibration(); + // get current altitude in meters relative to altitude at the time // of the last calibrate() call float get_altitude(void);