Browse Source

AC_AutoTune: log 3 axis PIDs during twitch

master
Andrew Tridgell 6 years ago
parent
commit
e279fde505
  1. 4
      libraries/AC_AutoTune/AC_AutoTune.cpp
  2. 3
      libraries/AC_AutoTune/AC_AutoTune.h

4
libraries/AC_AutoTune/AC_AutoTune.cpp

@ -561,7 +561,7 @@ void AC_AutoTune::control_attitude() @@ -561,7 +561,7 @@ void AC_AutoTune::control_attitude()
case TWITCHING: {
// Run the twitching step
// Note: we should be using intra-test gains (which are very close to the original gains but have lower I)
load_gains(GAIN_TWITCH);
// disable rate limits
attitude_control->use_sqrt_controller(false);
@ -664,7 +664,7 @@ void AC_AutoTune::control_attitude() @@ -664,7 +664,7 @@ void AC_AutoTune::control_attitude()
// log this iterations lean angle and rotation rate
Log_Write_AutoTuneDetails(lean_angle, rotation_rate);
DataFlash_Class::instance()->Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
log_pids();
break;
}

3
libraries/AC_AutoTune/AC_AutoTune.h

@ -53,6 +53,9 @@ protected: @@ -53,6 +53,9 @@ protected:
// init pos controller Z velocity and accel limits
virtual void init_z_limits() = 0;
// log PIDs at full rate for during twitch
virtual void log_pids() = 0;
// start tune - virtual so that vehicle code can add additional pre-conditions
virtual bool start(void);

Loading…
Cancel
Save