/**
 * Timer process to poll for new data from the MPU6000.
 */
void AP_InertialSensor_MPU6000::_poll_data(void)
{
    if (hal.scheduler->in_timerprocess()) {
        if (!_spi_sem->take_nonblocking()) {
            /*
              the semaphore being busy is an expected condition when the
              mainline code is calling wait_for_sample() which will
              grab the semaphore. We return now and rely on the mainline
              code grabbing the latest sample.
            */
            return;
        }   
        if (_data_ready()) {
            _last_sample_time_micros = hal.scheduler->micros();
            _read_data_transaction(); 
        }
        _spi_sem->give();
    } else {
        /* Synchronous read - take semaphore */
        if (_spi_sem->take(10)) {
            if (_data_ready()) {
                _last_sample_time_micros = hal.scheduler->micros();
                _read_data_transaction(); 
            }
            _spi_sem->give();
        } else {
            hal.scheduler->panic(
                PSTR("PANIC: AP_InertialSensor_MPU6000::_poll_data "
                     "failed to take SPI semaphore synchronously"));
        }
    }
}
uint16_t AP_InertialSensor_MPU6000::_init_sensor( Sample_rate sample_rate )
{
    if (_initialised) return _mpu6000_product_id;
    _initialised = true;

    _spi = hal.spi->device(AP_HAL::SPIDevice_MPU6000);
    _spi_sem = _spi->get_semaphore();

    /* Pin 70 defined especially to hook
       up PE6 to the hal.gpio abstraction.
       (It is not a valid pin under Arduino.) */
    _drdy_pin = hal.gpio->channel(70);

    hal.scheduler->suspend_timer_procs();

    uint8_t tries = 0;
    do {
        bool success = _hardware_init(sample_rate);
        if (success) {
            hal.scheduler->delay(5+2);
            if (!_spi_sem->take(100)) {
                hal.scheduler->panic(PSTR("MPU6000: Unable to get semaphore"));
            }
            if (_data_ready()) {
                _spi_sem->give();
                break;
            } else {
                hal.console->println_P(
                        PSTR("MPU6000 startup failed: no data ready"));
            }
            _spi_sem->give();
        }
        if (tries++ > 5) {
            hal.scheduler->panic(PSTR("PANIC: failed to boot MPU6000 5 times")); 
        }
    } while (1);

    hal.scheduler->resume_timer_procs();
    

    /* read the first lot of data.
     * _read_data_transaction requires the spi semaphore to be taken by
     * its caller. */
    _last_sample_time_micros = hal.scheduler->micros();
    hal.scheduler->delay(10);
    if (_spi_sem->take(100)) {
        _read_data_transaction();
        _spi_sem->give();
    }

    // start the timer process to read samples
    hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_MPU6000::_poll_data));

#if MPU6000_DEBUG
    _dump_registers();
#endif
    return _mpu6000_product_id;
}
/**
 * Timer process to poll for new data from the MPU6000.
 */
void AP_InertialSensor_MPU6000::_poll_data(void)
{
    if (!_spi_sem->take_nonblocking()) {
        return;
    }   
    if (_data_ready()) {
        _read_data_transaction(); 
    }
    _spi_sem->give();
}
/*
  initialise the sensor
 */
bool AP_InertialSensor_MPU6000::_init_sensor(void)
{
    _spi = hal.spi->device(AP_HAL::SPIDevice_MPU6000);
    _spi_sem = _spi->get_semaphore();

#ifdef MPU6000_DRDY_PIN
    _drdy_pin = hal.gpio->channel(MPU6000_DRDY_PIN);
    _drdy_pin->mode(HAL_GPIO_INPUT);
#endif

    hal.scheduler->suspend_timer_procs();

    uint8_t tries = 0;
    do {
        bool success = _hardware_init();
        if (success) {
            hal.scheduler->delay(5+2);
            if (!_spi_sem->take(100)) {
                return false;
            }
            if (_data_ready()) {
                _spi_sem->give();
                break;
            } else {
                return false;
            }
            _spi_sem->give();
        }
        if (tries++ > 5) {
            hal.console->print_P(PSTR("failed to boot MPU6000 5 times")); 
            return false;
        }
    } while (1);

    // grab the used instances
    _gyro_instance = _imu.register_gyro();
    _accel_instance = _imu.register_accel();

    hal.scheduler->resume_timer_procs();
    
    // start the timer process to read samples
    hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_MPU6000::_poll_data));

#if MPU6000_DEBUG
    _dump_registers();
#endif

    return true;
}
/**
 * Timer process to poll for new data from the MPU6000.
 */
void AP_InertialSensor_MPU6000::_poll_data(void)
{
    if (_data_ready()) {
        if (hal.scheduler->in_timerprocess()) {
            _read_data_from_timerprocess();
        } else {
            /* Synchronous read - take semaphore */
            bool got = _spi_sem->take(10);
            if (got) {
                _last_sample_time_micros = hal.scheduler->micros();
                _read_data_transaction(); 
                _spi_sem->give();
            } else {
                hal.scheduler->panic(
                        PSTR("PANIC: AP_InertialSensor_MPU6000::_poll_data "
                             "failed to take SPI semaphore synchronously"));
            }
        }
    }
}
uint16_t AP_InertialSensor_L3GD20::_init_sensor( Sample_rate sample_rate )
{
    if (_initialised) return _L3GD20_product_id;
    _initialised = true;

    _spi = hal.spi->device(AP_HAL::SPIDevice_L3GD20);
    _spi_sem = _spi->get_semaphore();

#ifdef L3GD20_DRDY_PIN
    _drdy_pin = hal.gpio->channel(L3GD20_DRDY_PIN);
    _drdy_pin->mode(HAL_GPIO_INPUT);
#endif

    hal.scheduler->suspend_timer_procs();

    // Test WHOAMI
    uint8_t whoami = _register_read(ADDR_WHO_AM_I);
    if (whoami != WHO_I_AM) {
        // TODO: we should probably accept multiple chip
        // revisions. This is the one on the PXF
        hal.console->printf("L3GD20: unexpected WHOAMI 0x%x\n", (unsigned)whoami);
        hal.scheduler->panic(PSTR("L3GD20: bad WHOAMI"));
    }

    uint8_t tries = 0;
    do {
        bool success = _hardware_init(sample_rate);
        if (success) {
            hal.scheduler->delay(5+2);
            if (!_spi_sem->take(100)) {
                hal.scheduler->panic(PSTR("L3GD20: Unable to get semaphore"));
            }
            if (_data_ready()) {
                _spi_sem->give();
                break;
            } else {
                hal.console->println_P(
                        PSTR("L3GD20 startup failed: no data ready"));
            }
            _spi_sem->give();
        }
        if (tries++ > 5) {
            hal.scheduler->panic(PSTR("PANIC: failed to boot L3GD20 5 times")); 
        }
    } while (1);

    hal.scheduler->resume_timer_procs();
    

    /* read the first lot of data.
     * _read_data_transaction requires the spi semaphore to be taken by
     * its caller. */
    _last_sample_time_micros = hal.scheduler->micros();
    hal.scheduler->delay(10);
    if (_spi_sem->take(100)) {
        _read_data_transaction();
        _spi_sem->give();
    }

    // start the timer process to read samples
    hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_L3GD20::_poll_data));

#if L3GD20_DEBUG
    _dump_registers();
#endif
    return _L3GD20_product_id;
}
uint16_t AP_InertialSensor_LSM9DS0::_init_sensor( AP_InertialSensor::Sample_rate sample_rate)
{
    if (_initialised) return _lsm9ds0_product_id;
    _initialised = true;

    _spi = hal.spi->device(AP_HAL::SPIDevice_LSM9DS0_AM);
    _spi_sem = _spi->get_semaphore();
    
    _drdy_pin_a = hal.gpio->channel(BBB_P8_8);
    _drdy_pin_m = hal.gpio->channel(BBB_P8_10);
    _drdy_pin_g = hal.gpio->channel(BBB_P8_34);

    // For some reason configuring the pins as an inputs make the driver fail
    // _drdy_pin_a->mode(GPIO_IN);
    // _drdy_pin_m->mode(GPIO_IN);
    // _drdy_pin_g->mode(GPIO_IN);
    
    hal.scheduler->suspend_timer_procs();

    uint8_t tries = 0;
    do {
        bool success = _hardware_init(sample_rate);
        if (success) {
            hal.scheduler->delay(5+2);
            if (!_spi_sem->take(100)) {
                hal.scheduler->panic(PSTR("LSM9DS0: Unable to get semaphore"));
            }
            if (_data_ready()) {
                _spi_sem->give();
                break;
            } else {
                hal.console->println_P(
                        PSTR("LSM9DS0 startup failed: no data ready"));
            }
            _spi_sem->give();
        }
        if (tries++ > 5) {
            hal.scheduler->panic(PSTR("PANIC: failed to boot LSM9DS0 5 times")); 
        }
    } while (1);

    hal.scheduler->resume_timer_procs();
    
    /* read the first lot of data.
     * _read_data_transaction requires the spi semaphore to be taken by
     * its caller. */
    _last_sample_time_micros = hal.scheduler->micros();
    hal.scheduler->delay(10);
    if (_spi_sem->take(100)) {
        _read_data_transaction_g();
        _read_data_transaction_xm();
        _spi_sem->give();
    }

    // start the timer process to read samples
    hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_LSM9DS0::_poll_data));

#if LSM9DS0_DEBUG
    _dump_registers();
#endif
    return _lsm9ds0_product_id;
}