Copter: Add option to resume precland after reposiiton
This commit is contained in:
parent
4d437c3368
commit
a7ccfd6f19
@ -667,6 +667,13 @@ void Mode::land_run_horizontal_control()
|
||||
AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE);
|
||||
}
|
||||
copter.ap.land_repo_active = true;
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
} else {
|
||||
// no override right now, check if we should allow precland
|
||||
if (copter.precland.allow_precland_after_reposition()) {
|
||||
copter.ap.land_repo_active = false;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user