mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_InertialSensor: fixed setup of DRDY pin on MPU9250
This commit is contained in:
parent
6a6dbe5790
commit
6f9965cc22
@ -206,8 +206,7 @@ uint16_t AP_InertialSensor_MPU9250::_init_sensor( Sample_rate sample_rate )
|
||||
_spi = hal.spi->device(AP_HAL::SPIDevice_MPU9250);
|
||||
_spi_sem = _spi->get_semaphore();
|
||||
_drdy_pin = hal.gpio->channel(BBB_P8_7);
|
||||
// For some reason configuring the pin as an input make the driver fail
|
||||
// _drdy_pin->mode(GPIO_IN);
|
||||
_drdy_pin->mode(HAL_GPIO_INPUT);
|
||||
|
||||
hal.scheduler->suspend_timer_procs();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user