mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 07:38:28 -04:00
GCS_Common: create virtual get_battery_remaining_percentage()
This commit is contained in:
parent
799ac6f741
commit
7855d324b3
@ -431,6 +431,7 @@ protected:
|
||||
virtual float vfr_hud_airspeed() const;
|
||||
virtual int16_t vfr_hud_throttle() const { return 0; }
|
||||
virtual float vfr_hud_alt() const;
|
||||
virtual uint8_t get_battery_remaining_percentage();
|
||||
|
||||
static constexpr const float magic_force_arm_value = 2989.0f;
|
||||
static constexpr const float magic_force_disarm_value = 21196.0f;
|
||||
|
@ -3931,7 +3931,7 @@ void GCS_MAVLINK::send_sys_status()
|
||||
int8_t battery_remaining;
|
||||
|
||||
if (battery.healthy() && battery.current_amps(battery_current)) {
|
||||
battery_remaining = battery.capacity_remaining_pct();
|
||||
battery_remaining = get_battery_remaining_percentage();
|
||||
battery_current *= 100;
|
||||
} else {
|
||||
battery_current = -1;
|
||||
@ -4661,6 +4661,11 @@ void GCS_MAVLINK::manual_override(RC_Channel *c, int16_t value_in, const uint16_
|
||||
c->set_override(override_value, tnow);
|
||||
}
|
||||
|
||||
uint8_t GCS_MAVLINK::get_battery_remaining_percentage() {
|
||||
const AP_BattMonitor &battery = AP::battery();
|
||||
return battery.capacity_remaining_pct();
|
||||
}
|
||||
|
||||
GCS &gcs()
|
||||
{
|
||||
return *GCS::get_singleton();
|
||||
|
Loading…
Reference in New Issue
Block a user