APM:Libraries
AP_InertialSensor_LSM9DS0.h
Go to the documentation of this file.
1 #pragma once
2 
3 #define LSM9DS0_DEBUG 0
4 
5 #include <AP_HAL/AP_HAL.h>
6 #include <AP_HAL/SPIDevice.h>
7 
8 #include "AP_InertialSensor.h"
10 
12 {
13 public:
15  void start(void) override;
16  bool update() override;
17 
21  enum Rotation rotation_a = ROTATION_NONE,
22  enum Rotation rotation_g = ROTATION_NONE,
23  enum Rotation rotation_gH = ROTATION_NONE);
24 
25 private:
29  int drdy_pin_num_a, int drdy_pin_num_b,
30  enum Rotation rotation_a,
31  enum Rotation rotation_g,
32  enum Rotation rotation_gH);
33 
35  int16_t x;
36  int16_t y;
37  int16_t z;
38  };
39 
40  enum gyro_scale {
44  };
45 
46  enum accel_scale {
52  };
53 
54  bool _accel_data_ready();
55  bool _gyro_data_ready();
56 
57  void _poll_data();
58 
59  bool _init_sensor();
60  bool _hardware_init();
61 
62  void _gyro_init();
63  void _accel_init();
64 
65  void _gyro_disable_i2c();
66  void _accel_disable_i2c();
67 
68  void _set_gyro_scale(gyro_scale scale);
69  void _set_accel_scale(accel_scale scale);
70 
71  uint8_t _register_read_xm(uint8_t reg);
72  uint8_t _register_read_g(uint8_t reg);
73  void _register_write_xm(uint8_t reg, uint8_t val, bool checked=false);
74  void _register_write_g(uint8_t reg, uint8_t val, bool checked=false);
75 
78 
79 #if LSM9DS0_DEBUG
80  void _dump_registers();
81 #endif
82 
86 
87  /*
88  * If data-ready GPIO pins numbers are not defined (i.e. any negative
89  * value), the fallback approach used is to check if there's new data ready
90  * by reading the status register. It is *strongly* recommended to use
91  * data-ready GPIO pins for performance reasons.
92  */
95  float _gyro_scale;
96  float _accel_scale;
99  uint8_t _gyro_instance;
101 
102  // gyro whoami
103  uint8_t whoami_g;
104 
105  /*
106  for boards that have a separate LSM303D and L3GD20 there can be
107  different rotations for each
108  */
110  enum Rotation _rotation_g; // for L3GD20
111  enum Rotation _rotation_gH; // for L3GD20H
112 };
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_accel
void _set_accel_scale(accel_scale scale)
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)
Rotation
Definition: rotations.h:27
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)
void _set_gyro_scale(gyro_scale scale)
AP_HAL::DigitalSource * _drdy_pin_a
AP_HAL::DigitalSource * _drdy_pin_g
#define PACKED
Definition: AP_Common.h:28
void _register_write_g(uint8_t reg, uint8_t val, bool checked=false)
void _register_write_xm(uint8_t reg, uint8_t val, bool checked=false)