mirror of https://github.com/ArduPilot/ardupilot
AP_Generator: rename fuel_remain_pct to fuel_remain_scale
This commit is contained in:
parent
6bc9b7c435
commit
a32180f709
|
@ -38,14 +38,15 @@ public:
|
|||
// Helpers to retrieve measurements
|
||||
float get_voltage(void) const { return _voltage; }
|
||||
float get_current(void) const { return _current; }
|
||||
float get_fuel_remaining_pct(void) const { return _fuel_remain_pct; }
|
||||
// get_fuel_remaining returns fuel remaining as a scale 0-1
|
||||
float get_fuel_remaining(void) const { return _fuel_remaining; }
|
||||
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_pct() const { return _has_fuel_remaining_pct; }
|
||||
bool has_fuel_remaining() const { return _has_fuel_remaining; }
|
||||
|
||||
// healthy() returns true if the generator is not present, or it is
|
||||
// present, providing telemetry and not indicating any errors.
|
||||
|
@ -99,13 +100,13 @@ private:
|
|||
// Front end variables
|
||||
float _voltage;
|
||||
float _current;
|
||||
float _fuel_remain_pct;
|
||||
float _fuel_remaining; // 0-1
|
||||
bool _has_fuel_remaining;
|
||||
float _consumed_mah;
|
||||
uint16_t _rpm;
|
||||
bool _healthy;
|
||||
bool _has_current;
|
||||
bool _has_consumed_energy;
|
||||
bool _has_fuel_remaining_pct;
|
||||
|
||||
static AP_Generator *_singleton;
|
||||
|
||||
|
|
|
@ -29,7 +29,7 @@ void AP_Generator_Backend::update_frontend()
|
|||
_frontend._voltage = _voltage;
|
||||
_frontend._current = _current;
|
||||
_frontend._consumed_mah = _consumed_mah;
|
||||
_frontend._fuel_remain_pct = _fuel_remain_pct;
|
||||
_frontend._fuel_remaining = _fuel_remaining;
|
||||
_frontend._rpm = _rpm;
|
||||
_frontend._healthy = healthy();
|
||||
}
|
||||
|
|
|
@ -43,7 +43,7 @@ protected:
|
|||
// Measurements readings to write to front end
|
||||
float _voltage;
|
||||
float _current;
|
||||
float _fuel_remain_pct; // Decimal from 0 to 1
|
||||
float _fuel_remaining; // Decimal from 0 to 1
|
||||
float _consumed_mah;
|
||||
uint16_t _rpm;
|
||||
|
||||
|
|
|
@ -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_pct = true;
|
||||
_frontend._has_fuel_remaining = true;
|
||||
}
|
||||
|
||||
// Update fuel cell, expected to be called at 20hz
|
||||
|
@ -43,10 +43,10 @@ void AP_Generator_IE_2400::assign_measurements(const uint32_t now)
|
|||
_state = (State)_parsed.state;
|
||||
_err_code = _parsed.err_code;
|
||||
|
||||
// Scale tank pressure linearly to a percentage.
|
||||
// Scale tank pressure linearly to a value between 0 and 1
|
||||
// Min = 5 bar, max = 300 bar, PRESS_GRAD = 1/295.
|
||||
const float PRESS_GRAD = 0.003389830508f;
|
||||
_fuel_remain_pct = constrain_float((_parsed.tank_bar-5)*PRESS_GRAD,0,1);
|
||||
_fuel_remaining = constrain_float((_parsed.tank_bar-5)*PRESS_GRAD,0,1);
|
||||
|
||||
// Update battery voltage
|
||||
_voltage = _parsed.battery_volt;
|
||||
|
@ -197,7 +197,7 @@ void AP_Generator_IE_2400::log_write()
|
|||
"F2---",
|
||||
"Qfiii",
|
||||
AP_HAL::micros64(),
|
||||
_fuel_remain_pct,
|
||||
_fuel_remaining,
|
||||
_spm_pwr,
|
||||
_pwr_out,
|
||||
_err_code
|
||||
|
|
|
@ -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_pct = false;
|
||||
_frontend._has_fuel_remaining = false;
|
||||
}
|
||||
|
||||
// Update fuel cell, expected to be called at 20hz
|
||||
|
@ -40,7 +40,7 @@ void AP_Generator_IE_650_800::assign_measurements(const uint32_t now)
|
|||
_err_code = _parsed.err_code;
|
||||
|
||||
// Update variables to be returned to front end
|
||||
_fuel_remain_pct = _parsed.tank_pct * 0.01;
|
||||
_fuel_remaining = _parsed.tank_pct * 0.01;
|
||||
|
||||
// Invert bat remaining percent to match AP_BattMonitor convention
|
||||
_consumed_mah = 100.0f - _parsed.battery_pct;
|
||||
|
|
|
@ -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_pct = false;
|
||||
_frontend._has_fuel_remaining = false;
|
||||
}
|
||||
|
||||
// find a RichenPower message in the buffer, starting at
|
||||
|
|
Loading…
Reference in New Issue