mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: autotune: allow access to autotune object and call through for disarm and aux function
This commit is contained in:
parent
94d3e2673a
commit
c0d2c15ac8
@ -809,12 +809,8 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
|
|||||||
}
|
}
|
||||||
|
|
||||||
#if AUTOTUNE_ENABLED == ENABLED
|
#if AUTOTUNE_ENABLED == ENABLED
|
||||||
// save auto tuned parameters
|
// Possibly save auto tuned parameters
|
||||||
if (copter.flightmode == &copter.mode_autotune) {
|
copter.mode_autotune.autotune.disarmed(copter.flightmode == &copter.mode_autotune);
|
||||||
copter.mode_autotune.save_tuning_gains();
|
|
||||||
} else {
|
|
||||||
copter.mode_autotune.reset();
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// we are not in the air
|
// we are not in the air
|
||||||
|
@ -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:
|
// the following functions do not need to be initialised:
|
||||||
case AUX_FUNC::ALTHOLD:
|
case AUX_FUNC::ALTHOLD:
|
||||||
case AUX_FUNC::AUTO:
|
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::BRAKE:
|
||||||
case AUX_FUNC::CIRCLE:
|
case AUX_FUNC::CIRCLE:
|
||||||
case AUX_FUNC::DRIFT:
|
case AUX_FUNC::DRIFT:
|
||||||
@ -291,9 +292,12 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AUTOTUNE_ENABLED == ENABLED
|
#if AUTOTUNE_ENABLED == ENABLED
|
||||||
case AUX_FUNC::AUTOTUNE:
|
case AUX_FUNC::AUTOTUNE_MODE:
|
||||||
do_aux_function_change_mode(Mode::Number::AUTOTUNE, ch_flag);
|
do_aux_function_change_mode(Mode::Number::AUTOTUNE, ch_flag);
|
||||||
break;
|
break;
|
||||||
|
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
|
||||||
|
copter.mode_autotune.autotune.do_aux_function(ch_flag);
|
||||||
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case AUX_FUNC::LAND:
|
case AUX_FUNC::LAND:
|
||||||
|
@ -796,18 +796,12 @@ public:
|
|||||||
bool allows_arming(AP_Arming::Method method) const override { return false; }
|
bool allows_arming(AP_Arming::Method method) const override { return false; }
|
||||||
bool is_autopilot() const override { return false; }
|
bool is_autopilot() const override { return false; }
|
||||||
|
|
||||||
void save_tuning_gains();
|
AutoTune autotune;
|
||||||
void reset();
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
const char *name() const override { return "AUTOTUNE"; }
|
const char *name() const override { return "AUTOTUNE"; }
|
||||||
const char *name4() const override { return "ATUN"; }
|
const char *name4() const override { return "ATUN"; }
|
||||||
|
|
||||||
private:
|
|
||||||
|
|
||||||
AutoTune autotune;
|
|
||||||
|
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -118,19 +118,9 @@ void ModeAutoTune::run()
|
|||||||
autotune.run();
|
autotune.run();
|
||||||
}
|
}
|
||||||
|
|
||||||
void ModeAutoTune::save_tuning_gains()
|
|
||||||
{
|
|
||||||
autotune.save_tuning_gains();
|
|
||||||
}
|
|
||||||
|
|
||||||
void ModeAutoTune::exit()
|
void ModeAutoTune::exit()
|
||||||
{
|
{
|
||||||
autotune.stop();
|
autotune.stop();
|
||||||
}
|
}
|
||||||
|
|
||||||
void ModeAutoTune::reset()
|
|
||||||
{
|
|
||||||
autotune.reset();
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // AUTOTUNE_ENABLED == ENABLED
|
#endif // AUTOTUNE_ENABLED == ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user