@ -15,6 +15,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
@@ -15,6 +15,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
// @Description: Controls enabling monitoring of the battery's voltage and current
// @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Maxell,8:UAVCAN-BatteryInfo
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO_FLAGS ( " MONITOR " , 1 , AP_BattMonitor_Params , _type , BattMonitor_TYPE_NONE , AP_PARAM_FLAG_ENABLE ) ,
// @Param: VOLT_PIN
@ -22,6 +23,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
@@ -22,6 +23,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
// @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.
// @Values: -1:Disabled, 0:A0, 1:A1, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 13:Pixhawk2_PM2, 100:PX4-v1
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " VOLT_PIN " , 2 , AP_BattMonitor_Params , _volt_pin , AP_BATT_VOLT_PIN ) ,
// @Param: CURR_PIN
@ -29,6 +31,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
@@ -29,6 +31,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
// @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.
// @Values: -1:Disabled, 1:A1, 2:A2, 3:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 14:Pixhawk2_PM2, 101:PX4-v1
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " CURR_PIN " , 3 , AP_BattMonitor_Params , _curr_pin , AP_BATT_CURR_PIN ) ,
// @Param: VOLT_MULT
@ -54,7 +57,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
@@ -54,7 +57,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
// @Param: CAPACITY
// @DisplayName: Battery capacity
// @Description: Capacity of the battery in mAh when full
// @Units: mA. h
// @Units: mAh
// @Increment: 50
// @User: Standard
AP_GROUPINFO ( " CAPACITY " , 7 , AP_BattMonitor_Params , _pack_capacity , 3300 ) ,
@ -100,7 +103,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
@@ -100,7 +103,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
// @Param: LOW_MAH
// @DisplayName: Low battery capacity
// @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.
// @Units: mA. h
// @Units: mAh
// @Increment: 50
// @User: Standard
AP_GROUPINFO ( " LOW_MAH " , 13 , AP_BattMonitor_Params , _low_capacity , 0 ) ,
@ -116,7 +119,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
@@ -116,7 +119,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
// @Param: CRT_MAH
// @DisplayName: Battery critical capacity
// @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.
// @Units: mA. h
// @Units: mAh
// @Increment: 50
// @User: Standard
AP_GROUPINFO ( " CRT_MAH " , 15 , AP_BattMonitor_Params , _critical_capacity , 0 ) ,
@ -124,22 +127,22 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
@@ -124,22 +127,22 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
// @Param: FS_LOW_ACT
// @DisplayName: Low battery failsafe action
// @Description: What action the vehicle should perform if it hits a low battery failsafe
// @Values{Plane}: 0:Nothing ,1:RTL,2:Land,3:Terminate
// @Values{Copter}: 0:Nothing ,1:Land,2:RTL,3:SmartRTL,4:SmartRTL or Land,5:Terminate
// @Values{Sub}: 0:Nothing ,2:Disarm,3:Enter surface mode
// @Values{Rover}: 0:Nothing ,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate
// @Values{Tracker}: 0:Nothing
// @Values{Plane}: 0:None ,1:RTL,2:Land,3:Terminate
// @Values{Copter}: 0:None ,1:Land,2:RTL,3:SmartRTL,4:SmartRTL or Land,5:Terminate
// @Values{Sub}: 0:None ,2:Disarm,3:Enter surface mode
// @Values{Rover}: 0:None ,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate
// @Values{Tracker}: 0:None
// @User: Standard
AP_GROUPINFO ( " FS_LOW_ACT " , 16 , AP_BattMonitor_Params , _failsafe_low_action , 0 ) ,
// @Param: FS_CRT_ACT
// @DisplayName: Critical battery failsafe action
// @Description: What action the vehicle should perform if it hits a critical battery failsafe
// @Values{Plane}: 0:Nothing ,1:RTL,2:Land,3:Terminate
// @Values{Copter}: 0:Nothing ,1:Land,2:RTL,3:SmartRTL,4:SmartRTL or Land,5:Terminate
// @Values{Sub}: 0:Nothing ,2:Disarm,3:Enter surface mode
// @Values{Rover}: 0:Nothing ,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate
// @Values{Tracker}: 0:Nothing
// @Values{Plane}: 0:None ,1:RTL,2:Land,3:Terminate
// @Values{Copter}: 0:None ,1:Land,2:RTL,3:SmartRTL,4:SmartRTL or Land,5:Terminate
// @Values{Sub}: 0:None ,2:Disarm,3:Enter surface mode
// @Values{Rover}: 0:None ,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate
// @Values{Tracker}: 0:None
// @User: Standard
AP_GROUPINFO ( " FS_CRT_ACT " , 17 , AP_BattMonitor_Params , _failsafe_critical_action , 0 ) ,