mirror of https://github.com/ArduPilot/ardupilot
Sub: failsafe_battery_event() -> failsafe_battery_check()
This commit is contained in:
parent
16fedbb9c9
commit
6bd05e4bac
|
@ -624,7 +624,7 @@ private:
|
|||
void failsafe_ekf_event();
|
||||
void failsafe_ekf_off_event(void);
|
||||
bool should_disarm_on_failsafe();
|
||||
void failsafe_battery_event(void);
|
||||
void failsafe_battery_check(void);
|
||||
void failsafe_gcs_check();
|
||||
void failsafe_manual_control_check(void);
|
||||
void set_neutral_controls(void);
|
||||
|
|
|
@ -70,7 +70,7 @@ void Sub::failsafe_check()
|
|||
}
|
||||
}
|
||||
|
||||
void Sub::failsafe_battery_event(void)
|
||||
void Sub::failsafe_battery_check(void)
|
||||
{
|
||||
// // return immediately if low battery event has already been triggered
|
||||
// if (failsafe.battery) {
|
||||
|
|
|
@ -160,15 +160,12 @@ void Sub::read_battery(void)
|
|||
if (battery.get_type() != AP_BattMonitor::BattMonitor_TYPE_NONE) {
|
||||
motors.set_voltage(battery.voltage());
|
||||
}
|
||||
|
||||
if (battery.has_current()) {
|
||||
motors.set_current(battery.current_amps());
|
||||
}
|
||||
|
||||
// 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.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
|
||||
failsafe_battery_event();
|
||||
}
|
||||
failsafe_battery_check();
|
||||
|
||||
// log battery info to the dataflash
|
||||
if (should_log(MASK_LOG_CURRENT)) {
|
||||
|
|
Loading…
Reference in New Issue