mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: pre-arm check of battery voltage
This commit is contained in:
parent
edc32092ce
commit
63052ff874
@ -478,6 +478,16 @@ bool Copter::pre_arm_checks(bool display_failure)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// check battery voltage
|
||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
|
||||
if (failsafe.battery || (!ap.usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah))) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check Battery"));
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// check various parameter values
|
||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_PARAMETERS)) {
|
||||
|
||||
@ -726,6 +736,16 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
||||
}
|
||||
}
|
||||
|
||||
// check battery voltage
|
||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
|
||||
if (failsafe.battery || (!ap.usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah))) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Check Battery"));
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// check throttle
|
||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {
|
||||
// check throttle is not too low - must be above failsafe throttle
|
||||
|
Loading…
Reference in New Issue
Block a user