mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Copter: log attitude target in degrees
This commit is contained in:
parent
8dee817acf
commit
d5b939fe76
@ -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);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user