mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: Use MPU9250 DRDY pin only on boards that support it
This commit is contained in:
parent
a09fbb4171
commit
34da221c3d
|
@ -205,8 +205,11 @@ uint16_t AP_InertialSensor_MPU9250::_init_sensor( Sample_rate sample_rate )
|
|||
|
||||
_spi = hal.spi->device(AP_HAL::SPIDevice_MPU9250);
|
||||
_spi_sem = _spi->get_semaphore();
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE
|
||||
_drdy_pin = hal.gpio->channel(BBB_P8_7);
|
||||
_drdy_pin->mode(HAL_GPIO_INPUT);
|
||||
#endif
|
||||
|
||||
hal.scheduler->suspend_timer_procs();
|
||||
|
||||
|
@ -642,4 +645,3 @@ float AP_InertialSensor_MPU9250::get_delta_time() const
|
|||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
||||
|
|
Loading…
Reference in New Issue