|
|
|
@ -101,7 +101,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
@@ -101,7 +101,7 @@ 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:None,1:RTL,2:Land,3:Terminate,4:QLand
|
|
|
|
|
// @Values{Plane}: 0:None,1:RTL,2:Land,3:Terminate,4:QLand,6:Loiter to QLand
|
|
|
|
|
// @Values{Copter}: 0:None,1:Land,2:RTL,3:SmartRTL or RTL,4:SmartRTL or Land,5:Terminate,6:Auto DO_LAND_START or RTL
|
|
|
|
|
// @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
|
|
|
|
@ -113,7 +113,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
@@ -113,7 +113,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
|
|
|
|
|
// @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:None,1:RTL,2:Land,3:Terminate,4:QLand,5:Parachute
|
|
|
|
|
// @Values{Plane}: 0:None,1:RTL,2:Land,3:Terminate,4:QLand,5:Parachute,6:Loiter to QLand
|
|
|
|
|
// @Values{Copter}: 0:None,1:Land,2:RTL,3:SmartRTL or RTL,4:SmartRTL or Land,5:Terminate,6:Auto DO_LAND_START or RTL
|
|
|
|
|
// @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
|
|
|
|
|