3 #define LSM9DS0_DEBUG 0 15 void start(
void)
override;
29 int drdy_pin_num_a,
int drdy_pin_num_b,
80 void _dump_registers();
void _accel_disable_i2c()
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_accel
void _set_accel_scale(accel_scale scale)
void start(void) override
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, enum Rotation rotation_a=ROTATION_NONE, enum Rotation rotation_g=ROTATION_NONE, enum Rotation rotation_gH=ROTATION_NONE)
void _read_data_transaction_g()
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_gyro
AP_InertialSensor_LSM9DS0(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, int drdy_pin_num_a, int drdy_pin_num_b, enum Rotation rotation_a, enum Rotation rotation_g, enum Rotation rotation_gH)
enum Rotation _rotation_a
uint8_t _register_read_g(uint8_t reg)
AP_HAL::Semaphore * _spi_sem
void _set_gyro_scale(gyro_scale scale)
void _read_data_transaction_a()
AP_HAL::DigitalSource * _drdy_pin_a
AP_HAL::DigitalSource * _drdy_pin_g
uint8_t _register_read_xm(uint8_t reg)
virtual ~AP_InertialSensor_LSM9DS0()
enum Rotation _rotation_gH
void _register_write_g(uint8_t reg, uint8_t val, bool checked=false)
enum Rotation _rotation_g
void _register_write_xm(uint8_t reg, uint8_t val, bool checked=false)