mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Compass: default to right mag offsets for SITL
This commit is contained in:
parent
2fe2c8fbda
commit
7ec6522b9d
@ -13,6 +13,9 @@ AP_Compass_SITL::AP_Compass_SITL(Compass &compass):
|
|||||||
if (_sitl != nullptr) {
|
if (_sitl != nullptr) {
|
||||||
_compass._setup_earth_field();
|
_compass._setup_earth_field();
|
||||||
for (uint8_t i=0; i<SITL_NUM_COMPASSES; i++) {
|
for (uint8_t i=0; i<SITL_NUM_COMPASSES; i++) {
|
||||||
|
// default offsets to correct value
|
||||||
|
compass.set_offsets(i, _sitl->mag_ofs);
|
||||||
|
|
||||||
_compass_instance[i] = register_compass();
|
_compass_instance[i] = register_compass();
|
||||||
set_dev_id(_compass_instance[i], AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SITL, i, 0, DEVTYPE_SITL));
|
set_dev_id(_compass_instance[i], AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SITL, i, 0, DEVTYPE_SITL));
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user