|
|
@ -869,6 +869,9 @@ AP_InertialSensor::detect_backends(void) |
|
|
|
for (uint8_t i=0; i<AP::sitl()->imu_count; i++) { |
|
|
|
for (uint8_t i=0; i<AP::sitl()->imu_count; i++) { |
|
|
|
ADD_BACKEND(AP_InertialSensor_SITL::detect(*this, i==1?INS_SITL_SENSOR_B:INS_SITL_SENSOR_A)); |
|
|
|
ADD_BACKEND(AP_InertialSensor_SITL::detect(*this, i==1?INS_SITL_SENSOR_B:INS_SITL_SENSOR_A)); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
#if defined(HAL_SITL_INVENSENSEV3) |
|
|
|
|
|
|
|
ADD_BACKEND(AP_InertialSensor_Invensensev3::probe(*this, hal.i2c_mgr->get_device(1, 1), ROTATION_NONE)); |
|
|
|
|
|
|
|
#endif |
|
|
|
#elif HAL_INS_DEFAULT == HAL_INS_HIL |
|
|
|
#elif HAL_INS_DEFAULT == HAL_INS_HIL |
|
|
|
ADD_BACKEND(AP_InertialSensor_HIL::detect(*this)); |
|
|
|
ADD_BACKEND(AP_InertialSensor_HIL::detect(*this)); |
|
|
|
#elif AP_FEATURE_BOARD_DETECT |
|
|
|
#elif AP_FEATURE_BOARD_DETECT |
|
|
|