Browse Source

AP_BattMonitor: added BATT_VOLT_TIMEO

this is useful for aircraft with very low C batteries, to prevent a low
voltage failsafe on takeoff. For long endurance aircraft low C batteries
are often used, and the voltage sags a lot on takeoff, but it fine for
the rest of the flight
mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
d4e6720b01
  1. 11
      libraries/AP_BattMonitor/AP_BattMonitor.cpp
  2. 4
      libraries/AP_BattMonitor/AP_BattMonitor.h

11
libraries/AP_BattMonitor/AP_BattMonitor.cpp

@ -143,6 +143,15 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { @@ -143,6 +143,15 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
#endif // AP_BATT_MONITOR_MAX_INSTANCES > 1
// @Param: _VOLT_TIMER
// @DisplayName: Low voltage timeout
// @Description: This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
// @Units: Seconds
// @Increment: 1
// @Range: 0 120
// @User: Advanced
AP_GROUPINFO("_VOLT_TIMER", 21, AP_BattMonitor, _volt_timeout, AP_BATT_LOW_VOLT_TIMEOUT_DEFAULT),
AP_GROUPEND
};
@ -307,7 +316,7 @@ bool AP_BattMonitor::exhausted(uint8_t instance, float low_voltage, float min_ca @@ -307,7 +316,7 @@ bool AP_BattMonitor::exhausted(uint8_t instance, float low_voltage, float min_ca
// this is the first time our voltage has dropped below minimum so start timer
if (state[instance].low_voltage_start_ms == 0) {
state[instance].low_voltage_start_ms = AP_HAL::millis();
} else if (AP_HAL::millis() - state[instance].low_voltage_start_ms > AP_BATT_LOW_VOLT_TIMEOUT_MS) {
} else if (_volt_timeout > 0 && AP_HAL::millis() - state[instance].low_voltage_start_ms > uint32_t(_volt_timeout.get())*1000U) {
return true;
}
} else {

4
libraries/AP_BattMonitor/AP_BattMonitor.h

@ -12,7 +12,7 @@ @@ -12,7 +12,7 @@
#define AP_BATT_PRIMARY_INSTANCE 0
#define AP_BATT_CAPACITY_DEFAULT 3300
#define AP_BATT_LOW_VOLT_TIMEOUT_MS 10000 // low voltage of 10 seconds will cause battery_exhausted to return true
#define AP_BATT_LOW_VOLT_TIMEOUT_DEFAULT 10 // low voltage of 10 seconds will cause battery_exhausted to return true
#define AP_BATT_MAX_WATT_DEFAULT 0
#define AP_BATT_SERIAL_NUMBER_DEFAULT -1
@ -150,6 +150,8 @@ protected: @@ -150,6 +150,8 @@ protected:
AP_Int16 _watt_max[AP_BATT_MONITOR_MAX_INSTANCES]; /// max battery power allowed. Reduce max throttle to reduce current to satisfy this limit
AP_Int32 _serial_numbers[AP_BATT_MONITOR_MAX_INSTANCES]; /// battery serial number, automatically filled in on SMBus batteries
AP_Int8 _volt_timeout;
private:
BattMonitor_State state[AP_BATT_MONITOR_MAX_INSTANCES];
AP_BattMonitor_Backend *drivers[AP_BATT_MONITOR_MAX_INSTANCES];

Loading…
Cancel
Save