|
|
|
@ -189,6 +189,8 @@ AP_InertialSensor_MPU9250::AP_InertialSensor_MPU9250(AP_InertialSensor &imu) :
@@ -189,6 +189,8 @@ AP_InertialSensor_MPU9250::AP_InertialSensor_MPU9250(AP_InertialSensor &imu) :
|
|
|
|
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO |
|
|
|
|
/* no rotation needed */ |
|
|
|
|
_default_rotation(ROTATION_NONE) |
|
|
|
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 |
|
|
|
|
_default_rotation(ROTATION_YAW_270) |
|
|
|
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI |
|
|
|
|
_default_rotation(ROTATION_NONE) |
|
|
|
|
#else /* rotate for bbone default (and other boards) */ |
|
|
|
|