mirror of https://github.com/ArduPilot/ardupilot
Rover: fix to use defined value of failsafe action
This commit is contained in:
parent
2afe72d79f
commit
44360a769d
|
@ -130,7 +130,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||||
// @Description: What to do on a failsafe event
|
// @Description: What to do on a failsafe event
|
||||||
// @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold
|
// @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(fs_action, "FS_ACTION", 2),
|
GSCALAR(fs_action, "FS_ACTION", Failsafe_Action_Hold),
|
||||||
|
|
||||||
// @Param: FS_TIMEOUT
|
// @Param: FS_TIMEOUT
|
||||||
// @DisplayName: Failsafe timeout
|
// @DisplayName: Failsafe timeout
|
||||||
|
|
|
@ -74,24 +74,24 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
|
||||||
RC_Channels::clear_overrides();
|
RC_Channels::clear_overrides();
|
||||||
|
|
||||||
switch (g.fs_action) {
|
switch (g.fs_action) {
|
||||||
case 0:
|
case Failsafe_Action_None:
|
||||||
break;
|
break;
|
||||||
case 1:
|
case Failsafe_Action_RTL:
|
||||||
if (!set_mode(mode_rtl, MODE_REASON_FAILSAFE)) {
|
if (!set_mode(mode_rtl, MODE_REASON_FAILSAFE)) {
|
||||||
set_mode(mode_hold, MODE_REASON_FAILSAFE);
|
set_mode(mode_hold, MODE_REASON_FAILSAFE);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 2:
|
case Failsafe_Action_Hold:
|
||||||
set_mode(mode_hold, MODE_REASON_FAILSAFE);
|
set_mode(mode_hold, MODE_REASON_FAILSAFE);
|
||||||
break;
|
break;
|
||||||
case 3:
|
case Failsafe_Action_SmartRTL:
|
||||||
if (!set_mode(mode_smartrtl, MODE_REASON_FAILSAFE)) {
|
if (!set_mode(mode_smartrtl, MODE_REASON_FAILSAFE)) {
|
||||||
if (!set_mode(mode_rtl, MODE_REASON_FAILSAFE)) {
|
if (!set_mode(mode_rtl, MODE_REASON_FAILSAFE)) {
|
||||||
set_mode(mode_hold, MODE_REASON_FAILSAFE);
|
set_mode(mode_hold, MODE_REASON_FAILSAFE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 4:
|
case Failsafe_Action_SmartRTL_Hold:
|
||||||
if (!set_mode(mode_smartrtl, MODE_REASON_FAILSAFE)) {
|
if (!set_mode(mode_smartrtl, MODE_REASON_FAILSAFE)) {
|
||||||
set_mode(mode_hold, MODE_REASON_FAILSAFE);
|
set_mode(mode_hold, MODE_REASON_FAILSAFE);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue