diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp index 728e3b918adca..88b5d1450f74a 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp @@ -138,9 +138,12 @@ AP_BattMonitor::Failsafe AP_BattMonitor_Backend::update_failsafes(void) // this is the first time our voltage has dropped below minimum so start timer if (_state.critical_voltage_start_ms == 0) { _state.critical_voltage_start_ms = now; - } else if (_params._low_voltage_timeout > 0 && - now - _state.critical_voltage_start_ms > uint32_t(_params._low_voltage_timeout)*1000U) { - return AP_BattMonitor::Failsafe::Critical; + } else { + int32_t voltage_timeout = _params._crt_voltage_timeout > 0 ? _params._crt_voltage_timeout : _params._low_voltage_timeout*1000; + if (voltage_timeout > 0 && + now - _state.critical_voltage_start_ms > uint32_t(voltage_timeout)) { + return AP_BattMonitor::Failsafe::Critical; + } } } else { // acceptable voltage so reset timer diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index 63d4ebe4d8124..d19871bb3f544 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -169,6 +169,17 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { AP_GROUPINFO("ESC_INDEX", 22, AP_BattMonitor_Params, _esc_telem_outbound_index, 0), #endif +#ifndef HAL_BUILD_AP_PERIPH + // @Param: CRT_TIMER + // @DisplayName: Critical voltage timeout + // @Description: This is the timeout in milli-seconds before a critical voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with critical voltage on long takeoffs. A value of zero disables critical voltage errors. + // @Units: ms + // @Increment: 1 + // @Range: 0 120000 + // @User: Advanced + AP_GROUPINFO("CRT_TIMER", 23, AP_BattMonitor_Params, _crt_voltage_timeout, 0), +#endif // HAL_BUILD_AP_PERIPH + AP_GROUPEND }; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h index 4665e0eeaa46a..3dd36fb6d07be 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h @@ -46,6 +46,7 @@ class AP_BattMonitor_Params { #endif AP_Int8 _type; /// 0=disabled, 3=voltage only, 4=voltage and current AP_Int8 _low_voltage_timeout; /// timeout in seconds before a low voltage event will be triggered + AP_Int32 _crt_voltage_timeout; /// timeout in milli-seconds before a critical voltage event will be triggered AP_Int8 _failsafe_voltage_source; /// voltage type used for detection of low voltage event AP_Int8 _failsafe_low_action; /// action to preform on a low battery failsafe AP_Int8 _failsafe_critical_action; /// action to preform on a critical battery failsafe