Browse Source

AP_InertialSensor: use internal drivers for PHMINI

this gets us fast sampling
mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
03b7bc9e65
  1. 4
      libraries/AP_InertialSensor/AP_InertialSensor.cpp

4
libraries/AP_InertialSensor/AP_InertialSensor.cpp

@ -688,6 +688,10 @@ AP_InertialSensor::detect_backends(void) @@ -688,6 +688,10 @@ AP_InertialSensor::detect_backends(void)
} else if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V4) {
_add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.spi->get_device(HAL_INS_ICM20608_NAME), ROTATION_ROLL_180_YAW_90));
_add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_ROLL_180_YAW_90));
} else if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PHMINI) {
// PHMINI uses ICM20608 on the ACCEL_MAG device and a MPU9250 on the old MPU6000 CS line
_add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.spi->get_device(HAL_INS_ICM20608_AM_NAME), ROTATION_ROLL_180));
_add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_ROLL_180));
}
// also add any PX4 backends (eg. canbus sensors)
_add_backend(AP_InertialSensor_PX4::detect(*this));

Loading…
Cancel
Save