APM: added error checking on barometer read

if the barometer is dead and the GPS has a fix, use the GPS for
altitude
This commit is contained in:
Andrew Tridgell 2011-12-28 20:34:11 +11:00
parent 98353b7ba8
commit cd3729d993
3 changed files with 19 additions and 10 deletions

View File

@ -978,8 +978,12 @@ static void update_alt()
// this function is in place to potentially add a sonar sensor in the future // this function is in place to potentially add a sonar sensor in the future
//altitude_sensor = BARO; //altitude_sensor = BARO;
if (barometer.healthy) {
current_loc.alt = (1 - g.altitude_mix) * g_gps->altitude; // alt_MSL centimeters (meters * 100) current_loc.alt = (1 - g.altitude_mix) * g_gps->altitude; // alt_MSL centimeters (meters * 100)
current_loc.alt += g.altitude_mix * (read_barometer() + home.alt); current_loc.alt += g.altitude_mix * (read_barometer() + home.alt);
} else if (g_gps->fix) {
current_loc.alt = g_gps->altitude; // alt_MSL centimeters (meters * 100)
}
#endif #endif
geofence_check(true); geofence_check(true);

View File

@ -11,7 +11,7 @@ static void init_barometer(void)
long ground_pressure = 0; long ground_pressure = 0;
int ground_temperature; int ground_temperature;
while(ground_pressure == 0){ while (ground_pressure == 0 || !barometer.healthy) {
barometer.read(); // Get initial data from absolute pressure sensor barometer.read(); // Get initial data from absolute pressure sensor
ground_pressure = barometer.get_pressure(); ground_pressure = barometer.get_pressure();
ground_temperature = barometer.get_temperature(); ground_temperature = barometer.get_temperature();
@ -25,7 +25,9 @@ static void init_barometer(void)
gcs_update(); // look for inbound hil packets gcs_update(); // look for inbound hil packets
#endif #endif
barometer.read(); // Get initial data from absolute pressure sensor do {
barometer.read(); // Get pressure sensor
} while (!barometer.healthy);
ground_pressure = (ground_pressure * 9l + barometer.get_pressure()) / 10l; ground_pressure = (ground_pressure * 9l + barometer.get_pressure()) / 10l;
ground_temperature = (ground_temperature * 9 + barometer.get_temperature()) / 10; ground_temperature = (ground_temperature * 9 + barometer.get_temperature()) / 10;
@ -59,7 +61,6 @@ static long read_barometer(void)
barometer.read(); // Get new data from absolute pressure sensor barometer.read(); // Get new data from absolute pressure sensor
//abs_pressure = (abs_pressure + barometer.get_pressure()) >> 1; // Small filtering //abs_pressure = (abs_pressure + barometer.get_pressure()) >> 1; // Small filtering
abs_pressure = ((float)abs_pressure * .7) + ((float)barometer.get_pressure() * .3); // large filtering abs_pressure = ((float)abs_pressure * .7) + ((float)barometer.get_pressure() * .3); // large filtering
scaling = (float)g.ground_pressure / (float)abs_pressure; scaling = (float)g.ground_pressure / (float)abs_pressure;

View File

@ -700,9 +700,13 @@ test_pressure(uint8_t argc, const Menu::arg *argv)
delay(100); delay(100);
current_loc.alt = read_barometer() + home.alt; current_loc.alt = read_barometer() + home.alt;
if (!barometer.healthy) {
Serial.println_P(PSTR("not healthy"));
} else {
Serial.printf_P(PSTR("Alt: %0.2fm, Raw: %ld Temperature: %.1f\n"), Serial.printf_P(PSTR("Alt: %0.2fm, Raw: %ld Temperature: %.1f\n"),
current_loc.alt / 100.0, current_loc.alt / 100.0,
abs_pressure, 0.1*barometer.get_temperature()); abs_pressure, 0.1*barometer.get_temperature());
}
if(Serial.available() > 0){ if(Serial.available() > 0){
return (0); return (0);