Copter: log attitude target in degrees

This commit is contained in:
Andy Piper 2024-09-05 14:02:46 +01:00 committed by Peter Barker
parent 8dee817acf
commit d5b939fe76
1 changed files with 1 additions and 3 deletions

View File

@ -75,9 +75,7 @@ void Copter::Log_Write_Control_Tuning()
// Write an attitude packet
void Copter::Log_Write_Attitude()
{
Vector3f targets = attitude_control->get_att_target_euler_cd();
targets.z = wrap_360_cd(targets.z);
ahrs.Write_Attitude(targets);
ahrs.Write_Attitude(attitude_control->get_att_target_euler_rad() * RAD_TO_DEG);
ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control);
}