AP_BattMonitor: Rearrange battery parameters to reduce memory usage

Saves 8 bytes per Params instance, which we have 9 of on every vehicle,
for a total saving of 72 bytes
This commit is contained in:
Michael du Breuil 2021-06-17 11:28:26 -07:00 committed by Andrew Tridgell
parent fa7a89ef83
commit 0de9d3e759

View File

@ -23,25 +23,25 @@ public:
BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); }
AP_Int8 _type; /// 0=disabled, 3=voltage only, 4=voltage and current
AP_Int8 _volt_pin; /// board pin used to measure battery voltage
AP_Int8 _curr_pin; /// board pin used to measure battery current
AP_Float _volt_multiplier; /// voltage on volt pin multiplied by this to calculate battery voltage
AP_Float _curr_amp_per_volt; /// voltage on current pin multiplied by this to calculate current in amps
AP_Float _curr_amp_offset; /// offset voltage that is subtracted from current pin before conversion to amps
AP_Int32 _pack_capacity; /// battery pack capacity less reserve in mAh
AP_Int16 _watt_max; /// max battery power allowed. Reduce max throttle to reduce current to satisfy t his limit
AP_Int32 _serial_number; /// battery serial number, automatically filled in on SMBus batteries
AP_Int8 _low_voltage_timeout; /// timeout in seconds before a low voltage event will be triggered
AP_Int8 _failsafe_voltage_source; /// voltage type used for detection of low voltage event
AP_Float _low_voltage; /// voltage level used to trigger a low battery failsafe
AP_Float _low_capacity; /// capacity level used to trigger a low battery failsafe
AP_Float _critical_voltage; /// voltage level used to trigger a critical battery failsafe
AP_Float _critical_capacity; /// capacity level used to trigger a critical battery failsafe
AP_Int8 _failsafe_low_action; /// action to preform on a low battery failsafe
AP_Int8 _failsafe_critical_action; /// action to preform on a critical battery failsafe
AP_Int32 _arming_minimum_capacity; /// capacity level required to arm
AP_Float _arming_minimum_voltage; /// voltage level required to arm
AP_Int8 _i2c_bus; /// I2C bus number
AP_Int32 _options; /// Options
AP_Int16 _watt_max; /// max battery power allowed. Reduce max throttle to reduce current to satisfy t his limit
AP_Int8 _type; /// 0=disabled, 3=voltage only, 4=voltage and current
AP_Int8 _volt_pin; /// board pin used to measure battery voltage
AP_Int8 _curr_pin; /// board pin used to measure battery current
AP_Int8 _low_voltage_timeout; /// timeout in seconds before a low voltage event will be triggered
AP_Int8 _i2c_bus; /// I2C bus number
AP_Int8 _failsafe_voltage_source; /// voltage type used for detection of low voltage event
AP_Int8 _failsafe_low_action; /// action to preform on a low battery failsafe
AP_Int8 _failsafe_critical_action; /// action to preform on a critical battery failsafe
};