mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: added logging of quadplane desired yaw
makes analysis of takeoffs easier
This commit is contained in:
parent
2d9c3e3d93
commit
fedabd1ace
@ -160,8 +160,15 @@ void Plane::Log_Write_Attitude(void)
|
||||
Vector3f targets; // Package up the targets into a vector for commonality with Copter usage of Log_Wrote_Attitude
|
||||
targets.x = nav_roll_cd;
|
||||
targets.y = nav_pitch_cd;
|
||||
targets.z = 0; //Plane does not have the concept of navyaw. This is a placeholder.
|
||||
|
||||
if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) {
|
||||
// when VTOL active log the copter target yaw
|
||||
targets.z = wrap_360_cd(quadplane.attitude_control->get_att_target_euler_cd().z);
|
||||
} else {
|
||||
//Plane does not have the concept of navyaw. This is a placeholder.
|
||||
targets.z = 0;
|
||||
}
|
||||
|
||||
if (quadplane.tailsitter_active()) {
|
||||
DataFlash.Log_Write_AttitudeView(*quadplane.ahrs_view, targets);
|
||||
} else {
|
||||
|
Loading…
Reference in New Issue
Block a user