Copter: autotune: allow access to autotune object and call through for disarm and aux function

This commit is contained in:
Iampete1 2024-08-04 23:37:09 +01:00 committed by Randy Mackay
parent 94d3e2673a
commit c0d2c15ac8
4 changed files with 9 additions and 25 deletions

View File

@ -809,12 +809,8 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
}
#if AUTOTUNE_ENABLED == ENABLED
// save auto tuned parameters
if (copter.flightmode == &copter.mode_autotune) {
copter.mode_autotune.save_tuning_gains();
} else {
copter.mode_autotune.reset();
}
// Possibly save auto tuned parameters
copter.mode_autotune.autotune.disarmed(copter.flightmode == &copter.mode_autotune);
#endif
// we are not in the air

View File

@ -76,7 +76,8 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi
// the following functions do not need to be initialised:
case AUX_FUNC::ALTHOLD:
case AUX_FUNC::AUTO:
case AUX_FUNC::AUTOTUNE:
case AUX_FUNC::AUTOTUNE_MODE:
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
case AUX_FUNC::BRAKE:
case AUX_FUNC::CIRCLE:
case AUX_FUNC::DRIFT:
@ -291,9 +292,12 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
#endif
#if AUTOTUNE_ENABLED == ENABLED
case AUX_FUNC::AUTOTUNE:
case AUX_FUNC::AUTOTUNE_MODE:
do_aux_function_change_mode(Mode::Number::AUTOTUNE, ch_flag);
break;
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
copter.mode_autotune.autotune.do_aux_function(ch_flag);
break;
#endif
case AUX_FUNC::LAND:

View File

@ -796,18 +796,12 @@ public:
bool allows_arming(AP_Arming::Method method) const override { return false; }
bool is_autopilot() const override { return false; }
void save_tuning_gains();
void reset();
AutoTune autotune;
protected:
const char *name() const override { return "AUTOTUNE"; }
const char *name4() const override { return "ATUN"; }
private:
AutoTune autotune;
};
#endif

View File

@ -118,19 +118,9 @@ void ModeAutoTune::run()
autotune.run();
}
void ModeAutoTune::save_tuning_gains()
{
autotune.save_tuning_gains();
}
void ModeAutoTune::exit()
{
autotune.stop();
}
void ModeAutoTune::reset()
{
autotune.reset();
}
#endif // AUTOTUNE_ENABLED == ENABLED