Copter: remove redundant takeoff_stop from flowhold

This commit is contained in:
Leonard Hall 2018-03-13 15:27:03 +09:00 committed by Randy Mackay
parent a03ddc6798
commit 8ff8364252
2 changed files with 0 additions and 6 deletions

View File

@ -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;
}

View File

@ -104,9 +104,6 @@ bool Copter::ModeFlowHold::init(bool ignore_checks)
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());
// start with INS height