BattMonitor: bug fix for current_total_mah

This commit is contained in:
Randy Mackay 2013-10-01 22:30:09 +09:00
parent cb91440c63
commit f1309ed63f
2 changed files with 2 additions and 2 deletions

View File

@ -100,7 +100,7 @@ AP_BattMonitor::read()
_current_amps = (_curr_pin_analog_source->voltage_average()-_curr_amp_offset)*_curr_amp_per_volt;
if (_last_time_micros != 0 && dt < 2000000.0f) {
// .0002778 is 1/3600 (conversion to hours)
_current_total_mah += _current_amps * dt * 0.2778f;
_current_total_mah += _current_amps * dt * 0.0000002778f;
}
_last_time_micros = tnow;
}

View File

@ -90,7 +90,7 @@ public:
float current_amps() const { return _current_amps; }
/// Total current drawn since start-up (Amp-hours)
float current_total_mah() const { return _current_total_mah; }\
float current_total_mah() const { return _current_total_mah; }
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
uint8_t capacity_remaining_pct() const;