AP_Frsky_Telem: update to use capacity_remaining_pct() as a bool

This commit is contained in:
Willian Galvani 2021-02-17 11:04:46 -03:00
parent 2eed23dcd6
commit 343328215f
2 changed files with 9 additions and 3 deletions

View File

@ -49,7 +49,9 @@ void AP_Frsky_D::send(void)
_D.last_200ms_frame = now;
send_uint16(DATA_ID_TEMP2, (uint16_t)(AP::gps().num_sats() * 10 + AP::gps().status())); // send GPS status and number of satellites as num_sats*10 + status (to fit into a uint8_t)
send_uint16(DATA_ID_TEMP1, gcs().custom_mode()); // send flight mode
send_uint16(DATA_ID_FUEL, (uint16_t)roundf(_battery.capacity_remaining_pct())); // send battery remaining
uint8_t percentage = 0;
IGNORE_RETURN(_battery.capacity_remaining_pct(percentage));
send_uint16(DATA_ID_FUEL, (uint16_t)roundf(percentage)); // send battery remaining
send_uint16(DATA_ID_VFAS, (uint16_t)roundf(_battery.voltage() * 10.0f)); // send battery voltage
float current;
if (!_battery.current_amps(current)) {

View File

@ -66,8 +66,12 @@ void AP_Frsky_SPort::send(void)
case SENSOR_ID_FAS: // Sensor ID 2
switch (_SPort.fas_call) {
case 0:
send_sport_frame(SPORT_DATA_FRAME, FUEL_ID, (uint16_t)roundf(_battery.capacity_remaining_pct())); // send battery remaining as %
break;
{
uint8_t percentage = 0;
IGNORE_RETURN(_battery.capacity_remaining_pct(percentage));
send_sport_frame(SPORT_DATA_FRAME, FUEL_ID, (uint16_t)roundf(percentage)); // send battery remaining
break;
}
case 1:
send_sport_frame(SPORT_DATA_FRAME, VFAS_ID, (uint16_t)roundf(_battery.voltage() * 100.0f)); // send battery voltage in cV
break;