diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 174ece4f04..d5b88527c7 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -550,7 +550,6 @@ public: void run() override; protected: - bool start(void) override; bool position_ok() override; float get_pilot_desired_climb_rate_cms(void) const override; void get_pilot_desired_rp_yrate_cd(float &roll_cd, float &pitch_cd, float &yaw_rate_cds) override; diff --git a/ArduCopter/mode_autotune.cpp b/ArduCopter/mode_autotune.cpp index 7e37484f99..4be6620afd 100644 --- a/ArduCopter/mode_autotune.cpp +++ b/ArduCopter/mode_autotune.cpp @@ -7,21 +7,6 @@ #if AUTOTUNE_ENABLED == ENABLED bool AutoTune::init() -{ - // use position hold while tuning if we were in QLOITER - bool position_hold = (copter.flightmode->mode_number() == Mode::Number::LOITER || copter.flightmode->mode_number() == Mode::Number::POSHOLD); - - return init_internals(position_hold, - copter.attitude_control, - copter.pos_control, - copter.ahrs_view, - &copter.inertial_nav); -} - -/* - start autotune mode - */ -bool AutoTune::start() { // only allow AutoTune from some flight modes, for example Stabilize, AltHold, PosHold or Loiter modes if (!copter.flightmode->allows_autotune()) { @@ -38,7 +23,14 @@ bool AutoTune::start() return false; } - return AC_AutoTune::start(); + // use position hold while tuning if we were in QLOITER + bool position_hold = (copter.flightmode->mode_number() == Mode::Number::LOITER || copter.flightmode->mode_number() == Mode::Number::POSHOLD); + + return init_internals(position_hold, + copter.attitude_control, + copter.pos_control, + copter.ahrs_view, + &copter.inertial_nav); } void AutoTune::run() @@ -128,7 +120,6 @@ bool ModeAutoTune::init(bool ignore_checks) return autotune.init(); } - void ModeAutoTune::run() { autotune.run();