APM:Libraries
AP_BattMonitor_Params.cpp
Go to the documentation of this file.
1 #include <AP_Common/AP_Common.h>
5 
6 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
7  #define DEFAULT_LOW_BATTERY_VOLTAGE 10.5f
8 #else
9  #define DEFAULT_LOW_BATTERY_VOLTAGE 0.0f
10 #endif // APM_BUILD_TYPE(APM_BUILD_ArduCopter)
11 
13  // @Param: MONITOR
14  // @DisplayName: Battery monitoring
15  // @Description: Controls enabling monitoring of the battery's voltage and current
16  // @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Maxell,8:UAVCAN-BatteryInfo
17  // @User: Standard
18  // @RebootRequired: True
19  AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, BattMonitor_TYPE_NONE, AP_PARAM_FLAG_ENABLE),
20 
21  // @Param: VOLT_PIN
22  // @DisplayName: Battery Voltage sensing pin
23  // @Description: Setting this to 0 ~ 13 will enable battery voltage sensing on pins A0 ~ A13. On the PX4-v1 it should be set to 100. On the Pixhawk, Pixracer and NAVIO boards it should be set to 2, Pixhawk2 Power2 is 13.
24  // @Values: -1:Disabled, 0:A0, 1:A1, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 13:Pixhawk2_PM2, 100:PX4-v1
25  // @User: Standard
26  // @RebootRequired: True
27  AP_GROUPINFO("VOLT_PIN", 2, AP_BattMonitor_Params, _volt_pin, AP_BATT_VOLT_PIN),
28 
29  // @Param: CURR_PIN
30  // @DisplayName: Battery Current sensing pin
31  // @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13. On the PX4-v1 it should be set to 101. On the Pixhawk, Pixracer and NAVIO boards it should be set to 3, Pixhawk2 Power2 is 14.
32  // @Values: -1:Disabled, 1:A1, 2:A2, 3:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 14:Pixhawk2_PM2, 101:PX4-v1
33  // @User: Standard
34  // @RebootRequired: True
35  AP_GROUPINFO("CURR_PIN", 3, AP_BattMonitor_Params, _curr_pin, AP_BATT_CURR_PIN),
36 
37  // @Param: VOLT_MULT
38  // @DisplayName: Voltage Multiplier
39  // @Description: Used to convert the voltage of the voltage sensing pin (@PREFIX@VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick on APM2 or Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
40  // @User: Advanced
41  AP_GROUPINFO("VOLT_MULT", 4, AP_BattMonitor_Params, _volt_multiplier, AP_BATT_VOLTDIVIDER_DEFAULT),
42 
43  // @Param: AMP_PERVLT
44  // @DisplayName: Amps per volt
45  // @Description: Number of amps that a 1V reading on the current sensor corresponds to. On the APM2 or Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
46  // @Units: A/V
47  // @User: Standard
48  AP_GROUPINFO("AMP_PERVLT", 5, AP_BattMonitor_Params, _curr_amp_per_volt, AP_BATT_CURR_AMP_PERVOLT_DEFAULT),
49 
50  // @Param: AMP_OFFSET
51  // @DisplayName: AMP offset
52  // @Description: Voltage offset at zero current on current sensor
53  // @Units: V
54  // @User: Standard
55  AP_GROUPINFO("AMP_OFFSET", 6, AP_BattMonitor_Params, _curr_amp_offset, 0),
56 
57  // @Param: CAPACITY
58  // @DisplayName: Battery capacity
59  // @Description: Capacity of the battery in mAh when full
60  // @Units: mAh
61  // @Increment: 50
62  // @User: Standard
63  AP_GROUPINFO("CAPACITY", 7, AP_BattMonitor_Params, _pack_capacity, 3300),
64 
65  // @Param: WATT_MAX
66  // @DisplayName: Maximum allowed power (Watts)
67  // @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.
68  // @Units: W
69  // @Increment: 1
70  // @User: Advanced
71  AP_GROUPINFO_FRAME("WATT_MAX", 8, AP_BattMonitor_Params, _watt_max, 0, AP_PARAM_FRAME_PLANE),
72 
73  // @Param: SERIAL_NUM
74  // @DisplayName: Battery serial number
75  // @Description: Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
76  // @User: Advanced
77  AP_GROUPINFO("SERIAL_NUM", 9, AP_BattMonitor_Params, _serial_number, AP_BATT_SERIAL_NUMBER_DEFAULT),
78 
79  // @Param: LOW_TIMER
80  // @DisplayName: Low voltage timeout
81  // @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.
82  // @Units: s
83  // @Increment: 1
84  // @Range: 0 120
85  // @User: Advanced
86  AP_GROUPINFO("LOW_TIMER", 10, AP_BattMonitor_Params, _low_voltage_timeout, 10),
87 
88  // @Param: FS_VOLTSRC
89  // @DisplayName: Failsafe voltage source
90  // @Description: Voltage type used for detection of low voltage event
91  // @Values: 0:Raw Voltage, 1:Sag Compensated Voltage
92  // @User: Advanced
93  AP_GROUPINFO("FS_VOLTSRC", 11, AP_BattMonitor_Params, _failsafe_voltage_source, BattMonitor_LowVoltageSource_Raw),
94 
95  // @Param: LOW_VOLT
96  // @DisplayName: Low battery voltage
97  // @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.
98  // @Units: V
99  // @Increment: 0.1
100  // @User: Standard
101  AP_GROUPINFO("LOW_VOLT", 12, AP_BattMonitor_Params, _low_voltage, DEFAULT_LOW_BATTERY_VOLTAGE),
102 
103  // @Param: LOW_MAH
104  // @DisplayName: Low battery capacity
105  // @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.
106  // @Units: mAh
107  // @Increment: 50
108  // @User: Standard
109  AP_GROUPINFO("LOW_MAH", 13, AP_BattMonitor_Params, _low_capacity, 0),
110 
111  // @Param: CRT_VOLT
112  // @DisplayName: Critical battery voltage
113  // @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.
114  // @Units: V
115  // @Increment: 0.1
116  // @User: Standard
117  AP_GROUPINFO("CRT_VOLT", 14, AP_BattMonitor_Params, _critical_voltage, 0),
118 
119  // @Param: CRT_MAH
120  // @DisplayName: Battery critical capacity
121  // @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.
122  // @Units: mAh
123  // @Increment: 50
124  // @User: Standard
125  AP_GROUPINFO("CRT_MAH", 15, AP_BattMonitor_Params, _critical_capacity, 0),
126 
127  // @Param: FS_LOW_ACT
128  // @DisplayName: Low battery failsafe action
129  // @Description: What action the vehicle should perform if it hits a low battery failsafe
130  // @Values{Plane}: 0:None,1:RTL,2:Land,3:Terminate
131  // @Values{Copter}: 0:None,1:Land,2:RTL,3:SmartRTL,4:SmartRTL or Land,5:Terminate
132  // @Values{Sub}: 0:None,2:Disarm,3:Enter surface mode
133  // @Values{Rover}: 0:None,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate
134  // @Values{Tracker}: 0:None
135  // @User: Standard
136  AP_GROUPINFO("FS_LOW_ACT", 16, AP_BattMonitor_Params, _failsafe_low_action, 0),
137 
138  // @Param: FS_CRT_ACT
139  // @DisplayName: Critical battery failsafe action
140  // @Description: What action the vehicle should perform if it hits a critical battery failsafe
141  // @Values{Plane}: 0:None,1:RTL,2:Land,3:Terminate
142  // @Values{Copter}: 0:None,1:Land,2:RTL,3:SmartRTL,4:SmartRTL or Land,5:Terminate
143  // @Values{Sub}: 0:None,2:Disarm,3:Enter surface mode
144  // @Values{Rover}: 0:None,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate
145  // @Values{Tracker}: 0:None
146  // @User: Standard
147  AP_GROUPINFO("FS_CRT_ACT", 17, AP_BattMonitor_Params, _failsafe_critical_action, 0),
148 
150 
151 };
152 
155 }
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
#define AP_BATT_CURR_PIN
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
static const struct AP_Param::GroupInfo var_info[]
#define AP_BATT_VOLT_PIN
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
#define DEFAULT_LOW_BATTERY_VOLTAGE
#define AP_GROUPINFO_FRAME(name, idx, clazz, element, def, frame_flags)
Definition: AP_Param.h:96
Common definitions and utility routines for the ArduPilot libraries.
#define AP_BATT_VOLTDIVIDER_DEFAULT
#define AP_PARAM_FRAME_PLANE
Definition: AP_Param.h:79
#define AP_BATT_SERIAL_NUMBER_DEFAULT
#define AP_BATT_CURR_AMP_PERVOLT_DEFAULT
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214