mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_Baro: added set_pressure_correction()
for use by AP_TempCalibration
This commit is contained in:
parent
99883ffc49
commit
9bdf971336
@ -534,7 +534,8 @@ void AP_Baro::update(void)
|
|||||||
}
|
}
|
||||||
float altitude = sensors[i].altitude;
|
float altitude = sensors[i].altitude;
|
||||||
if (sensors[i].type == BARO_TYPE_AIR) {
|
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) {
|
} else if (sensors[i].type == BARO_TYPE_WATER) {
|
||||||
//101325Pa is sea level air pressure, 9800 Pascal/ m depth in water.
|
//101325Pa is sea level air pressure, 9800 Pascal/ m depth in water.
|
||||||
//No temperature or depth compensation for density of 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;
|
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;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@ -152,6 +152,9 @@ public:
|
|||||||
// simple atmospheric model
|
// simple atmospheric model
|
||||||
static void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta);
|
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:
|
private:
|
||||||
// how many drivers do we have?
|
// how many drivers do we have?
|
||||||
uint8_t _num_drivers;
|
uint8_t _num_drivers;
|
||||||
@ -173,6 +176,7 @@ private:
|
|||||||
float temperature; // temperature in degrees C
|
float temperature; // temperature in degrees C
|
||||||
float altitude; // calculated altitude
|
float altitude; // calculated altitude
|
||||||
AP_Float ground_pressure;
|
AP_Float ground_pressure;
|
||||||
|
float p_correction;
|
||||||
} sensors[BARO_MAX_INSTANCES];
|
} sensors[BARO_MAX_INSTANCES];
|
||||||
|
|
||||||
AP_Float _alt_offset;
|
AP_Float _alt_offset;
|
||||||
|
Loading…
Reference in New Issue
Block a user