APM:Libraries
AP_InertialSensor_LSM9DS1.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #include <AP_HAL/SPIDevice.h>
5 
6 #include "AP_InertialSensor.h"
8 
9 /* enable debug to see a register dump on startup */
10 #define LSM9DS1_DEBUG 0
11 
13 {
14 public:
16  void start(void) override;
17  bool update() override;
18 
21  enum Rotation rotation = ROTATION_NONE);
22 private:
25  int drdy_pin_num_xg,
26  enum Rotation rotation);
27 
29 
31  int16_t x;
32  int16_t y;
33  int16_t z;
34  };
35 
36  enum accel_scale {
41  };
42 
43  void _poll_data();
44  void _fifo_reset();
45 
46  bool _init_sensor();
47  bool _hardware_init();
48 
49  void _gyro_init();
50  void _accel_init();
51 
52  void _set_gyro_scale();
53  void _set_accel_scale(accel_scale scale);
54 
55  uint8_t _register_read(uint8_t reg);
56  void _register_write(uint8_t reg, uint8_t val, bool checked=false);
57 
58  void _read_data_transaction_x(uint16_t samples);
59  void _read_data_transaction_g(uint16_t samples);
60 
61  #if LSM9DS1_DEBUG
62  void _dump_registers();
63  #endif
64 
68  float _gyro_scale;
69  float _accel_scale;
71  uint8_t _gyro_instance;
72  uint8_t _accel_instance;
74 };
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)
Rotation
Definition: rotations.h:27
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev
void _set_accel_scale(accel_scale scale)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
void _read_data_transaction_x(uint16_t samples)
void _read_data_transaction_g(uint16_t samples)
#define PACKED
Definition: AP_Common.h:28
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
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)