mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: fix rotation for bebop AK8963
Set the correct rotation for bebop
This commit is contained in:
parent
7dd0b5fae6
commit
0cd584c293
|
@ -227,6 +227,9 @@ void AP_Compass_AK8963::read()
|
|||
_mag_x_accum = _mag_y_accum = _mag_z_accum = 0;
|
||||
_accum_count = 0;
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
field.rotate(ROTATION_YAW_90);
|
||||
#endif
|
||||
publish_field(field, _compass_instance);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue