Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_Params.h
Views: 1798
#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);1314// low voltage sources (used for BATT_LOW_TYPE parameter)15enum BattMonitor_LowVoltage_Source {16BattMonitor_LowVoltageSource_Raw = 0,17BattMonitor_LowVoltageSource_SagCompensated = 118};19enum class Options : uint16_t {20Ignore_UAVCAN_SoC = (1U<<0), // Ignore UAVCAN State-of-Charge (charge %) supplied value from the device and use the internally calculated one21MPPT_Use_Input_Value = (1U<<1), // MPPT reports voltage and current from Input (usually solar panel) instead of the output22MPPT_Power_Off_At_Disarm = (1U<<2), // MPPT Disabled when vehicle is disarmed, if HW supports it23MPPT_Power_On_At_Arm = (1U<<3), // MPPT Enabled when vehicle is armed, if HW supports it24MPPT_Power_Off_At_Boot = (1U<<4), // MPPT Disabled at startup (aka boot), if HW supports it25MPPT_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_Boot26GCS_Resting_Voltage = (1U<<6), // send resistance resting voltage to GCS27AllowSplitAuxInfo = (1U<<7), // allow different node to provide aux info for DroneCAN28InternalUseOnly = (1U<<8), // for use internally to ArduPilot, not to be (eg.) sent via MAVLink BATTERY_STATUS29Minimum_Voltage = (1U<<9), // sum monitor measures minimum voltage rather than average30};3132BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); }3334AP_Int32 _pack_capacity; /// battery pack capacity less reserve in mAh35AP_Int32 _serial_number; /// battery serial number, automatically filled in on SMBus batteries36AP_Float _low_voltage; /// voltage level used to trigger a low battery failsafe37AP_Float _low_capacity; /// capacity level used to trigger a low battery failsafe38AP_Float _critical_voltage; /// voltage level used to trigger a critical battery failsafe39AP_Float _critical_capacity; /// capacity level used to trigger a critical battery failsafe40AP_Int32 _arming_minimum_capacity; /// capacity level required to arm41AP_Float _arming_minimum_voltage; /// voltage level required to arm42AP_Int32 _options; /// Options43#if AP_BATTERY_WATT_MAX_ENABLED44AP_Int16 _watt_max; /// max battery power allowed. Reduce max throttle to reduce current to satisfy t his limit45#endif46AP_Int8 _type; /// 0=disabled, 3=voltage only, 4=voltage and current47AP_Int8 _low_voltage_timeout; /// timeout in seconds before a low voltage event will be triggered48AP_Int8 _failsafe_voltage_source; /// voltage type used for detection of low voltage event49AP_Int8 _failsafe_low_action; /// action to preform on a low battery failsafe50AP_Int8 _failsafe_critical_action; /// action to preform on a critical battery failsafe51#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED52AP_Int8 _esc_telem_outbound_index; /// bitmask of ESCs to forward voltage, current, consumption and temperature to.53#endif54};555657