From 0a8677b3e274bca52993f311dfc86eda41ec4f46 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 7 Jan 2015 12:53:30 +1100 Subject: [PATCH] AP_Baro: fixed build after rebase with all_healthy() --- libraries/AP_Baro/AP_Baro.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 44a86137ee..3b5d41afc1 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -101,20 +101,20 @@ void AP_Baro::calibrate() for (uint8_t c = 0; c < num_samples; c++) { uint32_t tstart = hal.scheduler->millis(); - bool all_healthy = false; + bool all_sensors_healthy = false; do { update(); if (hal.scheduler->millis() - tstart > 500) { hal.scheduler->panic(PSTR("PANIC: AP_Baro::read unsuccessful " "for more than 500ms in AP_Baro::calibrate [3]\r\n")); } - all_healthy = true; + all_sensors_healthy = true; for (uint8_t i=0; i<_num_sensors; i++) { if (!healthy(i)) { - all_healthy = false; + all_sensors_healthy = false; } } - } while (!all_healthy); + } while (!all_sensors_healthy); for (uint8_t i=0; i<_num_sensors; i++) { sum_pressure[i] += sensors[i].pressure; sum_temperature[i] += sensors[i].temperature;