APM:Libraries
AP_Compass_MAG3110.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #include <utility>
16 
17 #include <AP_HAL/AP_HAL.h>
18 #include <AP_Math/AP_Math.h>
19 #include <stdio.h>
20 
21 #include "AP_Compass_MAG3110.h"
22 
23 extern const AP_HAL::HAL &hal;
24 
25 
26 /*
27 EN:
28  at first glance, the magnetometer MAG3110 consists only of flaws:
29     * noisy, with a bad characteristic, with very large difference on axes
30     * it can't be calibrated in any way, you just have to believe what he has been measured
31     * There are no adjustments and settings, it just sends data with some unknown sensitivity. Or does not sends :)
32     * One and a half setup registers, in which only the frequency of operation and the number of averagings are specified
33     
34     This is a device, wooden to the waist. But of all these shortcomings, its sole and basic virtue arises:
35     * He will never comes buggy or clevers.
36     
37     And since we do not need much from a magnetometer and it is required to calibrate the Ardupilot itself, the device
38     appears in a completely new light - as a reliable info "north is there." What we really need.
39 
40 RUS:
41  на первый взгляд, магнитометр MAG3110 состоит из одних лишь недостатков:
42  * шумный, с кривой характеристикой,
43  * никак не калибруется, приходится просто верить тому что он намерял
44  * нет никаких регулировок и настроек, он просто выдает данные с некой неизвестной чувствительностью. Или не выдает :)
45  * полтора настроечных регистра, в которых задается только частота работы и количество усреднений
46 
47  Такой вот девайс, по пояс деревянный. Но из всех этих недостатков проистекает его единственное и основное достоинство:
48  * он никогда не глючит и не умничает.
49 
50  А так как нам от магнитометра особо много и не требуется, а калибровать Ардупилот и сам умеет, то девайс
51  предстает в совсем новом свете - как надежный указатель "север там". Что нам собственно и надо.
52 
53 */
54 
55 /*
56  the vector length filter can help with noise on the bus, but may
57  interfere with higher level processing. It should really be moved
58  into the AP_Compass_backend code, with a parameter to enable it.
59  */
60 #ifndef MAG3110_ENABLE_LEN_FILTER
61 #define MAG3110_ENABLE_LEN_FILTER 0
62 #endif
63 
64 
65 // Registers
66 #define MAG3110_MAG_REG_STATUS 0x00
67 #define MAG3110_MAG_REG_HXL 0x01
68 #define MAG3110_MAG_REG_HXH 0x02
69 #define MAG3110_MAG_REG_HYL 0x03
70 #define MAG3110_MAG_REG_HYH 0x04
71 #define MAG3110_MAG_REG_HZL 0x05
72 #define MAG3110_MAG_REG_HZH 0x06
73 #define MAG3110_MAG_REG_WHO_AM_I 0x07
74 #define MAG3110_MAG_REG_SYSMODE 0x08
75 #define MAG3110_MAG_REG_CTRL_REG1 0x10
76 #define MAG3110_MAG_REG_CTRL_REG2 0x11
77 
78 #define BIT_STATUS_REG_DATA_READY (1 << 3)
79 
80 
81 
82 
84  : AP_Compass_Backend(compass)
85  , _dev(std::move(dev))
86 {
87 }
88 
91  enum Rotation rotation)
92 {
93  if (!dev) {
94  return nullptr;
95  }
96  AP_Compass_MAG3110 *sensor = new AP_Compass_MAG3110(compass, std::move(dev));
97  if (!sensor || !sensor->init(rotation)) {
98  delete sensor;
99  return nullptr;
100  }
101 
102  return sensor;
103 }
104 
105 
107 {
108 
109  bool success = _hardware_init();
110 
111  if (!success) {
112  return false;
113  }
114 
115  _initialised = true;
116 
117  // perform an initial read
118  read();
119 
120  /* register the compass instance in the frontend */
122 
123  set_rotation(_compass_instance, rotation);
124 
127 
129 
130  // read at 75Hz
132 
133  return true;
134 }
135 
137 {
138 
139  AP_HAL::Semaphore *bus_sem = _dev->get_semaphore();
140  if (!bus_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
141  AP_HAL::panic("MAG3110: Unable to get semaphore");
142  }
143 
144  // initially run the bus at low speed
146 
147  bool ret=false;
148 
149  _dev->set_retries(5);
150 
151  uint8_t sig = 0;
152  bool ack = _dev->read_registers(MAG3110_MAG_REG_WHO_AM_I, &sig, 1);
153  if (!ack || sig != 0xC4) goto exit;
154 
155  ack = _dev->write_register(MAG3110_MAG_REG_CTRL_REG1, 0x01); // active mode 80 Hz ODR with OSR = 1
156  if (!ack) goto exit;
157 
158  hal.scheduler->delay(20);
159 
160  ack = _dev->write_register(MAG3110_MAG_REG_CTRL_REG2, 0xA0); // AUTO_MRST_EN + RAW
161  if (!ack) goto exit;
162 
163  ret = true;
164 
165  _dev->set_retries(3);
166 
167  printf("MAG3110 found on bus 0x%x\n", (uint16_t)_dev->get_bus_id());
168 
169 exit:
171  bus_sem->give();
172  return ret;
173 }
174 
175 
176 // Read Sensor data
178 {
179  {
180  uint8_t status;
181  bool ack = _dev->read_registers(MAG3110_MAG_REG_STATUS, &status, 1);
182 
183  if (!ack || (status & BIT_STATUS_REG_DATA_READY) == 0) {
184  return false;
185  }
186  }
187 
188  uint8_t buf[6];
189  bool ack = _dev->read_registers(MAG3110_MAG_REG_HXL, buf, 6);
190  if (!ack) {
191  return false;
192  }
193 
194  _mag_x = (int16_t)(buf[0] << 8 | buf[1]);
195  _mag_y = (int16_t)(buf[2] << 8 | buf[3]);
196  _mag_z = (int16_t)(buf[4] << 8 | buf[5]);
197 
198  return true;
199 }
200 
201 
202 #define MAG_SCALE (1.0f/10000 / 0.0001f * 1000) // 1 Tesla full scale of +-10000, 1 Gauss = 0,0001 Tesla, library needs milliGauss
203 
205 {
206  if (!_read_sample()) {
207  return;
208  }
209 
210  Vector3f raw_field = Vector3f((float)_mag_x, (float)_mag_y, (float)_mag_z) * MAG_SCALE;
211 
212  // rotate raw_field from sensor frame to body frame
213  rotate_field(raw_field, _compass_instance);
214 
215  // publish raw_field (uncorrected point sample) for calibration use
217 
218  // correct raw_field for known errors
219  correct_field(raw_field, _compass_instance);
220 
221  if (!field_ok(raw_field)) {
222  return;
223  }
224 
226  _mag_x_accum += raw_field.x;
227  _mag_y_accum += raw_field.y;
228  _mag_z_accum += raw_field.z;
229  _accum_count++;
230  if (_accum_count == 10) {
231  _mag_x_accum /= 2;
232  _mag_y_accum /= 2;
233  _mag_z_accum /= 2;
234  _accum_count /= 2;
235  }
236  _sem->give();
237  }
238 }
239 
240 
241 // Read Sensor data
243 {
244  if (!_initialised) {
245  return;
246  }
247 
248  if (!_sem->take_nonblocking()) {
249  return;
250  }
251 
252  if (_accum_count == 0) {
253  /* We're not ready to publish*/
254  _sem->give();
255  return;
256  }
257 
259  field /= _accum_count;
260 
261  _accum_count = 0;
263 
264  _sem->give();
265 
267 }
int printf(const char *fmt,...)
Definition: stdio.c:113
Vector3< float > Vector3f
Definition: vector3.h:246
void set_external(uint8_t instance, bool external)
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
uint32_t get_bus_id(void) const
Definition: Device.h:60
AP_HAL::OwnPtr< AP_HAL::Device > _dev
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
#define MAG3110_MAG_REG_HXL
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
bool field_ok(const Vector3f &field)
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
bool init(enum Rotation rotation)
void set_dev_id(uint8_t instance, uint32_t dev_id)
Rotation
Definition: rotations.h:27
#define MAG_SCALE
virtual void delay(uint16_t ms)=0
void set_device_type(uint8_t devtype)
Definition: Device.h:70
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
virtual bool take_nonblocking() WARN_IF_UNUSED=0
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
uint8_t register_compass(void) const
virtual bool set_speed(Speed speed)=0
#define MAG3110_MAG_REG_WHO_AM_I
T y
Definition: vector3.h:67
T z
Definition: vector3.h:67
AP_Compass_MAG3110(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev)
virtual bool give()=0
static Compass compass
Definition: AHRS_Test.cpp:20
#define MAG3110_MAG_REG_CTRL_REG2
AP_HAL::Semaphore * _sem
#define MAG3110_MAG_REG_STATUS
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation=ROTATION_NONE)
void set_rotation(uint8_t instance, enum Rotation rotation)
#define MAG3110_MAG_REG_CTRL_REG1
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)
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
#define BIT_STATUS_REG_DATA_READY
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
T x
Definition: vector3.h:67