AP_BattMonitor: rename VOLT_TIMER to LOW_TIMER

This commit is contained in:
Randy Mackay 2017-05-25 14:06:59 +09:00
parent 989677ddfd
commit f64777849f
2 changed files with 5 additions and 6 deletions

View File

@ -143,15 +143,15 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
#endif // AP_BATT_MONITOR_MAX_INSTANCES > 1
// @Param: _VOLT_TIMER
// @Param: _LOW_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: s
// @Increment: 1
// @Range: 0 120
// @User: Advanced
AP_GROUPINFO("_VOLT_TIMER", 21, AP_BattMonitor, _volt_timeout, AP_BATT_LOW_VOLT_TIMEOUT_DEFAULT),
AP_GROUPINFO("_LOW_TIMER", 21, AP_BattMonitor, _low_voltage_timeout, AP_BATT_LOW_VOLT_TIMEOUT_DEFAULT),
AP_GROUPEND
};
@ -312,7 +312,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 (_volt_timeout > 0 && AP_HAL::millis() - state[instance].low_voltage_start_ms > uint32_t(_volt_timeout.get())*1000U) {
} else if (_low_voltage_timeout > 0 && AP_HAL::millis() - state[instance].low_voltage_start_ms > uint32_t(_low_voltage_timeout.get())*1000U) {
return true;
}
} else {

View File

@ -149,8 +149,7 @@ protected:
AP_Int32 _pack_capacity[AP_BATT_MONITOR_MAX_INSTANCES]; /// battery pack capacity less reserve in mAh
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;
AP_Int8 _low_voltage_timeout; /// timeout in seconds before a low voltage event will be triggered
private:
BattMonitor_State state[AP_BATT_MONITOR_MAX_INSTANCES];