Rover: use battery.has_current

This commit is contained in:
Randy Mackay 2014-12-04 15:51:40 +09:00
parent b4b062e9ef
commit fe8730497a
2 changed files with 8 additions and 4 deletions

View File

@ -177,7 +177,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
int16_t battery_current = -1;
int8_t battery_remaining = -1;
if (battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_AND_CURRENT) {
if (battery.has_current()) {
battery_remaining = battery.capacity_remaining_pct();
battery_current = battery.current_amps() * 100;
}

View File

@ -467,9 +467,13 @@ static void report_batt_monitor()
//print_blanks(2);
cliSerial->printf_P(PSTR("Batt Mointor\n"));
print_divider();
if(battery.monitoring() == AP_BATT_MONITOR_DISABLED) cliSerial->printf_P(PSTR("Batt monitoring disabled"));
if(battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_ONLY) cliSerial->printf_P(PSTR("Monitoring batt volts"));
if(battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_AND_CURRENT) cliSerial->printf_P(PSTR("Monitoring volts and current"));
if (battery.num_instances() == 0) {
cliSerial->printf_P(PSTR("Batt monitoring disabled"));
} else if (!battery.has_current()) {
cliSerial->printf_P(PSTR("Monitoring batt volts"));
} else {
cliSerial->printf_P(PSTR("Monitoring volts and current"));
}
print_blanks(2);
}
static void report_radio()