mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
AC_AutoTune: print gains on axis completion
This commit is contained in:
parent
8a7a22e707
commit
0e0f4c86dc
@ -454,6 +454,8 @@ void AC_AutoTune::control_attitude()
|
|||||||
// we've reached the end of a D-up-down PI-up-down tune type cycle
|
// we've reached the end of a D-up-down PI-up-down tune type cycle
|
||||||
next_tune_type(tune_type, true);
|
next_tune_type(tune_type, true);
|
||||||
|
|
||||||
|
report_final_gains(axis);
|
||||||
|
|
||||||
// advance to the next axis
|
// advance to the next axis
|
||||||
bool complete = false;
|
bool complete = false;
|
||||||
switch (axis) {
|
switch (axis) {
|
||||||
|
@ -174,6 +174,9 @@ protected:
|
|||||||
// return current axis string
|
// return current axis string
|
||||||
const char *axis_string() const;
|
const char *axis_string() const;
|
||||||
|
|
||||||
|
// report final gains for a given axis to GCS
|
||||||
|
virtual void report_final_gains(AxisType test_axis) const = 0;
|
||||||
|
|
||||||
// Functions added for heli autotune
|
// Functions added for heli autotune
|
||||||
|
|
||||||
// Add additional updating gain functions specific to heli
|
// Add additional updating gain functions specific to heli
|
||||||
|
Loading…
Reference in New Issue
Block a user