Browse Source

Copter: only save autotune gains if disarmed in autotue

mission-4.1.18
Peter Hall 6 years ago committed by Andrew Tridgell
parent
commit
3fe63d5bc0
  1. 1
      ArduCopter/mode.h
  2. 5
      ArduCopter/mode_autotune.cpp
  3. 6
      ArduCopter/motors.cpp

1
ArduCopter/mode.h

@ -499,6 +499,7 @@ public:
void save_tuning_gains(); void save_tuning_gains();
void stop(); void stop();
void reset();
protected: protected:

5
ArduCopter/mode_autotune.cpp

@ -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

6
ArduCopter/motors.cpp

@ -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…
Cancel
Save