APM:Libraries
AP_Compass_LSM9DS1.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 = ROTATION_NONE);
17 
18  static constexpr const char *name = "LSM9DS1";
19 
20  void read() override;
21 
22  virtual ~AP_Compass_LSM9DS1() {}
23 
24 private:
26  enum Rotation rotation = ROTATION_NONE);
27  bool init();
28  bool _check_id(void);
29  bool _configure(void);
30  bool _set_scale(void);
31  void _update(void);
32 
33  uint8_t _register_read(uint8_t reg);
34  void _register_write(uint8_t reg, uint8_t val);
35  void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits);
36  bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size);
37  void _dump_registers();
38 
41  float _scaling;
42  float _mag_x_accum;
43  float _mag_y_accum;
44  float _mag_z_accum;
45  uint32_t _accum_count;
47 };
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size)
void _register_write(uint8_t reg, uint8_t val)
uint8_t _register_read(uint8_t reg)
Rotation
Definition: rotations.h:27
#define constexpr
Definition: AP_HAL_Macros.h:16
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
AP_Compass_LSM9DS1(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation=ROTATION_NONE)
void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
static Compass compass
Definition: AHRS_Test.cpp:20
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation=ROTATION_NONE)
Common definitions and utility routines for the ArduPilot libraries.
enum Rotation _rotation
AP_HAL::OwnPtr< AP_HAL::Device > _dev
static constexpr const char * name