AP_Compass: make AHRS attitude member variables private

This commit is contained in:
Peter Barker 2024-01-12 23:40:22 +11:00 committed by Peter Barker
parent f7e94bcc75
commit cad4bd41e9
1 changed files with 1 additions and 1 deletions

View File

@ -538,7 +538,7 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,
field = R * field;
Matrix3f dcm;
dcm.from_euler(AP::ahrs().roll, AP::ahrs().pitch, radians(yaw_deg));
dcm.from_euler(AP::ahrs().get_roll(), AP::ahrs().get_pitch(), radians(yaw_deg));
// Rotate into body frame using provided yaw
field = dcm.transposed() * field;