diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 33c31ed6f1..f856fd4410 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -226,7 +226,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; } diff --git a/ArduCopter/compassmot.pde b/ArduCopter/compassmot.pde index 9bb3a681f8..f255a252ef 100644 --- a/ArduCopter/compassmot.pde +++ b/ArduCopter/compassmot.pde @@ -76,7 +76,7 @@ static uint8_t mavlink_compassmot(mavlink_channel_t chan) init_compass(); // default compensation type to use current if possible - if (battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_AND_CURRENT) { + if (battery.has_current()) { comp_type = AP_COMPASS_MOT_COMP_CURRENT; }else{ comp_type = AP_COMPASS_MOT_COMP_THROTTLE; diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index c81968261e..3a88aed867 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -146,7 +146,7 @@ static void read_battery(void) battery.read(); // update compass with current value - if (battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_AND_CURRENT) { + if (battery.has_current()) { compass.set_current(battery.current_amps()); }