Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

After a GPS_GLITCH without RC control, set mode to LAND. #299

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion ArduCopter/control_land.pde
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ static bool land_ramp;
static bool land_init(bool ignore_checks)
{
// check if we have GPS and decide which LAND we're going to do
land_with_gps = position_ok();
land_with_gps = position_ok() && !failsafe.gps_glitch;
if (land_with_gps) {
// set target to stopping point
Vector3f stopping_point;
Expand Down
12 changes: 9 additions & 3 deletions ArduCopter/gps_glitch.pde
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,15 @@ static void gps_glitch_on_event() {
failsafe.gps_glitch = true;
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_GPS, ERROR_CODE_FAILSAFE_OCCURRED);

if (motors.armed() && mode_requires_RC(control_mode) && mode_requires_GPS(control_mode) && !failsafe.radio && !failsafe.ekf) {
if(set_mode(ALT_HOLD)) {
gps_glitch_switch_mode_on_resolve = true;
if (motors.armed() && mode_requires_GPS(control_mode) && !failsafe.radio && !failsafe.ekf) {
if (mode_requires_RC(control_mode)) {
if(set_mode(ALT_HOLD)) {
gps_glitch_switch_mode_on_resolve = true;
}
} else {
if(set_mode(LAND)) {
gps_glitch_switch_mode_on_resolve = true;
}
}
}
}
Expand Down