mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Plane: remove dead code from do_vtol_land
This commit is contained in:
parent
569f55f5c6
commit
25224cd261
@ -2179,13 +2179,6 @@ bool QuadPlane::do_vtol_land(const AP_Mission::Mission_Command& cmd)
|
|||||||
|
|
||||||
throttle_wait = false;
|
throttle_wait = false;
|
||||||
landing_detect.lower_limit_start_ms = 0;
|
landing_detect.lower_limit_start_ms = 0;
|
||||||
Location origin = inertial_nav.get_origin();
|
|
||||||
Vector2f diff2d;
|
|
||||||
Vector3f target;
|
|
||||||
diff2d = location_diff(origin, plane.next_WP_loc);
|
|
||||||
target.x = diff2d.x * 100;
|
|
||||||
target.y = diff2d.y * 100;
|
|
||||||
target.z = plane.next_WP_loc.alt - origin.alt;
|
|
||||||
set_alt_target_current();
|
set_alt_target_current();
|
||||||
|
|
||||||
// also update nav_controller for status output
|
// also update nav_controller for status output
|
||||||
|
Loading…
Reference in New Issue
Block a user