mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: mode_auto: don't set takeoff dest from bad current location
This commit is contained in:
parent
0e4b751786
commit
e3da6d69d5
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user