APM:Libraries
AP_Compass_LIS3MDL.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  Driver by Andrew Tridgell, Nov 2016
17 
18  thanks to Robert Dickenson and the PX4 team for register definitions
19  */
20 #include "AP_Compass_LIS3MDL.h"
21 
22 #include <AP_HAL/AP_HAL.h>
23 #include <utility>
24 #include <AP_Math/AP_Math.h>
25 #include <stdio.h>
26 
27 #define ADDR_CTRL_REG1 0x20
28 #define ADDR_CTRL_REG2 0x21
29 #define ADDR_CTRL_REG3 0x22
30 #define ADDR_CTRL_REG4 0x23
31 #define ADDR_CTRL_REG5 0x24
32 
33 #define ADDR_STATUS_REG 0x27
34 #define ADDR_OUT_X_L 0x28
35 #define ADDR_OUT_X_H 0x29
36 #define ADDR_OUT_Y_L 0x2a
37 #define ADDR_OUT_Y_H 0x2b
38 #define ADDR_OUT_Z_L 0x2c
39 #define ADDR_OUT_Z_H 0x2d
40 #define ADDR_OUT_T_L 0x2e
41 #define ADDR_OUT_T_H 0x2f
42 
43 #define MODE_REG_CONTINOUS_MODE (0 << 0)
44 #define MODE_REG_SINGLE_MODE (1 << 0)
45 
46 #define ADDR_WHO_AM_I 0x0f
47 #define ID_WHO_AM_I 0x3d
48 
49 extern const AP_HAL::HAL &hal;
50 
53  bool force_external,
54  enum Rotation rotation)
55 {
56  if (!dev) {
57  return nullptr;
58  }
59  AP_Compass_LIS3MDL *sensor = new AP_Compass_LIS3MDL(compass, std::move(dev), force_external, rotation);
60  if (!sensor || !sensor->init()) {
61  delete sensor;
62  return nullptr;
63  }
64 
65  return sensor;
66 }
67 
70  bool _force_external,
71  enum Rotation _rotation)
72  : AP_Compass_Backend(compass)
73  , dev(std::move(_dev))
74  , force_external(_force_external)
75  , rotation(_rotation)
76 {
77 }
78 
80 {
82  return false;
83  }
84 
86  dev->set_read_flag(0xC0);
87  }
88 
89  // high retries for init
90  dev->set_retries(10);
91 
92  uint8_t whoami;
93  if (!dev->read_registers(ADDR_WHO_AM_I, &whoami, 1) ||
94  whoami != ID_WHO_AM_I) {
95  // not a 3MDL
96  goto fail;
97  }
98 
100 
101  dev->write_register(ADDR_CTRL_REG1, 0xFC, true); // 80Hz, UHP
102  dev->write_register(ADDR_CTRL_REG2, 0, true); // 4Ga range
103  dev->write_register(ADDR_CTRL_REG3, 0, true); // continuous
104  dev->write_register(ADDR_CTRL_REG4, 0x0C, true); // z-axis ultra high perf
105  dev->write_register(ADDR_CTRL_REG5, 0x40, true); // block-data-update
106 
107  // lower retries for run
108  dev->set_retries(3);
109 
110  dev->get_semaphore()->give();
111 
112  /* register the compass instance in the frontend */
114 
115  printf("Found a LIS3MDL on 0x%x as compass %u\n", dev->get_bus_id(), compass_instance);
116 
118 
119  if (force_external) {
121  }
122 
125 
126  // call timer() at 80Hz
127  dev->register_periodic_callback(1000000U/80U,
129 
130  return true;
131 
132 fail:
133  dev->get_semaphore()->give();
134  return false;
135 }
136 
138 {
139  struct PACKED {
140  int16_t magx;
141  int16_t magy;
142  int16_t magz;
143  } data;
144  const float range_scale = 1000.0f / 6842.0f;
145  Vector3f field;
146 
147  // check data ready
148  uint8_t status;
149  if (!dev->read_registers(ADDR_STATUS_REG, (uint8_t *)&status, 1)) {
150  goto check_registers;
151  }
152  if (!(status & 0x08)) {
153  // data not available yet
154  goto check_registers;
155  }
156 
157  if (!dev->read_registers(ADDR_OUT_X_L, (uint8_t *)&data, sizeof(data))) {
158  goto check_registers;
159  }
160 
161  field(data.magx * range_scale, data.magy * range_scale, data.magz * range_scale);
162 
163  /* rotate raw_field from sensor frame to body frame */
165 
166  /* publish raw_field (uncorrected point sample) for calibration use */
168 
169  /* correct raw_field for known errors */
171 
173  accum += field;
174  accum_count++;
175  _sem->give();
176  }
177 
178 check_registers:
180 }
181 
183 {
184  if (!_sem->take_nonblocking()) {
185  return;
186  }
187  if (accum_count == 0) {
188  _sem->give();
189  return;
190  }
191 
192 #if 0
193  // debugging code for sample rate
194  static uint32_t lastt;
195  static uint32_t total;
196  total += accum_count;
197  uint32_t now = AP_HAL::micros();
198  float dt = (now - lastt) * 1.0e-6;
199  if (dt > 1) {
200  printf("%u samples\n", total);
201  lastt = now;
202  total = 0;
203  }
204 #endif
205 
206  accum /= accum_count;
207 
209 
210  accum.zero();
211  accum_count = 0;
212 
213  _sem->give();
214 }
int printf(const char *fmt,...)
Definition: stdio.c:113
void set_external(uint8_t instance, bool external)
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define ADDR_CTRL_REG2
uint32_t get_bus_id(void) const
Definition: Device.h:60
virtual AP_HAL::Semaphore * get_semaphore()=0
void rotate_field(Vector3f &mag, uint8_t instance)
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
#define ADDR_CTRL_REG3
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define ID_WHO_AM_I
void set_dev_id(uint8_t instance, uint32_t dev_id)
Rotation
Definition: rotations.h:27
bool setup_checked_registers(uint8_t num_regs, uint8_t frequency=10)
Definition: Device.cpp:39
void fail(const char *why)
Definition: eedump.c:28
#define ADDR_CTRL_REG5
void set_device_type(uint8_t devtype)
Definition: Device.h:70
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AP_Compass_LIS3MDL(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external, enum Rotation rotation)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define ADDR_CTRL_REG4
AP_HAL::OwnPtr< AP_HAL::Device > dev
uint8_t register_compass(void) const
enum BusType bus_type(void) const
Definition: Device.h:50
#define ADDR_WHO_AM_I
#define ADDR_CTRL_REG1
virtual bool give()=0
static Compass compass
Definition: AHRS_Test.cpp:20
AP_HAL::Semaphore * _sem
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define ADDR_STATUS_REG
void set_read_flag(uint8_t flag)
Definition: Device.h:221
void set_rotation(uint8_t instance, enum Rotation rotation)
bool check_next_register(void)
Definition: Device.cpp:85
#define PACKED
Definition: AP_Common.h:28
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void publish_raw_field(const Vector3f &mag, uint8_t instance)
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
enum Rotation rotation
uint32_t micros()
Definition: system.cpp:152
void zero()
Definition: vector3.h:182
#define ADDR_OUT_X_L