From 32f53624d63d64144f6ac5f7838cb45cd40058fb Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 13 Oct 2013 13:52:52 +0900 Subject: [PATCH] Copter: rename low_battery to failsafe.battery --- ArduCopter/AP_State.pde | 4 ++-- ArduCopter/ArduCopter.pde | 2 +- ArduCopter/GCS_Mavlink.pde | 2 +- ArduCopter/events.pde | 8 ++++---- ArduCopter/leds.pde | 2 +- ArduCopter/sensors.pde | 4 ++-- 6 files changed, 11 insertions(+), 11 deletions(-) diff --git a/ArduCopter/AP_State.pde b/ArduCopter/AP_State.pde index 0a197bb650..a7328f9f28 100644 --- a/ArduCopter/AP_State.pde +++ b/ArduCopter/AP_State.pde @@ -71,9 +71,9 @@ static void set_failsafe_radio(bool b) // --------------------------------------------- -void set_low_battery(bool b) +void set_failsafe_battery(bool b) { - failsafe.low_battery = b; + failsafe.battery = b; AP_Notify::flags.failsafe_battery = b; } diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 22cb4f8165..642ce6815d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -422,7 +422,7 @@ static uint8_t receiver_rssi; static struct { uint8_t rc_override_active : 1; // 0 // true if rc control are overwritten by ground station uint8_t radio : 1; // 1 // A status flag for the radio failsafe - uint8_t low_battery : 1; // 2 // A status flag for the battery failsafe + uint8_t battery : 1; // 2 // A status flag for the battery failsafe uint8_t gps : 1; // 3 // A status flag for the gps failsafe uint8_t gcs : 1; // 4 // A status flag for the ground station failsafe diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 26336e8f92..f9f6318eb5 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -51,7 +51,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan) uint32_t custom_mode = control_mode; // set system as critical if any failsafe have triggered - if (failsafe.radio || failsafe.low_battery || failsafe.gps || failsafe.gcs) { + if (failsafe.radio || failsafe.battery || failsafe.gps || failsafe.gcs) { system_status = MAV_STATE_CRITICAL; } diff --git a/ArduCopter/events.pde b/ArduCopter/events.pde index 566d0d5ebd..12887a29da 100644 --- a/ArduCopter/events.pde +++ b/ArduCopter/events.pde @@ -50,7 +50,7 @@ static void failsafe_radio_on_event() break; case LAND: // continue to land if battery failsafe is also active otherwise fall through to default handling - if (g.failsafe_battery_enabled && failsafe.low_battery) { + if (g.failsafe_battery_enabled && failsafe.battery) { break; } default: @@ -83,10 +83,10 @@ static void failsafe_radio_off_event() Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_RADIO, ERROR_CODE_FAILSAFE_RESOLVED); } -static void low_battery_event(void) +static void failsafe_battery_event(void) { // return immediately if low battery event has already been triggered - if (failsafe.low_battery) { + if (failsafe.battery) { return; } @@ -121,7 +121,7 @@ static void low_battery_event(void) } // set the low battery flag - set_low_battery(true); + set_failsafe_battery(true); // warn the ground station and log to dataflash gcs_send_text_P(SEVERITY_LOW,PSTR("Low Battery!")); diff --git a/ArduCopter/leds.pde b/ArduCopter/leds.pde index 1865aca534..681b32e399 100644 --- a/ArduCopter/leds.pde +++ b/ArduCopter/leds.pde @@ -60,7 +60,7 @@ static void update_copter_leds(void) // motor leds control if (g.copter_leds_mode & COPTER_LEDS_BITMASK_ENABLED) { if (motors.armed()) { - if (failsafe.low_battery) { + if (failsafe.battery) { if (g.copter_leds_mode & COPTER_LEDS_BITMASK_BATT_OSCILLATE) { copter_leds_oscillate(); //if motors are armed, but battery level is low, motor leds fast blink } else { diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index e34ea2a863..67c47530aa 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -110,8 +110,8 @@ static void read_battery(void) // check for low voltage or current if the low voltage check hasn't already been triggered // we only check when we're not powered by USB to avoid false alarms during bench tests - if (!ap.usb_connected && !failsafe.low_battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) { - low_battery_event(); + if (!ap.usb_connected && !failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) { + failsafe_battery_event(); } }