mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Copter: only save autotune gains if disarmed in autotue
This commit is contained in:
parent
0b1d392342
commit
3fe63d5bc0
@ -499,6 +499,7 @@ public:
|
|||||||
|
|
||||||
void save_tuning_gains();
|
void save_tuning_gains();
|
||||||
void stop();
|
void stop();
|
||||||
|
void reset();
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
@ -173,4 +173,9 @@ void Copter::ModeAutoTune::stop()
|
|||||||
copter.autotune.stop();
|
copter.autotune.stop();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Copter::ModeAutoTune::reset()
|
||||||
|
{
|
||||||
|
copter.autotune.reset();
|
||||||
|
}
|
||||||
|
|
||||||
#endif // AUTOTUNE_ENABLED == ENABLED
|
#endif // AUTOTUNE_ENABLED == ENABLED
|
||||||
|
@ -266,7 +266,11 @@ void Copter::init_disarm_motors()
|
|||||||
|
|
||||||
#if AUTOTUNE_ENABLED == ENABLED
|
#if AUTOTUNE_ENABLED == ENABLED
|
||||||
// save auto tuned parameters
|
// save auto tuned parameters
|
||||||
mode_autotune.save_tuning_gains();
|
if (control_mode == AUTOTUNE) {;
|
||||||
|
mode_autotune.save_tuning_gains();
|
||||||
|
} else {
|
||||||
|
mode_autotune.reset();
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// we are not in the air
|
// we are not in the air
|
||||||
|
Loading…
Reference in New Issue
Block a user