Plane: fixed attitude logging for tailsitters

This commit is contained in:
Andrew Tridgell 2017-03-31 10:37:47 +11:00
parent 6c31a6982b
commit 6a90257d2a

View File

@ -162,7 +162,11 @@ void Plane::Log_Write_Attitude(void)
targets.y = nav_pitch_cd;
targets.z = 0; //Plane does not have the concept of navyaw. This is a placeholder.
DataFlash.Log_Write_Attitude(ahrs, targets);
if (quadplane.tailsitter_active()) {
DataFlash.Log_Write_AttitudeView(*quadplane.ahrs_view, targets);
} else {
DataFlash.Log_Write_Attitude(ahrs, targets);
}
if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) {
// log quadplane PIDs separately from fixed wing PIDs
DataFlash.Log_Write_PID(LOG_PIQR_MSG, quadplane.attitude_control->get_rate_roll_pid().get_pid_info());