Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp
9317 views
#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// @SortValues: AlphabeticalZeroAtTop24// @Values: 0:Disabled25// @Values: 3:Analog Voltage Only26// @Values: 4:Analog Voltage and Current27// @Values: 5:Solo28// @Values: 6:Bebop29// @Values: 7:SMBus-Generic30// @Values: 8:DroneCAN-BatteryInfo31// @Values: 9:ESC32// @Values: 10:Sum Of Selected Monitors33// @Values: 11:FuelFlow34// @Values: 12:FuelLevelPWM35// @Values: 13:SMBUS-SUI336// @Values: 14:SMBUS-SUI637// @Values: 15:NeoDesign38// @Values: 16:SMBus-Maxell39// @Values: 17:Generator-Elec40// @Values: 18:Generator-Fuel41// @Values: 19:Rotoye42// @Values: 20:MPPT43// @Values: 21:INA2XX (INA226 INA228 INA238 INA231 INA260)44// @Values: 22:LTC294645// @Values: 23:Torqeedo46// @Values: 24:FuelLevelAnalog47// @Values: 25:Synthetic Current and Analog Voltage48// @Values: 26:INA239_SPI49// @Values: 27:EFI50// @Values: 28:AD7091R551// @Values: 29:Scripting52// @Values: 30:INA322153// @Values: 31:Analog Current Only54// @Values: 32:TIBQ76952-I2C (Periph only)55// @User: Standard56// @RebootRequired: True57AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, int8_t(AP_BattMonitor::Type::NONE), AP_PARAM_FLAG_ENABLE),5859// 2 was VOLT_PIN6061// 3 was CURR_PIN6263// 4 was VOLT_MULT6465// 5 was AMP_PERVLT6667// 6 was AMP_OFFSET6869// @Param: CAPACITY70// @DisplayName: Battery capacity71// @Description: Capacity of the battery in mAh when full72// @Units: mAh73// @Increment: 5074// @User: Standard75AP_GROUPINFO("CAPACITY", 7, AP_BattMonitor_Params, _pack_capacity, AP_BATT_MONITOR_BATTERY_CAPACITY),7677#if AP_BATTERY_WATT_MAX_ENABLED78// @Param{Plane,Rover}: WATT_MAX79// @DisplayName: Maximum allowed power (Watts)80// @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.81// @Units: W82// @Increment: 183// @User: Advanced84AP_GROUPINFO_FRAME("WATT_MAX", 8, AP_BattMonitor_Params, _watt_max, 0, AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_ROVER),85#endif8687// @Param: SERIAL_NUM88// @DisplayName: Battery serial number89// @Description: Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With DroneCan it is the battery_id.90// @User: Advanced91AP_GROUPINFO("SERIAL_NUM", 9, AP_BattMonitor_Params, _serial_number, AP_BATT_SERIAL_NUMBER_DEFAULT),9293#ifndef HAL_BUILD_AP_PERIPH94// @Param: LOW_TIMER95// @DisplayName: Low voltage timeout96// @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.97// @Units: s98// @Increment: 199// @Range: 0 120100// @User: Advanced101AP_GROUPINFO("LOW_TIMER", 10, AP_BattMonitor_Params, _low_voltage_timeout, 10),102103// @Param: FS_VOLTSRC104// @DisplayName: Failsafe voltage source105// @Description: Voltage type used for detection of low voltage event106// @Values: 0:Raw Voltage, 1:Sag Compensated Voltage107// @User: Advanced108AP_GROUPINFO("FS_VOLTSRC", 11, AP_BattMonitor_Params, _failsafe_voltage_source, BattMonitor_LowVoltageSource_Raw),109110// @Param: LOW_VOLT111// @DisplayName: Low battery voltage112// @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.113// @Units: V114// @Increment: 0.1115// @User: Standard116AP_GROUPINFO("LOW_VOLT", 12, AP_BattMonitor_Params, _low_voltage, DEFAULT_LOW_BATTERY_VOLTAGE),117118// @Param: LOW_MAH119// @DisplayName: Low battery capacity120// @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.121// @Units: mAh122// @Increment: 50123// @User: Standard124AP_GROUPINFO("LOW_MAH", 13, AP_BattMonitor_Params, _low_capacity, 0),125126// @Param: CRT_VOLT127// @DisplayName: Critical battery voltage128// @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.129// @Units: V130// @Increment: 0.1131// @User: Standard132AP_GROUPINFO("CRT_VOLT", 14, AP_BattMonitor_Params, _critical_voltage, 0),133134// @Param: CRT_MAH135// @DisplayName: Battery critical capacity136// @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.137// @Units: mAh138// @Increment: 50139// @User: Standard140AP_GROUPINFO("CRT_MAH", 15, AP_BattMonitor_Params, _critical_capacity, 0),141142// @Param: FS_LOW_ACT143// @DisplayName: Low battery failsafe action144// @Description: What action the vehicle should perform if it hits a low battery failsafe145// @Values{Copter}: 0:Warn only,1:Land,2:RTL,3:SmartRTL or RTL,4:SmartRTL or Land,5:Terminate,6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Brake or Land146// @Values{Plane}: 0:Warn only,1:RTL,2:Land,3:Terminate,4:QLand,5:Parachute release,6:Loiter to QLand,7:AUTOLAND or RTL147// @Values{Sub}: 0:Warn only,2:Disarm,3:Enter surface mode148// @Values{Rover}: 0:Warn only,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate,6:Loiter or Hold149// @Values{Tracker}: 0:Warn only150// @Values{Blimp}: 0:Warn only,1:Land151// @User: Standard152AP_GROUPINFO("FS_LOW_ACT", 16, AP_BattMonitor_Params, _failsafe_low_action, 0),153154// @Param: FS_CRT_ACT155// @DisplayName: Critical battery failsafe action156// @Description: What action the vehicle should perform if it hits a critical battery failsafe157// @Values{Copter}: 0:Warn only,1:Land,2:RTL,3:SmartRTL or RTL,4:SmartRTL or Land,5:Terminate,6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Brake or Land158// @Values{Plane}: 0:Warn only,1:RTL,2:Land,3:Terminate,4:QLand,5:Parachute,6:Loiter to QLand,7:AUTOLAND or RTL159// @Values{Sub}: 0:Warn only,2:Disarm,3:Enter surface mode160// @Values{Rover}: 0:Warn only,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate,6:Loiter or Hold161// @Values{Tracker}: 0:Warn only162// @Values{Blimp}: 0:Warn only,1:Land163// @User: Standard164AP_GROUPINFO("FS_CRT_ACT", 17, AP_BattMonitor_Params, _failsafe_critical_action, 0),165166// @Param: ARM_VOLT167// @DisplayName: Required arming voltage168// @Description: Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.169// @Units: V170// @Increment: 0.1171// @User: Advanced172AP_GROUPINFO("ARM_VOLT", 18, AP_BattMonitor_Params, _arming_minimum_voltage, 0),173174// @Param: ARM_MAH175// @DisplayName: Required arming remaining capacity176// @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.177// @Units: mAh178// @Increment: 50179// @User: Advanced180AP_GROUPINFO("ARM_MAH", 19, AP_BattMonitor_Params, _arming_minimum_capacity, 0),181182// 20 was BUS183#endif // HAL_BUILD_AP_PERIPH184185#if AP_BATTERY_OPTIONS_PARAM_ENABLED186// @Param: OPTIONS187// @DisplayName: Battery monitor options188// @Description: This sets options to change the behaviour of the battery monitor189// @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 average, 10:Allow DroneCAN dynamic node update on hot-swap190// @User: Advanced191AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0),192#endif // AP_BATTERY_OPTIONS_PARAM_ENABLED193194#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED195// @Param: ESC_INDEX196// @DisplayName: ESC Telemetry Index to write to197// @Description: ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.198// @Range: 0 10199// @Increment: 1200// @User: Advanced201AP_GROUPINFO("ESC_INDEX", 22, AP_BattMonitor_Params, _esc_telem_outbound_index, 0),202#endif203204AP_GROUPEND205206};207208AP_BattMonitor_Params::AP_BattMonitor_Params(void) {209AP_Param::setup_object_defaults(this, var_info);210}211212#endif // AP_BATTERY_ENABLED213214215