AP_Compass: handle ROTATION_CUSTOM in SITL

This commit is contained in:
Mark Whitehorn 2020-04-21 10:58:16 -06:00 committed by Andrew Tridgell
parent db1c7d9bdd
commit 570aa929ca

View File

@ -126,7 +126,12 @@ void AP_Compass_SITL::_timer()
if (i == 0) {
// rotate the first compass, allowing for testing of external compass rotation
f.rotate_inverse((enum Rotation)_sitl->mag_orient.get());
// and add in AHRS_ORIENTATION setting if not an external compass
if (get_board_orientation() == ROTATION_CUSTOM) {
f = _sitl->ahrs_rotation * f;
} else {
f.rotate(get_board_orientation());
}
// scale the first compass to simulate sensor scale factor errors
f *= _sitl->mag_scaling;