|
|
@ -739,6 +739,12 @@ AP_InertialSensor::detect_backends(void) |
|
|
|
ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_YAW_270)); |
|
|
|
ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_YAW_270)); |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case AP_BoardConfig::PX4_BOARD_FMUV5: |
|
|
|
|
|
|
|
_fast_sampling_mask.set_default(1); |
|
|
|
|
|
|
|
ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("icm20689"), ROTATION_NONE)); |
|
|
|
|
|
|
|
ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("icm20602"), ROTATION_NONE)); |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case AP_BoardConfig::PX4_BOARD_SP01: |
|
|
|
case AP_BoardConfig::PX4_BOARD_SP01: |
|
|
|
_fast_sampling_mask.set_default(1); |
|
|
|
_fast_sampling_mask.set_default(1); |
|
|
|
ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_EXT_NAME), ROTATION_NONE)); |
|
|
|
ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_EXT_NAME), ROTATION_NONE)); |
|
|
|