Copter: do not permit RTL unless home is set

Rover has a similar check for entering RTL

Without this, if you do not have any rally points then we end up
attempting to manipulate an invalid location.
This commit is contained in:
Peter Barker 2018-09-03 21:29:46 +10:00 committed by Randy Mackay
parent ab7ee4fefb
commit 7ad4d95426

View File

@ -12,6 +12,11 @@
// rtl_init - initialise rtl controller
bool Copter::ModeRTL::init(bool ignore_checks)
{
if (!ignore_checks) {
if (!AP::ahrs().home_is_set()) {
return false;
}
}
// initialise waypoint and spline controller
wp_nav->wp_and_spline_init();
build_path(!copter.failsafe.terrain);