Browse Source

AP_HAL_Linux: Set initial rotation on Dark to None

master
Martin Evans 8 years ago committed by Lucas De Marchi
parent
commit
0e19b8c9a0
  1. 2
      libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp

2
libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp

@ -215,6 +215,8 @@ AP_InertialSensor_MPU9250::AP_InertialSensor_MPU9250(AP_InertialSensor &imu, @@ -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)

Loading…
Cancel
Save