CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp
Views: 1798
1
#include "AP_BattMonitor_config.h"
2
3
#if AP_BATTERY_ENABLED
4
5
#include <AP_Common/AP_Common.h>
6
#include <AP_Vehicle/AP_Vehicle_Type.h>
7
#include "AP_BattMonitor_Params.h"
8
#include "AP_BattMonitor.h"
9
10
#if APM_BUILD_COPTER_OR_HELI
11
#define DEFAULT_LOW_BATTERY_VOLTAGE 10.5f
12
#else
13
#define DEFAULT_LOW_BATTERY_VOLTAGE 0.0f
14
#endif // APM_BUILD_COPTER_OR_HELI
15
16
#ifndef AP_BATT_MONITOR_BATTERY_CAPACITY
17
#define AP_BATT_MONITOR_BATTERY_CAPACITY 3300
18
#endif
19
20
const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
21
// @Param: MONITOR
22
// @DisplayName: Battery monitoring
23
// @Description: Controls enabling monitoring of the battery's voltage and current
24
// @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:INA3221
25
// @User: Standard
26
// @RebootRequired: True
27
AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, int8_t(AP_BattMonitor::Type::NONE), AP_PARAM_FLAG_ENABLE),
28
29
// 2 was VOLT_PIN
30
31
// 3 was CURR_PIN
32
33
// 4 was VOLT_MULT
34
35
// 5 was AMP_PERVLT
36
37
// 6 was AMP_OFFSET
38
39
// @Param: CAPACITY
40
// @DisplayName: Battery capacity
41
// @Description: Capacity of the battery in mAh when full
42
// @Units: mAh
43
// @Increment: 50
44
// @User: Standard
45
AP_GROUPINFO("CAPACITY", 7, AP_BattMonitor_Params, _pack_capacity, AP_BATT_MONITOR_BATTERY_CAPACITY),
46
47
#if AP_BATTERY_WATT_MAX_ENABLED
48
// @Param{Plane}: WATT_MAX
49
// @DisplayName: Maximum allowed power (Watts)
50
// @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.
51
// @Units: W
52
// @Increment: 1
53
// @User: Advanced
54
AP_GROUPINFO_FRAME("WATT_MAX", 8, AP_BattMonitor_Params, _watt_max, 0, AP_PARAM_FRAME_PLANE),
55
#endif
56
57
// @Param: SERIAL_NUM
58
// @DisplayName: Battery serial number
59
// @Description: Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With DroneCan it is the battery_id.
60
// @User: Advanced
61
AP_GROUPINFO("SERIAL_NUM", 9, AP_BattMonitor_Params, _serial_number, AP_BATT_SERIAL_NUMBER_DEFAULT),
62
63
#ifndef HAL_BUILD_AP_PERIPH
64
// @Param: LOW_TIMER
65
// @DisplayName: Low voltage timeout
66
// @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.
67
// @Units: s
68
// @Increment: 1
69
// @Range: 0 120
70
// @User: Advanced
71
AP_GROUPINFO("LOW_TIMER", 10, AP_BattMonitor_Params, _low_voltage_timeout, 10),
72
73
// @Param: FS_VOLTSRC
74
// @DisplayName: Failsafe voltage source
75
// @Description: Voltage type used for detection of low voltage event
76
// @Values: 0:Raw Voltage, 1:Sag Compensated Voltage
77
// @User: Advanced
78
AP_GROUPINFO("FS_VOLTSRC", 11, AP_BattMonitor_Params, _failsafe_voltage_source, BattMonitor_LowVoltageSource_Raw),
79
80
// @Param: LOW_VOLT
81
// @DisplayName: Low battery voltage
82
// @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.
83
// @Units: V
84
// @Increment: 0.1
85
// @User: Standard
86
AP_GROUPINFO("LOW_VOLT", 12, AP_BattMonitor_Params, _low_voltage, DEFAULT_LOW_BATTERY_VOLTAGE),
87
88
// @Param: LOW_MAH
89
// @DisplayName: Low battery capacity
90
// @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.
91
// @Units: mAh
92
// @Increment: 50
93
// @User: Standard
94
AP_GROUPINFO("LOW_MAH", 13, AP_BattMonitor_Params, _low_capacity, 0),
95
96
// @Param: CRT_VOLT
97
// @DisplayName: Critical battery voltage
98
// @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.
99
// @Units: V
100
// @Increment: 0.1
101
// @User: Standard
102
AP_GROUPINFO("CRT_VOLT", 14, AP_BattMonitor_Params, _critical_voltage, 0),
103
104
// @Param: CRT_MAH
105
// @DisplayName: Battery critical capacity
106
// @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.
107
// @Units: mAh
108
// @Increment: 50
109
// @User: Standard
110
AP_GROUPINFO("CRT_MAH", 15, AP_BattMonitor_Params, _critical_capacity, 0),
111
112
// @Param: FS_LOW_ACT
113
// @DisplayName: Low battery failsafe action
114
// @Description: What action the vehicle should perform if it hits a low battery failsafe
115
// @Values{Plane}: 0:None,1:RTL,2:Land,3:Terminate,4:QLand,6:Loiter to QLand
116
// @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 RTL
117
// @Values{Sub}: 0:None,2:Disarm,3:Enter surface mode
118
// @Values{Rover}: 0:None,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate
119
// @Values{Tracker}: 0:None
120
// @Values{Blimp}: 0:None,1:Land
121
// @User: Standard
122
AP_GROUPINFO("FS_LOW_ACT", 16, AP_BattMonitor_Params, _failsafe_low_action, 0),
123
124
// @Param: FS_CRT_ACT
125
// @DisplayName: Critical battery failsafe action
126
// @Description: What action the vehicle should perform if it hits a critical battery failsafe
127
// @Values{Plane}: 0:None,1:RTL,2:Land,3:Terminate,4:QLand,5:Parachute,6:Loiter to QLand
128
// @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 RTL
129
// @Values{Sub}: 0:None,2:Disarm,3:Enter surface mode
130
// @Values{Rover}: 0:None,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate
131
// @Values{Tracker}: 0:None
132
// @Values{Blimp}: 0:None,1:Land
133
// @User: Standard
134
AP_GROUPINFO("FS_CRT_ACT", 17, AP_BattMonitor_Params, _failsafe_critical_action, 0),
135
136
// @Param: ARM_VOLT
137
// @DisplayName: Required arming voltage
138
// @Description: Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
139
// @Units: V
140
// @Increment: 0.1
141
// @User: Advanced
142
AP_GROUPINFO("ARM_VOLT", 18, AP_BattMonitor_Params, _arming_minimum_voltage, 0),
143
144
// @Param: ARM_MAH
145
// @DisplayName: Required arming remaining capacity
146
// @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.
147
// @Units: mAh
148
// @Increment: 50
149
// @User: Advanced
150
AP_GROUPINFO("ARM_MAH", 19, AP_BattMonitor_Params, _arming_minimum_capacity, 0),
151
152
// 20 was BUS
153
#endif // HAL_BUILD_AP_PERIPH
154
155
#if AP_BATTERY_OPTIONS_PARAM_ENABLED
156
// @Param: OPTIONS
157
// @DisplayName: Battery monitor options
158
// @Description: This sets options to change the behaviour of the battery monitor
159
// @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
160
// @User: Advanced
161
AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0),
162
#endif // AP_BATTERY_OPTIONS_PARAM_ENABLED
163
164
#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED
165
// @Param: ESC_INDEX
166
// @DisplayName: ESC Telemetry Index to write to
167
// @Description: ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.
168
// @Range: 0 10
169
// @Increment: 1
170
// @User: Advanced
171
AP_GROUPINFO("ESC_INDEX", 22, AP_BattMonitor_Params, _esc_telem_outbound_index, 0),
172
#endif
173
174
AP_GROUPEND
175
176
};
177
178
AP_BattMonitor_Params::AP_BattMonitor_Params(void) {
179
AP_Param::setup_object_defaults(this, var_info);
180
}
181
182
#endif // AP_BATTERY_ENABLED
183
184