mirror of https://github.com/ArduPilot/ardupilot
Copter: remove redundant takeoff_stop from flowhold
This commit is contained in:
parent
a03ddc6798
commit
8ff8364252
|
@ -18,9 +18,6 @@ bool Copter::ModeAltHold::init(bool ignore_checks)
|
|||
pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());
|
||||
}
|
||||
|
||||
// stop takeoff if running
|
||||
takeoff_stop();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -103,9 +103,6 @@ bool Copter::ModeFlowHold::init(bool ignore_checks)
|
|||
quality_filtered = 0;
|
||||
flow_pi_xy.reset_I();
|
||||
limited = false;
|
||||
|
||||
// stop takeoff if running
|
||||
copter.takeoff_stop();
|
||||
|
||||
flow_pi_xy.set_dt(1.0/copter.scheduler.get_loop_rate_hz());
|
||||
|
||||
|
|
Loading…
Reference in New Issue