Copter: rename low_battery to failsafe.battery
This commit is contained in:
parent
0e740bd4e1
commit
32f53624d6
@ -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;
|
||||
}
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
@ -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!"));
|
||||
|
@ -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 {
|
||||
|
@ -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();
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user