mirror of https://github.com/ArduPilot/ardupilot
Copter: FS_OPTIONS defaults to continue pilot controlled modes on GCS failsafe
This commit is contained in:
parent
e1aaea0834
commit
98a41ab005
|
@ -953,7 +953,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @Values: 0:Disabled, 1:Continue if in Auto on RC failsafe only, 2:Continue if in Auto on GCS failsafe only, 3:Continue if in Auto on RC and/or GCS failsafe, 4:Continue if in Guided on RC failsafe only, 8:Continue if landing on any failsafe, 16:Continue if in pilot controlled modes on GCS failsafe, 19:Continue if in Auto on RC and/or GCS failsafe and continue if in pilot controlled modes on GCS failsafe
|
||||
// @Bitmask: 0:Continue if in Auto on RC failsafe, 1:Continue if in Auto on GCS failsafe, 2:Continue if in Guided on RC failsafe, 3:Continue if landing on any failsafe, 4:Continue if in pilot controlled modes on GCS failsafe, 5:Release Gripper
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FS_OPTIONS", 36, ParametersG2, fs_options, 0),
|
||||
AP_GROUPINFO("FS_OPTIONS", 36, ParametersG2, fs_options, (float)Copter::FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL),
|
||||
|
||||
#if MODE_AUTOROTATE_ENABLED == ENABLED
|
||||
// @Group: AROT_
|
||||
|
@ -1568,7 +1568,7 @@ void Copter::convert_fs_options_params(void)
|
|||
}
|
||||
|
||||
// Variable to capture the new FS_OPTIONS setting
|
||||
int32_t fs_options_converted = 0;
|
||||
int32_t fs_options_converted = (int32_t)FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL;
|
||||
|
||||
// If FS_THR_ENABLED is 2 (continue mission), change to RTL and add continue mission to the new FS_OPTIONS parameter
|
||||
if (g.failsafe_throttle == FS_THR_ENABLED_CONTINUE_MISSION) {
|
||||
|
|
Loading…
Reference in New Issue