Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_Params.h
9717 views
#pragma once12#include <AP_Param/AP_Param.h>3#include "AP_BattMonitor_config.h"45class AP_BattMonitor_Params {6public:7static const struct AP_Param::GroupInfo var_info[];89AP_BattMonitor_Params(void);1011/* Do not allow copies */12CLASS_NO_COPY(AP_BattMonitor_Params);1314enum class Type {15NONE = 0,16ANALOG_VOLTAGE_ONLY = 3,17ANALOG_VOLTAGE_AND_CURRENT = 4,18SOLO = 5,19BEBOP = 6,20SMBus_Generic = 7,21UAVCAN_BatteryInfo = 8,22BLHeliESC = 9,23Sum = 10,24FuelFlow = 11,25FuelLevel_PWM = 12,26SUI3 = 13,27SUI6 = 14,28NeoDesign = 15,29MAXELL = 16,30GENERATOR_ELEC = 17,31GENERATOR_FUEL = 18,32Rotoye = 19,33// 20 was MPPT_PacketDigital34INA2XX = 21,35LTC2946 = 22,36Torqeedo = 23,37FuelLevel_Analog = 24,38Analog_Volt_Synthetic_Current = 25,39INA239_SPI = 26,40EFI = 27,41AD7091R5 = 28,42Scripting = 29,43INA3221 = 30,44ANALOG_CURRENT_ONLY = 31,45TIBQ76952_I2C = 32,46};4748// low voltage sources (used for BATT_LOW_TYPE parameter)49enum BattMonitor_LowVoltage_Source {50BattMonitor_LowVoltageSource_Raw = 0,51BattMonitor_LowVoltageSource_SagCompensated = 152};53enum class Options : uint16_t {54Ignore_UAVCAN_SoC = (1U<<0), // Ignore UAVCAN State-of-Charge (charge %) supplied value from the device and use the internally calculated one55MPPT_Use_Input_Value = (1U<<1), // MPPT reports voltage and current from Input (usually solar panel) instead of the output56MPPT_Power_Off_At_Disarm = (1U<<2), // MPPT Disabled when vehicle is disarmed, if HW supports it57MPPT_Power_On_At_Arm = (1U<<3), // MPPT Enabled when vehicle is armed, if HW supports it58MPPT_Power_Off_At_Boot = (1U<<4), // MPPT Disabled at startup (aka boot), if HW supports it59MPPT_Power_On_At_Boot = (1U<<5), // MPPT Enabled at startup (aka boot), if HW supports it. If Power_Off_at_Boot is also set, the behavior is Power_Off_at_Boot60GCS_Resting_Voltage = (1U<<6), // send resistance resting voltage to GCS61AllowSplitAuxInfo = (1U<<7), // allow different node to provide aux info for DroneCAN62InternalUseOnly = (1U<<8), // for use internally to ArduPilot, not to be (eg.) sent via MAVLink BATTERY_STATUS63Minimum_Voltage = (1U<<9), // sum monitor measures minimum voltage rather than average64AllowDynamicNodeUpdate = (1U<<10), // allow dynamic update of DroneCAN node ID during hot-swap when telemetry is lost65};6667BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); }6869AP_Int32 _pack_capacity; /// battery pack capacity less reserve in mAh70AP_Int32 _serial_number; /// battery serial number, automatically filled in on SMBus batteries71AP_Float _low_voltage; /// voltage level used to trigger a low battery failsafe72AP_Float _low_capacity; /// capacity level used to trigger a low battery failsafe73AP_Float _critical_voltage; /// voltage level used to trigger a critical battery failsafe74AP_Float _critical_capacity; /// capacity level used to trigger a critical battery failsafe75AP_Int32 _arming_minimum_capacity; /// capacity level required to arm76AP_Float _arming_minimum_voltage; /// voltage level required to arm77AP_Int32 _options; /// Options78#if AP_BATTERY_WATT_MAX_ENABLED79AP_Int16 _watt_max; /// max battery power allowed. Reduce max throttle to reduce current to satisfy t his limit80#endif81AP_Enum<Type> _type; /// 0=disabled, 3=voltage only, 4=voltage and current82AP_Int8 _low_voltage_timeout; /// timeout in seconds before a low voltage event will be triggered83AP_Int8 _failsafe_voltage_source; /// voltage type used for detection of low voltage event84AP_Int8 _failsafe_low_action; /// action to preform on a low battery failsafe85AP_Int8 _failsafe_critical_action; /// action to preform on a critical battery failsafe86#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED87AP_Int8 _esc_telem_outbound_index; /// bitmask of ESCs to forward voltage, current, consumption and temperature to.88#endif89};909192