AP_BattMonitor_logging: update to use capacity_remaining_pct() as a bool

This commit is contained in:
Willian Galvani 2021-08-06 14:39:51 -03:00 committed by Andrew Tridgell
parent 901164a317
commit 1057161f88
1 changed files with 3 additions and 1 deletions

View File

@ -7,6 +7,8 @@ extern const AP_HAL::HAL& hal;
void AP_BattMonitor_Backend::Log_Write_BAT(const uint8_t instance, const uint64_t time_us) const
{
bool has_curr = has_current();
uint8_t percent = -1;
IGNORE_RETURN(capacity_remaining_pct(percent));
const struct log_BAT pkt{
LOG_PACKET_HEADER_INIT(LOG_BAT_MSG),
@ -19,7 +21,7 @@ void AP_BattMonitor_Backend::Log_Write_BAT(const uint8_t instance, const uint64_
consumed_wh : has_curr ? _state.consumed_wh : AP::logger().quiet_nanf(),
temperature : (int16_t) ( has_temperature() ? _state.temperature * 100 : 0),
resistance : _state.resistance,
rem_percent : capacity_remaining_pct(),
rem_percent : percent,
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}