mirror of https://github.com/ArduPilot/ardupilot
AP_Generator: rename has_fuel_remaining to has_fuel_remaining_pct
This commit is contained in:
parent
1a061b2c1a
commit
aa95dfb15e
|
@ -42,14 +42,14 @@ public:
|
|||
// Helpers to retrieve measurements
|
||||
float get_voltage(void) const { return _voltage; }
|
||||
float get_current(void) const { return _current; }
|
||||
float get_fuel_remain(void) const { return _fuel_remain_pct; }
|
||||
float get_fuel_remaining_pct(void) const { return _fuel_remain_pct; }
|
||||
float get_batt_consumed(void) const { return _consumed_mah; }
|
||||
uint16_t get_rpm(void) const { return _rpm; }
|
||||
|
||||
// Helpers to see if backend has a measurement
|
||||
bool has_current() const { return _has_current; }
|
||||
bool has_consumed_energy() const { return _has_consumed_energy; }
|
||||
bool has_fuel_remaining() const { return _has_fuel_remaining; }
|
||||
bool has_fuel_remaining_pct() const { return _has_fuel_remaining_pct; }
|
||||
|
||||
// healthy() returns true if the generator is not present, or it is
|
||||
// present, providing telemetry and not indicating any errors.
|
||||
|
@ -103,7 +103,7 @@ private:
|
|||
bool _healthy;
|
||||
bool _has_current;
|
||||
bool _has_consumed_energy;
|
||||
bool _has_fuel_remaining;
|
||||
bool _has_fuel_remaining_pct;
|
||||
|
||||
static AP_Generator *_singleton;
|
||||
|
||||
|
|
|
@ -29,7 +29,7 @@ void AP_Generator_IE_2400::init()
|
|||
// Tell frontend what measurements are available for this generator
|
||||
_frontend._has_current = true;
|
||||
_frontend._has_consumed_energy = true;
|
||||
_frontend._has_fuel_remaining = true;
|
||||
_frontend._has_fuel_remaining_pct = true;
|
||||
}
|
||||
|
||||
// Update fuel cell, expected to be called at 20hz
|
||||
|
|
|
@ -28,7 +28,7 @@ void AP_Generator_IE_650_800::init()
|
|||
// This unit does not have current but this needs to be true to make use of consumed_mah in BattMonitor
|
||||
_frontend._has_current = true;
|
||||
_frontend._has_consumed_energy = true;
|
||||
_frontend._has_fuel_remaining = false;
|
||||
_frontend._has_fuel_remaining_pct = false;
|
||||
}
|
||||
|
||||
// Update fuel cell, expected to be called at 20hz
|
||||
|
|
|
@ -41,7 +41,7 @@ void AP_Generator_RichenPower::init()
|
|||
// Tell frontend what measurements are available for this generator
|
||||
_frontend._has_current = true;
|
||||
_frontend._has_consumed_energy = false;
|
||||
_frontend._has_fuel_remaining = false;
|
||||
_frontend._has_fuel_remaining_pct = false;
|
||||
}
|
||||
|
||||
// find a RichenPower message in the buffer, starting at
|
||||
|
|
Loading…
Reference in New Issue