Copter: position control PID logging

This commit is contained in:
Leonard Hall 2021-01-20 11:51:03 +09:00 committed by Randy Mackay
parent a29e2d8920
commit d981de1ff4
1 changed files with 4 additions and 0 deletions

View File

@ -76,6 +76,10 @@ void Copter::Log_Write_Attitude()
logger.Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info());
logger.Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info());
logger.Write_PID(LOG_PIDA_MSG, pos_control->get_accel_z_pid().get_pid_info() );
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS())) {
logger.Write_PID(LOG_PIDN_MSG, pos_control->get_vel_xy_pid().get_pid_info_x());
logger.Write_PID(LOG_PIDE_MSG, pos_control->get_vel_xy_pid().get_pid_info_y());
}
}
}