10 #define LSM9DS1_DEBUG 0 16 void start(
void)
override;
62 void _dump_registers();
AP_HAL::DigitalSource * _drdy_pin_xg
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev, enum Rotation rotation=ROTATION_NONE)
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev
void _set_accel_scale(accel_scale scale)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
void _read_data_transaction_x(uint16_t samples)
AP_HAL::Semaphore * _spi_sem
void _read_data_transaction_g(uint16_t samples)
virtual ~AP_InertialSensor_LSM9DS1()
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
uint8_t _register_read(uint8_t reg)
AP_InertialSensor_LSM9DS1(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev, int drdy_pin_num_xg, enum Rotation rotation)
void _register_write(uint8_t reg, uint8_t val, bool checked=false)
void start(void) override