mirror of https://github.com/ArduPilot/ardupilot
Copter: log PIDs at full rate during AUTOTUNE twitch
This commit is contained in:
parent
7939f3488b
commit
b897551e0b
|
@ -455,6 +455,7 @@ protected:
|
|||
void get_pilot_desired_rp_yrate_cd(int32_t &roll_cd, int32_t &pitch_cd, int32_t &yaw_rate_cds) override;
|
||||
void init_z_limits() override;
|
||||
void Log_Write_Event(enum at_event id) override;
|
||||
void log_pids() override;
|
||||
};
|
||||
|
||||
class ModeAutoTune : public Mode {
|
||||
|
|
|
@ -112,6 +112,13 @@ void Copter::AutoTune::init_z_limits()
|
|||
copter.pos_control->set_max_accel_z(copter.g.pilot_accel_z);
|
||||
}
|
||||
|
||||
void Copter::AutoTune::log_pids()
|
||||
{
|
||||
copter.DataFlash.Log_Write_PID(LOG_PIDR_MSG, copter.attitude_control->get_rate_roll_pid().get_pid_info());
|
||||
copter.DataFlash.Log_Write_PID(LOG_PIDP_MSG, copter.attitude_control->get_rate_pitch_pid().get_pid_info());
|
||||
copter.DataFlash.Log_Write_PID(LOG_PIDY_MSG, copter.attitude_control->get_rate_yaw_pid().get_pid_info());
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
Write an event packet. This maps from AC_AutoTune event IDs to
|
||||
|
|
Loading…
Reference in New Issue