mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-06 16:08:28 -04:00
Plane: fixed VTOL takeoff to ignore lat/lon in mission
we should always takeoff vertically
This commit is contained in:
parent
8a64876eb2
commit
a57f3880d1
@ -2123,7 +2123,11 @@ bool QuadPlane::do_vtol_takeoff(const AP_Mission::Mission_Command& cmd)
|
||||
return false;
|
||||
}
|
||||
|
||||
plane.set_next_WP(cmd.content.location);
|
||||
// we always use the current location in XY for takeoff.
|
||||
Location loc = cmd.content.location;
|
||||
loc.lat = 0;
|
||||
loc.lng = 0;
|
||||
plane.set_next_WP(loc);
|
||||
plane.next_WP_loc.alt = plane.current_loc.alt + cmd.content.location.alt;
|
||||
throttle_wait = false;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user