Browse Source

Plane: use battery.has_current

master
Randy Mackay 10 years ago
parent
commit
5cdb8a4c2a
  1. 2
      ArduPlane/GCS_Mavlink.pde

2
ArduPlane/GCS_Mavlink.pde

@ -254,7 +254,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) @@ -254,7 +254,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;
}

Loading…
Cancel
Save