mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_InertialSensor_LSM9DS0: Fix the CS.
This commit is contained in:
parent
ad3a3f9366
commit
bb5de8a6a1
@ -22,6 +22,7 @@
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
||||
#include "AP_InertialSensor_LSM9DS0.h"
|
||||
#include "../AP_HAL_Linux/GPIO.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -120,7 +121,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_InertialSensor_LSM9DS0::AP_InertialSensor_LSM9DS0():
|
||||
AP_InertialSensor(),
|
||||
_drdy_pin_xm(NULL),
|
||||
_drdy_pin_a(NULL),
|
||||
_drdy_pin_m(NULL),
|
||||
_drdy_pin_g(NULL),
|
||||
_initialised(false),
|
||||
_lsm9ds0_product_id(AP_PRODUCT_ID_NONE)
|
||||
@ -135,10 +137,17 @@ uint16_t AP_InertialSensor_LSM9DS0::_init_sensor( Sample_rate sample_rate)
|
||||
_spi = hal.spi->device(AP_HAL::SPIDevice_LSM9DS0);
|
||||
_spi_sem = _spi->get_semaphore();
|
||||
|
||||
_drdy_pin_xm = hal.gpio->channel(LSM9DS0_SPI_ACCELMAG_DRDY);
|
||||
_drdy_pin_g = hal.gpio->channel(LSM9DS0_SPI_GYRO_DRDY);
|
||||
_cs_xm = hal.gpio->channel(LSM9DS0_SPI_ACCELMAG_CS);
|
||||
_cs_g = hal.gpio->channel(LSM9DS0_SPI_GYRO_CS);
|
||||
_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);
|
||||
|
||||
_cs_xm = hal.gpio->channel(BBB_P9_17);
|
||||
_cs_g = hal.gpio->channel(BBB_P8_9);
|
||||
|
||||
hal.scheduler->suspend_timer_procs();
|
||||
|
||||
@ -349,20 +358,20 @@ bool AP_InertialSensor_LSM9DS0::_hardware_init(Sample_rate sample_rate)
|
||||
* TODO, read the
|
||||
* status register.
|
||||
*/
|
||||
bool AP_InertialSensor_LSM9DS0::_data_ready()
|
||||
uint8_t AP_InertialSensor_LSM9DS0::_data_ready()
|
||||
{
|
||||
uint8_t rvalue = 0;
|
||||
if (_drdy_pin_g) {
|
||||
if (_drdy_pin_g->read() != 0){
|
||||
rvalue=1;
|
||||
}
|
||||
if (_drdy_pin_xm) {
|
||||
if (_drdy_pin_xm->read() != 0){
|
||||
if (_drdy_pin_a) {
|
||||
if (_drdy_pin_a->read() != 0){
|
||||
rvalue = 3;
|
||||
}
|
||||
}
|
||||
} else if (_drdy_pin_xm) {
|
||||
if (_drdy_pin_xm->read() != 0){
|
||||
} else if (_drdy_pin_a) {
|
||||
if (_drdy_pin_a->read() != 0){
|
||||
rvalue = 2;
|
||||
}
|
||||
}
|
||||
|
@ -10,13 +10,6 @@
|
||||
#include "AP_InertialSensor.h"
|
||||
|
||||
|
||||
// TODO review these pins
|
||||
#define LSM9DS0_SPI_ACCELMAG_CS 1 // Accel and mag chip select pin
|
||||
#define LSM9DS0_SPI_GYRO_CS 2 // Gyro chip select pin
|
||||
#define LSM9DS0_SPI_ACCELMAG_DRDY 3 // Accel and mag data ready pin
|
||||
#define LSM9DS0_SPI_GYRO_DRDY 4 // Gyro data ready pin
|
||||
|
||||
|
||||
// gyro_scale_lsm9ds0 defines the possible full-scale ranges of the gyroscope:
|
||||
enum gyro_scale_lsm9ds0
|
||||
{
|
||||
@ -121,7 +114,8 @@ protected:
|
||||
uint16_t _init_sensor( Sample_rate sample_rate );
|
||||
|
||||
private:
|
||||
AP_HAL::DigitalSource *_drdy_pin_xm;
|
||||
AP_HAL::DigitalSource *_drdy_pin_a;
|
||||
AP_HAL::DigitalSource *_drdy_pin_m;
|
||||
AP_HAL::DigitalSource *_drdy_pin_g;
|
||||
AP_HAL::DigitalSource *_cs_xm;
|
||||
AP_HAL::DigitalSource *_cs_g;
|
||||
@ -169,7 +163,7 @@ private:
|
||||
bool _sample_available();
|
||||
void _read_data_transaction_g();
|
||||
void _read_data_transaction_xm();
|
||||
bool _data_ready();
|
||||
uint8_t _data_ready();
|
||||
void _poll_data(void);
|
||||
uint8_t _register_read_xm( uint8_t reg );
|
||||
uint8_t _register_read_g( uint8_t reg );
|
||||
|
Loading…
Reference in New Issue
Block a user