mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: make AHRS attitude member variables private
This commit is contained in:
parent
f7e94bcc75
commit
cad4bd41e9
|
@ -538,7 +538,7 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,
|
||||||
field = R * field;
|
field = R * field;
|
||||||
|
|
||||||
Matrix3f dcm;
|
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
|
// Rotate into body frame using provided yaw
|
||||||
field = dcm.transposed() * field;
|
field = dcm.transposed() * field;
|
||||||
|
|
Loading…
Reference in New Issue