Copter: log ANG attitude message

This commit is contained in:
Andy Piper 2024-09-10 11:56:22 +01:00 committed by Andrew Tridgell
parent 64a1fda05a
commit 505d05d5f8
2 changed files with 4 additions and 2 deletions

View File

@ -566,7 +566,9 @@ void Copter::loop_rate_logging()
// should be run at 10hz
void Copter::ten_hz_logging_loop()
{
// log attitude data if we're not already logging at the higher rate
// always write AHRS attitude at 10Hz
ahrs.Write_Attitude(attitude_control->get_att_target_euler_rad() * RAD_TO_DEG);
// log attitude controller data if we're not already logging at the higher rate
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
Log_Write_Attitude();
}

View File

@ -75,7 +75,7 @@ void Copter::Log_Write_Control_Tuning()
// Write an attitude packet
void Copter::Log_Write_Attitude()
{
ahrs.Write_Attitude(attitude_control->get_att_target_euler_rad() * RAD_TO_DEG);
attitude_control->Write_ANG();
attitude_control->Write_Rate(*pos_control);
}