mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
GCS_MAVLINK: Common capacity_remaining_pct checks healthy status and has_current
This commit is contained in:
parent
ca568953d9
commit
1e0ae4b998
@ -4684,10 +4684,9 @@ void GCS_MAVLINK::send_sys_status()
|
|||||||
|
|
||||||
const AP_BattMonitor &battery = AP::battery();
|
const AP_BattMonitor &battery = AP::battery();
|
||||||
float battery_current;
|
float battery_current;
|
||||||
int8_t battery_remaining = -1;
|
const int8_t battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE);
|
||||||
|
|
||||||
if (battery.healthy() && battery.current_amps(battery_current)) {
|
if (battery.healthy() && battery.current_amps(battery_current)) {
|
||||||
battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE);
|
|
||||||
battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX);
|
battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX);
|
||||||
} else {
|
} else {
|
||||||
battery_current = -1;
|
battery_current = -1;
|
||||||
@ -5780,10 +5779,9 @@ void GCS_MAVLINK::send_high_latency2() const
|
|||||||
|
|
||||||
const AP_BattMonitor &battery = AP::battery();
|
const AP_BattMonitor &battery = AP::battery();
|
||||||
float battery_current = -1;
|
float battery_current = -1;
|
||||||
int8_t battery_remaining = -1;
|
const int8_t battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE);
|
||||||
|
|
||||||
if (battery.healthy() && battery.current_amps(battery_current)) {
|
if (battery.healthy() && battery.current_amps(battery_current)) {
|
||||||
battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE);
|
|
||||||
battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX);
|
battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user