mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AC_AutoTune: add public reset method
This commit is contained in:
parent
e4f6ffe719
commit
a0d8c04f3e
@ -1215,9 +1215,7 @@ void AC_AutoTune::save_tuning_gains()
|
|||||||
update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS);
|
update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS);
|
||||||
Log_Write_Event(EVENT_AUTOTUNE_SAVEDGAINS);
|
Log_Write_Event(EVENT_AUTOTUNE_SAVEDGAINS);
|
||||||
|
|
||||||
// reset Autotune so that gains are not saved again and autotune can be run again.
|
reset();
|
||||||
mode = UNINITIALISED;
|
|
||||||
axes_completed = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// update_gcs - send message to ground station
|
// update_gcs - send message to ground station
|
||||||
|
@ -37,6 +37,12 @@ public:
|
|||||||
// stop tune, reverting gains
|
// stop tune, reverting gains
|
||||||
void stop();
|
void stop();
|
||||||
|
|
||||||
|
// reset Autotune so that gains are not saved again and autotune can be run again.
|
||||||
|
void reset() {
|
||||||
|
mode = UNINITIALISED;
|
||||||
|
axes_completed = 0;
|
||||||
|
}
|
||||||
|
|
||||||
// var_info for holding Parameter information
|
// var_info for holding Parameter information
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user