Browse Source

Copter: use battery.has_current method

master
Randy Mackay 10 years ago
parent
commit
3ccc61c163
  1. 2
      ArduCopter/GCS_Mavlink.pde
  2. 2
      ArduCopter/compassmot.pde
  3. 2
      ArduCopter/sensors.pde

2
ArduCopter/GCS_Mavlink.pde

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

2
ArduCopter/compassmot.pde

@ -76,7 +76,7 @@ static uint8_t mavlink_compassmot(mavlink_channel_t chan) @@ -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;

2
ArduCopter/sensors.pde

@ -146,7 +146,7 @@ static void read_battery(void) @@ -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());
}

Loading…
Cancel
Save