AP_Compass: don't apply offsets twice in SITL

This commit is contained in:
Andrew Tridgell 2018-10-19 11:21:07 +11:00
parent 5b955333ce
commit 55e4b64755

View File

@ -116,10 +116,6 @@ void AP_Compass_SITL::_timer()
f.rotate(get_board_orientation());
}
rotate_field(f, _compass_instance[i]);
publish_raw_field(f, _compass_instance[i]);
correct_field(f, _compass_instance[i]);
accumulate_sample(f, _compass_instance[i], 10);
}
}