Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp
9317 views
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
// @SortValues: AlphabeticalZeroAtTop
25
// @Values: 0:Disabled
26
// @Values: 3:Analog Voltage Only
27
// @Values: 4:Analog Voltage and Current
28
// @Values: 5:Solo
29
// @Values: 6:Bebop
30
// @Values: 7:SMBus-Generic
31
// @Values: 8:DroneCAN-BatteryInfo
32
// @Values: 9:ESC
33
// @Values: 10:Sum Of Selected Monitors
34
// @Values: 11:FuelFlow
35
// @Values: 12:FuelLevelPWM
36
// @Values: 13:SMBUS-SUI3
37
// @Values: 14:SMBUS-SUI6
38
// @Values: 15:NeoDesign
39
// @Values: 16:SMBus-Maxell
40
// @Values: 17:Generator-Elec
41
// @Values: 18:Generator-Fuel
42
// @Values: 19:Rotoye
43
// @Values: 20:MPPT
44
// @Values: 21:INA2XX (INA226 INA228 INA238 INA231 INA260)
45
// @Values: 22:LTC2946
46
// @Values: 23:Torqeedo
47
// @Values: 24:FuelLevelAnalog
48
// @Values: 25:Synthetic Current and Analog Voltage
49
// @Values: 26:INA239_SPI
50
// @Values: 27:EFI
51
// @Values: 28:AD7091R5
52
// @Values: 29:Scripting
53
// @Values: 30:INA3221
54
// @Values: 31:Analog Current Only
55
// @Values: 32:TIBQ76952-I2C (Periph only)
56
// @User: Standard
57
// @RebootRequired: True
58
AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, int8_t(AP_BattMonitor::Type::NONE), AP_PARAM_FLAG_ENABLE),
59
60
// 2 was VOLT_PIN
61
62
// 3 was CURR_PIN
63
64
// 4 was VOLT_MULT
65
66
// 5 was AMP_PERVLT
67
68
// 6 was AMP_OFFSET
69
70
// @Param: CAPACITY
71
// @DisplayName: Battery capacity
72
// @Description: Capacity of the battery in mAh when full
73
// @Units: mAh
74
// @Increment: 50
75
// @User: Standard
76
AP_GROUPINFO("CAPACITY", 7, AP_BattMonitor_Params, _pack_capacity, AP_BATT_MONITOR_BATTERY_CAPACITY),
77
78
#if AP_BATTERY_WATT_MAX_ENABLED
79
// @Param{Plane,Rover}: WATT_MAX
80
// @DisplayName: Maximum allowed power (Watts)
81
// @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.
82
// @Units: W
83
// @Increment: 1
84
// @User: Advanced
85
AP_GROUPINFO_FRAME("WATT_MAX", 8, AP_BattMonitor_Params, _watt_max, 0, AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_ROVER),
86
#endif
87
88
// @Param: SERIAL_NUM
89
// @DisplayName: Battery serial number
90
// @Description: Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With DroneCan it is the battery_id.
91
// @User: Advanced
92
AP_GROUPINFO("SERIAL_NUM", 9, AP_BattMonitor_Params, _serial_number, AP_BATT_SERIAL_NUMBER_DEFAULT),
93
94
#ifndef HAL_BUILD_AP_PERIPH
95
// @Param: LOW_TIMER
96
// @DisplayName: Low voltage timeout
97
// @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.
98
// @Units: s
99
// @Increment: 1
100
// @Range: 0 120
101
// @User: Advanced
102
AP_GROUPINFO("LOW_TIMER", 10, AP_BattMonitor_Params, _low_voltage_timeout, 10),
103
104
// @Param: FS_VOLTSRC
105
// @DisplayName: Failsafe voltage source
106
// @Description: Voltage type used for detection of low voltage event
107
// @Values: 0:Raw Voltage, 1:Sag Compensated Voltage
108
// @User: Advanced
109
AP_GROUPINFO("FS_VOLTSRC", 11, AP_BattMonitor_Params, _failsafe_voltage_source, BattMonitor_LowVoltageSource_Raw),
110
111
// @Param: LOW_VOLT
112
// @DisplayName: Low battery voltage
113
// @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.
114
// @Units: V
115
// @Increment: 0.1
116
// @User: Standard
117
AP_GROUPINFO("LOW_VOLT", 12, AP_BattMonitor_Params, _low_voltage, DEFAULT_LOW_BATTERY_VOLTAGE),
118
119
// @Param: LOW_MAH
120
// @DisplayName: Low battery capacity
121
// @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.
122
// @Units: mAh
123
// @Increment: 50
124
// @User: Standard
125
AP_GROUPINFO("LOW_MAH", 13, AP_BattMonitor_Params, _low_capacity, 0),
126
127
// @Param: CRT_VOLT
128
// @DisplayName: Critical battery voltage
129
// @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.
130
// @Units: V
131
// @Increment: 0.1
132
// @User: Standard
133
AP_GROUPINFO("CRT_VOLT", 14, AP_BattMonitor_Params, _critical_voltage, 0),
134
135
// @Param: CRT_MAH
136
// @DisplayName: Battery critical capacity
137
// @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.
138
// @Units: mAh
139
// @Increment: 50
140
// @User: Standard
141
AP_GROUPINFO("CRT_MAH", 15, AP_BattMonitor_Params, _critical_capacity, 0),
142
143
// @Param: FS_LOW_ACT
144
// @DisplayName: Low battery failsafe action
145
// @Description: What action the vehicle should perform if it hits a low battery failsafe
146
// @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 Land
147
// @Values{Plane}: 0:Warn only,1:RTL,2:Land,3:Terminate,4:QLand,5:Parachute release,6:Loiter to QLand,7:AUTOLAND or RTL
148
// @Values{Sub}: 0:Warn only,2:Disarm,3:Enter surface mode
149
// @Values{Rover}: 0:Warn only,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate,6:Loiter or Hold
150
// @Values{Tracker}: 0:Warn only
151
// @Values{Blimp}: 0:Warn only,1:Land
152
// @User: Standard
153
AP_GROUPINFO("FS_LOW_ACT", 16, AP_BattMonitor_Params, _failsafe_low_action, 0),
154
155
// @Param: FS_CRT_ACT
156
// @DisplayName: Critical battery failsafe action
157
// @Description: What action the vehicle should perform if it hits a critical battery failsafe
158
// @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 Land
159
// @Values{Plane}: 0:Warn only,1:RTL,2:Land,3:Terminate,4:QLand,5:Parachute,6:Loiter to QLand,7:AUTOLAND or RTL
160
// @Values{Sub}: 0:Warn only,2:Disarm,3:Enter surface mode
161
// @Values{Rover}: 0:Warn only,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate,6:Loiter or Hold
162
// @Values{Tracker}: 0:Warn only
163
// @Values{Blimp}: 0:Warn only,1:Land
164
// @User: Standard
165
AP_GROUPINFO("FS_CRT_ACT", 17, AP_BattMonitor_Params, _failsafe_critical_action, 0),
166
167
// @Param: ARM_VOLT
168
// @DisplayName: Required arming voltage
169
// @Description: Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
170
// @Units: V
171
// @Increment: 0.1
172
// @User: Advanced
173
AP_GROUPINFO("ARM_VOLT", 18, AP_BattMonitor_Params, _arming_minimum_voltage, 0),
174
175
// @Param: ARM_MAH
176
// @DisplayName: Required arming remaining capacity
177
// @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.
178
// @Units: mAh
179
// @Increment: 50
180
// @User: Advanced
181
AP_GROUPINFO("ARM_MAH", 19, AP_BattMonitor_Params, _arming_minimum_capacity, 0),
182
183
// 20 was BUS
184
#endif // HAL_BUILD_AP_PERIPH
185
186
#if AP_BATTERY_OPTIONS_PARAM_ENABLED
187
// @Param: OPTIONS
188
// @DisplayName: Battery monitor options
189
// @Description: This sets options to change the behaviour of the battery monitor
190
// @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-swap
191
// @User: Advanced
192
AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0),
193
#endif // AP_BATTERY_OPTIONS_PARAM_ENABLED
194
195
#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED
196
// @Param: ESC_INDEX
197
// @DisplayName: ESC Telemetry Index to write to
198
// @Description: ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.
199
// @Range: 0 10
200
// @Increment: 1
201
// @User: Advanced
202
AP_GROUPINFO("ESC_INDEX", 22, AP_BattMonitor_Params, _esc_telem_outbound_index, 0),
203
#endif
204
205
AP_GROUPEND
206
207
};
208
209
AP_BattMonitor_Params::AP_BattMonitor_Params(void) {
210
AP_Param::setup_object_defaults(this, var_info);
211
}
212
213
#endif // AP_BATTERY_ENABLED
214
215