|
|
|
@ -118,6 +118,17 @@ void AP_Baro::calibrate()
@@ -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
|
|
|
|
|