mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: quadplane: do_vtol_land remove uneded I reset
This commit is contained in:
parent
f148c3fc44
commit
a350ebb358
@ -2810,7 +2810,6 @@ bool QuadPlane::do_vtol_land(const AP_Mission::Mission_Command& cmd)
|
||||
if (!setup()) {
|
||||
return false;
|
||||
}
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
|
||||
plane.set_next_WP(cmd.content.location);
|
||||
// initially aim for current altitude
|
||||
|
Loading…
Reference in New Issue
Block a user