mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AP_Baro: added update_calibration() method
used for auto baro calibration when disarmed
This commit is contained in:
parent
7cab8cb3bb
commit
487caea3a5
@ -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
|
||||
|
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user