Copter: mode_auto: don't set takeoff dest from bad current location

This commit is contained in:
Peter Barker 2019-06-13 12:11:12 +10:00 committed by Randy Mackay
parent 0e4b751786
commit e3da6d69d5

View File

@ -143,6 +143,12 @@ void ModeAuto::takeoff_start(const Location& dest_loc)
Location dest(dest_loc);
if (!copter.current_loc.initialised()) {
// vehicle doesn't know where it is ATM. We should not
// initialise our takeoff destination without knowing this!
return;
}
// set horizontal target
dest.lat = copter.current_loc.lat;
dest.lng = copter.current_loc.lng;