AP_HAL_Linux: Set initial rotation on Dark to None

This commit is contained in:
Martin Evans 2016-10-17 19:13:34 +01:00 committed by Lucas De Marchi
parent 6f6112d7c2
commit 0e19b8c9a0
1 changed files with 2 additions and 0 deletions

View File

@ -215,6 +215,8 @@ AP_InertialSensor_MPU9250::AP_InertialSensor_MPU9250(AP_InertialSensor &imu,
, _default_rotation(ROTATION_NONE)
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
, _default_rotation(ROTATION_NONE)
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK
, _default_rotation(ROTATION_NONE)
#else
/* rotate for PXF (and default for other boards) */
, _default_rotation(ROTATION_ROLL_180_YAW_90)