Plane: log: only log yaw and steer PIDs when active

This commit is contained in:
Iampete1 2022-09-16 16:13:19 +01:00 committed by Andrew Tridgell
parent ad32d277ff
commit fef42ecd8c

View File

@ -42,8 +42,14 @@ void Plane::Log_Write_Attitude(void)
logger.Write_PID(LOG_PIDR_MSG, rollController.get_pid_info());
logger.Write_PID(LOG_PIDP_MSG, pitchController.get_pid_info());
logger.Write_PID(LOG_PIDY_MSG, yawController.get_pid_info());
logger.Write_PID(LOG_PIDS_MSG, steerController.get_pid_info());
if (yawController.enabled()) {
logger.Write_PID(LOG_PIDY_MSG, yawController.get_pid_info());
}
if (steerController.active()) {
logger.Write_PID(LOG_PIDS_MSG, steerController.get_pid_info());
}
AP::ahrs().Log_Write();
}