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.cpp
Views: 1798
#include "AP_BattMonitor_config.h"12#if AP_BATTERY_ENABLED34#include <AP_Common/AP_Common.h>5#include <AP_Vehicle/AP_Vehicle_Type.h>6#include "AP_BattMonitor_Params.h"7#include "AP_BattMonitor.h"89#if APM_BUILD_COPTER_OR_HELI10#define DEFAULT_LOW_BATTERY_VOLTAGE 10.5f11#else12#define DEFAULT_LOW_BATTERY_VOLTAGE 0.0f13#endif // APM_BUILD_COPTER_OR_HELI1415#ifndef AP_BATT_MONITOR_BATTERY_CAPACITY16#define AP_BATT_MONITOR_BATTERY_CAPACITY 330017#endif1819const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {20// @Param: MONITOR21// @DisplayName: Battery monitoring22// @Description: Controls enabling monitoring of the battery's voltage and current23// @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Generic,8:DroneCAN-BatteryInfo,9:ESC,10:Sum Of Selected Monitors,11:FuelFlow,12:FuelLevelPWM,13:SMBUS-SUI3,14:SMBUS-SUI6,15:NeoDesign,16:SMBus-Maxell,17:Generator-Elec,18:Generator-Fuel,19:Rotoye,20:MPPT,21:INA2XX,22:LTC2946,23:Torqeedo,24:FuelLevelAnalog,25:Synthetic Current and Analog Voltage,26:INA239_SPI,27:EFI,28:AD7091R5,29:Scripting,30:INA322124// @User: Standard25// @RebootRequired: True26AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, int8_t(AP_BattMonitor::Type::NONE), AP_PARAM_FLAG_ENABLE),2728// 2 was VOLT_PIN2930// 3 was CURR_PIN3132// 4 was VOLT_MULT3334// 5 was AMP_PERVLT3536// 6 was AMP_OFFSET3738// @Param: CAPACITY39// @DisplayName: Battery capacity40// @Description: Capacity of the battery in mAh when full41// @Units: mAh42// @Increment: 5043// @User: Standard44AP_GROUPINFO("CAPACITY", 7, AP_BattMonitor_Params, _pack_capacity, AP_BATT_MONITOR_BATTERY_CAPACITY),4546#if AP_BATTERY_WATT_MAX_ENABLED47// @Param{Plane}: WATT_MAX48// @DisplayName: Maximum allowed power (Watts)49// @Description: If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.50// @Units: W51// @Increment: 152// @User: Advanced53AP_GROUPINFO_FRAME("WATT_MAX", 8, AP_BattMonitor_Params, _watt_max, 0, AP_PARAM_FRAME_PLANE),54#endif5556// @Param: SERIAL_NUM57// @DisplayName: Battery serial number58// @Description: Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With DroneCan it is the battery_id.59// @User: Advanced60AP_GROUPINFO("SERIAL_NUM", 9, AP_BattMonitor_Params, _serial_number, AP_BATT_SERIAL_NUMBER_DEFAULT),6162#ifndef HAL_BUILD_AP_PERIPH63// @Param: LOW_TIMER64// @DisplayName: Low voltage timeout65// @Description: This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.66// @Units: s67// @Increment: 168// @Range: 0 12069// @User: Advanced70AP_GROUPINFO("LOW_TIMER", 10, AP_BattMonitor_Params, _low_voltage_timeout, 10),7172// @Param: FS_VOLTSRC73// @DisplayName: Failsafe voltage source74// @Description: Voltage type used for detection of low voltage event75// @Values: 0:Raw Voltage, 1:Sag Compensated Voltage76// @User: Advanced77AP_GROUPINFO("FS_VOLTSRC", 11, AP_BattMonitor_Params, _failsafe_voltage_source, BattMonitor_LowVoltageSource_Raw),7879// @Param: LOW_VOLT80// @DisplayName: Low battery voltage81// @Description: Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the @PREFIX@LOW_TIMER parameter then the vehicle will perform the failsafe specified by the @PREFIX@FS_LOW_ACT parameter.82// @Units: V83// @Increment: 0.184// @User: Standard85AP_GROUPINFO("LOW_VOLT", 12, AP_BattMonitor_Params, _low_voltage, DEFAULT_LOW_BATTERY_VOLTAGE),8687// @Param: LOW_MAH88// @DisplayName: Low battery capacity89// @Description: Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the @PREFIX@FS_LOW_ACT parameter.90// @Units: mAh91// @Increment: 5092// @User: Standard93AP_GROUPINFO("LOW_MAH", 13, AP_BattMonitor_Params, _low_capacity, 0),9495// @Param: CRT_VOLT96// @DisplayName: Critical battery voltage97// @Description: Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the @PREFIX@LOW_TIMER parameter then the vehicle will perform the failsafe specified by the @PREFIX@FS_CRT_ACT parameter.98// @Units: V99// @Increment: 0.1100// @User: Standard101AP_GROUPINFO("CRT_VOLT", 14, AP_BattMonitor_Params, _critical_voltage, 0),102103// @Param: CRT_MAH104// @DisplayName: Battery critical capacity105// @Description: Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the @PREFIX@FS_CRT_ACT parameter.106// @Units: mAh107// @Increment: 50108// @User: Standard109AP_GROUPINFO("CRT_MAH", 15, AP_BattMonitor_Params, _critical_capacity, 0),110111// @Param: FS_LOW_ACT112// @DisplayName: Low battery failsafe action113// @Description: What action the vehicle should perform if it hits a low battery failsafe114// @Values{Plane}: 0:None,1:RTL,2:Land,3:Terminate,4:QLand,6:Loiter to QLand115// @Values{Copter}: 0:None,1:Land,2:RTL,3:SmartRTL or RTL,4:SmartRTL or Land,5:Terminate,6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL116// @Values{Sub}: 0:None,2:Disarm,3:Enter surface mode117// @Values{Rover}: 0:None,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate118// @Values{Tracker}: 0:None119// @Values{Blimp}: 0:None,1:Land120// @User: Standard121AP_GROUPINFO("FS_LOW_ACT", 16, AP_BattMonitor_Params, _failsafe_low_action, 0),122123// @Param: FS_CRT_ACT124// @DisplayName: Critical battery failsafe action125// @Description: What action the vehicle should perform if it hits a critical battery failsafe126// @Values{Plane}: 0:None,1:RTL,2:Land,3:Terminate,4:QLand,5:Parachute,6:Loiter to QLand127// @Values{Copter}: 0:None,1:Land,2:RTL,3:SmartRTL or RTL,4:SmartRTL or Land,5:Terminate,6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL128// @Values{Sub}: 0:None,2:Disarm,3:Enter surface mode129// @Values{Rover}: 0:None,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate130// @Values{Tracker}: 0:None131// @Values{Blimp}: 0:None,1:Land132// @User: Standard133AP_GROUPINFO("FS_CRT_ACT", 17, AP_BattMonitor_Params, _failsafe_critical_action, 0),134135// @Param: ARM_VOLT136// @DisplayName: Required arming voltage137// @Description: Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.138// @Units: V139// @Increment: 0.1140// @User: Advanced141AP_GROUPINFO("ARM_VOLT", 18, AP_BattMonitor_Params, _arming_minimum_voltage, 0),142143// @Param: ARM_MAH144// @DisplayName: Required arming remaining capacity145// @Description: Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the @PREFIX@ARM_VOLT parameter.146// @Units: mAh147// @Increment: 50148// @User: Advanced149AP_GROUPINFO("ARM_MAH", 19, AP_BattMonitor_Params, _arming_minimum_capacity, 0),150151// 20 was BUS152#endif // HAL_BUILD_AP_PERIPH153154#if AP_BATTERY_OPTIONS_PARAM_ENABLED155// @Param: OPTIONS156// @DisplayName: Battery monitor options157// @Description: This sets options to change the behaviour of the battery monitor158// @Bitmask: 0:Ignore DroneCAN SoC, 1:MPPT reports input voltage and current, 2:MPPT Powered off when disarmed, 3:MPPT Powered on when armed, 4:MPPT Powered off at boot, 5:MPPT Powered on at boot, 6:Send resistance compensated voltage to GCS, 7:Allow DroneCAN InfoAux to be from a different CAN node, 8:Battery is for internal autopilot use only, 9:Sum monitor measures minimum voltage instead of average159// @User: Advanced160AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0),161#endif // AP_BATTERY_OPTIONS_PARAM_ENABLED162163#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED164// @Param: ESC_INDEX165// @DisplayName: ESC Telemetry Index to write to166// @Description: ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.167// @Range: 0 10168// @Increment: 1169// @User: Advanced170AP_GROUPINFO("ESC_INDEX", 22, AP_BattMonitor_Params, _esc_telem_outbound_index, 0),171#endif172173AP_GROUPEND174175};176177AP_BattMonitor_Params::AP_BattMonitor_Params(void) {178AP_Param::setup_object_defaults(this, var_info);179}180181#endif // AP_BATTERY_ENABLED182183184