mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: fixed SITL compass
This commit is contained in:
parent
f1322252ae
commit
3699932417
|
@ -64,6 +64,7 @@ void AP_Compass_HIL::read()
|
||||||
uint8_t compass_instance = _compass_instance[i];
|
uint8_t compass_instance = _compass_instance[i];
|
||||||
Vector3f field = _compass._hil.field[compass_instance];
|
Vector3f field = _compass._hil.field[compass_instance];
|
||||||
rotate_field(field, compass_instance);
|
rotate_field(field, compass_instance);
|
||||||
|
publish_raw_field(field, hal.scheduler->micros(), compass_instance);
|
||||||
correct_field(field, compass_instance);
|
correct_field(field, compass_instance);
|
||||||
publish_filtered_field(field, compass_instance);
|
publish_filtered_field(field, compass_instance);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue