mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
AC_AutoTune: log 3 axis PIDs during twitch
This commit is contained in:
parent
b5066cffb6
commit
e279fde505
@ -561,7 +561,7 @@ void AC_AutoTune::control_attitude()
|
|||||||
|
|
||||||
case TWITCHING: {
|
case TWITCHING: {
|
||||||
// Run the twitching step
|
// 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
|
// disable rate limits
|
||||||
attitude_control->use_sqrt_controller(false);
|
attitude_control->use_sqrt_controller(false);
|
||||||
@ -664,7 +664,7 @@ void AC_AutoTune::control_attitude()
|
|||||||
// log this iterations lean angle and rotation rate
|
// log this iterations lean angle and rotation rate
|
||||||
Log_Write_AutoTuneDetails(lean_angle, rotation_rate);
|
Log_Write_AutoTuneDetails(lean_angle, rotation_rate);
|
||||||
DataFlash_Class::instance()->Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
|
DataFlash_Class::instance()->Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
|
||||||
|
log_pids();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -53,6 +53,9 @@ protected:
|
|||||||
// init pos controller Z velocity and accel limits
|
// init pos controller Z velocity and accel limits
|
||||||
virtual void init_z_limits() = 0;
|
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
|
// start tune - virtual so that vehicle code can add additional pre-conditions
|
||||||
virtual bool start(void);
|
virtual bool start(void);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user