AP_Baro: added set_pressure_correction()

for use by AP_TempCalibration
This commit is contained in:
Andrew Tridgell 2017-03-31 20:08:52 +11:00
parent 99883ffc49
commit 9bdf971336
2 changed files with 14 additions and 1 deletions

View File

@ -534,7 +534,8 @@ void AP_Baro::update(void)
}
float altitude = sensors[i].altitude;
if (sensors[i].type == BARO_TYPE_AIR) {
altitude = get_altitude_difference(sensors[i].ground_pressure, sensors[i].pressure);
float pressure = sensors[i].pressure + sensors[i].p_correction;
altitude = get_altitude_difference(sensors[i].ground_pressure, pressure);
} else if (sensors[i].type == BARO_TYPE_WATER) {
//101325Pa is sea level air pressure, 9800 Pascal/ m depth in water.
//No temperature or depth compensation for density of water.
@ -608,3 +609,11 @@ bool AP_Baro::all_healthy(void) const
}
return _num_sensors > 0;
}
// set a pressure correction from AP_TempCalibration
void AP_Baro::set_pressure_correction(uint8_t instance, float p_correction)
{
if (instance < _num_sensors) {
sensors[instance].p_correction = p_correction;
}
}

View File

@ -152,6 +152,9 @@ public:
// simple atmospheric model
static void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta);
// set a pressure correction from AP_TempCalibration
void set_pressure_correction(uint8_t instance, float p_correction);
private:
// how many drivers do we have?
uint8_t _num_drivers;
@ -173,6 +176,7 @@ private:
float temperature; // temperature in degrees C
float altitude; // calculated altitude
AP_Float ground_pressure;
float p_correction;
} sensors[BARO_MAX_INSTANCES];
AP_Float _alt_offset;