mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: Change to floating value multiplication
This commit is contained in:
parent
f34bb256dc
commit
0ab76afb4d
|
@ -49,7 +49,7 @@ void AP_BattMonitor_Torqeedo::read(void)
|
|||
const uint32_t tnow_us = AP_HAL::micros();
|
||||
const uint32_t diff_us = tnow_us - _state.last_time_micros;
|
||||
if (diff_us < AP_BATTMON_TORQEEDO_TIMEOUT_US) {
|
||||
_state.consumed_mah += _state.current_amps * diff_us / 1000000.0 / 3600.0 * 1000.0;
|
||||
_state.consumed_mah += _state.current_amps * diff_us * 1e-6f / 3600.0 * 1000.0;
|
||||
}
|
||||
_state.last_time_micros = tnow_us;
|
||||
_state.healthy = true;
|
||||
|
@ -77,4 +77,3 @@ bool AP_BattMonitor_Torqeedo::capacity_remaining_pct(uint8_t &percentage) const
|
|||
}
|
||||
|
||||
#endif // AP_BATTERY_TORQEEDO_ENABLED
|
||||
|
||||
|
|
Loading…
Reference in New Issue