Copter: use battery.has_current method
This commit is contained in:
parent
cf36fd55bd
commit
3ccc61c163
@ -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;
|
||||
}
|
||||
|
@ -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;
|
||||
|
@ -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…
Reference in New Issue
Block a user