AP_InertialSensor_MPU9250: Fix SPI CS.

This commit is contained in:
Víctor Mayoral Vilches 2014-06-03 15:12:46 +02:00 committed by Andrew Tridgell
parent 651cb58ebc
commit aa60a89cda
1 changed files with 4 additions and 1 deletions

View File

@ -18,6 +18,7 @@
#include <AP_HAL.h>
#include "AP_InertialSensor_MPU9250.h"
#include "../AP_HAL_Linux/GPIO.h"
extern const AP_HAL::HAL& hal;
@ -201,7 +202,9 @@ 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(66); // BBB_P8_7
_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);
hal.scheduler->suspend_timer_procs();