APM:Libraries
AP_Compass_LSM303D.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_HAL/AP_HAL.h>
5 #include <AP_HAL/Device.h>
6 #include <AP_Math/AP_Math.h>
7 
8 #include "AP_Compass.h"
9 #include "AP_Compass_Backend.h"
10 
12 {
13 public:
16  enum Rotation = ROTATION_NONE);
17 
18  static constexpr const char *name = "LSM303D";
19 
20  void read() override;
21 
22  virtual ~AP_Compass_LSM303D() { }
23 
24 private:
26 
27  bool init(enum Rotation rotation);
28  uint8_t _register_read(uint8_t reg);
29  void _register_write(uint8_t reg, uint8_t val);
30  void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits);
31  bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size);
32 
33  bool _read_sample();
34 
35  bool _data_ready();
36  bool _hardware_init();
37  void _update();
38  void _disable_i2c();
39  bool _mag_set_range(uint8_t max_ga);
40  bool _mag_set_samplerate(uint16_t frequency);
41 
44 
46  float _mag_x_accum;
47  float _mag_y_accum;
48  float _mag_z_accum;
49  int16_t _mag_x;
50  int16_t _mag_y;
51  int16_t _mag_z;
52  uint8_t _accum_count;
53 
56 
57  uint8_t _mag_range_ga;
58  uint8_t _mag_samplerate;
59  uint8_t _reg7_expected;
60 };
AP_HAL::OwnPtr< AP_HAL::Device > _dev
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation=ROTATION_NONE)
void _register_write(uint8_t reg, uint8_t val)
uint8_t _register_read(uint8_t reg)
AP_Compass_LSM303D(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev)
Rotation
Definition: rotations.h:27
void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
bool _mag_set_samplerate(uint16_t frequency)
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size)
#define constexpr
Definition: AP_HAL_Macros.h:16
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
static Compass compass
Definition: AHRS_Test.cpp:20
bool init(enum Rotation rotation)
Common definitions and utility routines for the ArduPilot libraries.
static constexpr const char * name
AP_HAL::DigitalSource * _drdy_pin_m
bool _mag_set_range(uint8_t max_ga)