mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: fix rotation for LSM9DS1 compass
Move rotation to the right place. Otherwise live calibration and onboard calibration show different results.
This commit is contained in:
parent
bed521e2b5
commit
67dd4d3efe
|
@ -158,6 +158,10 @@ void AP_Compass_LSM9DS1::_update(void)
|
|||
|
||||
raw_field *= _scaling;
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
||||
raw_field.rotate(ROTATION_ROLL_180);
|
||||
#endif
|
||||
|
||||
// rotate raw_field from sensor frame to body frame
|
||||
rotate_field(raw_field, _compass_instance);
|
||||
|
||||
|
@ -200,10 +204,6 @@ void AP_Compass_LSM9DS1::read()
|
|||
|
||||
hal.scheduler->resume_timer_procs();
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
||||
field.rotate(ROTATION_ROLL_180);
|
||||
#endif
|
||||
|
||||
publish_filtered_field(field, _compass_instance);
|
||||
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue