APM:Libraries
AP_Compass_HMC5843.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 
16 /*
17  * AP_Compass_HMC5843.cpp - Arduino Library for HMC5843 I2C magnetometer
18  * Code by Jordi Muñoz and Jose Julio. DIYDrones.com
19  *
20  * Sensor is connected to I2C port
21  * Sensor is initialized in Continuos mode (10Hz)
22  *
23  */
24 #include <AP_HAL/AP_HAL.h>
25 
26 #ifdef HAL_COMPASS_HMC5843_I2C_ADDR
27 
28 #include <assert.h>
29 #include <utility>
30 #include <stdio.h>
31 
32 #include <AP_Math/AP_Math.h>
33 #include <AP_HAL/AP_HAL.h>
35 
36 #include "AP_Compass_HMC5843.h"
39 
40 extern const AP_HAL::HAL& hal;
41 
42 /*
43  * Defaul address: 0x1E
44  */
45 
46 #define HMC5843_REG_CONFIG_A 0x00
47 // Valid sample averaging for 5883L
48 #define HMC5843_SAMPLE_AVERAGING_1 (0x00 << 5)
49 #define HMC5843_SAMPLE_AVERAGING_2 (0x01 << 5)
50 #define HMC5843_SAMPLE_AVERAGING_4 (0x02 << 5)
51 #define HMC5843_SAMPLE_AVERAGING_8 (0x03 << 5)
52 
53 #define HMC5843_CONF_TEMP_ENABLE (0x80)
54 
55 // Valid data output rates for 5883L
56 #define HMC5843_OSR_0_75HZ (0x00 << 2)
57 #define HMC5843_OSR_1_5HZ (0x01 << 2)
58 #define HMC5843_OSR_3HZ (0x02 << 2)
59 #define HMC5843_OSR_7_5HZ (0x03 << 2)
60 #define HMC5843_OSR_15HZ (0x04 << 2)
61 #define HMC5843_OSR_30HZ (0x05 << 2)
62 #define HMC5843_OSR_75HZ (0x06 << 2)
63 // Sensor operation modes
64 #define HMC5843_OPMODE_NORMAL 0x00
65 #define HMC5843_OPMODE_POSITIVE_BIAS 0x01
66 #define HMC5843_OPMODE_NEGATIVE_BIAS 0x02
67 #define HMC5843_OPMODE_MASK 0x03
68 
69 #define HMC5843_REG_CONFIG_B 0x01
70 #define HMC5883L_GAIN_0_88_GA (0x00 << 5)
71 #define HMC5883L_GAIN_1_30_GA (0x01 << 5)
72 #define HMC5883L_GAIN_1_90_GA (0x02 << 5)
73 #define HMC5883L_GAIN_2_50_GA (0x03 << 5)
74 #define HMC5883L_GAIN_4_00_GA (0x04 << 5)
75 #define HMC5883L_GAIN_4_70_GA (0x05 << 5)
76 #define HMC5883L_GAIN_5_60_GA (0x06 << 5)
77 #define HMC5883L_GAIN_8_10_GA (0x07 << 5)
78 
79 #define HMC5843_GAIN_0_70_GA (0x00 << 5)
80 #define HMC5843_GAIN_1_00_GA (0x01 << 5)
81 #define HMC5843_GAIN_1_50_GA (0x02 << 5)
82 #define HMC5843_GAIN_2_00_GA (0x03 << 5)
83 #define HMC5843_GAIN_3_20_GA (0x04 << 5)
84 #define HMC5843_GAIN_3_80_GA (0x05 << 5)
85 #define HMC5843_GAIN_4_50_GA (0x06 << 5)
86 #define HMC5843_GAIN_6_50_GA (0x07 << 5)
87 
88 #define HMC5843_REG_MODE 0x02
89 #define HMC5843_MODE_CONTINUOUS 0x00
90 #define HMC5843_MODE_SINGLE 0x01
91 
92 #define HMC5843_REG_DATA_OUTPUT_X_MSB 0x03
93 
94 #define HMC5843_REG_ID_A 0x0A
95 
96 
98  bool force_external, enum Rotation rotation)
99  : AP_Compass_Backend(compass)
100  , _bus(bus)
101  , _rotation(rotation)
102  , _force_external(force_external)
103 {
104 }
105 
107 {
108  delete _bus;
109 }
110 
113  bool force_external,
114  enum Rotation rotation)
115 {
116  if (!dev) {
117  return nullptr;
118  }
119  AP_HMC5843_BusDriver *bus = new AP_HMC5843_BusDriver_HALDevice(std::move(dev));
120  if (!bus) {
121  return nullptr;
122  }
123 
124  AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(compass, bus, force_external, rotation);
125  if (!sensor || !sensor->init()) {
126  delete sensor;
127  return nullptr;
128  }
129 
130  return sensor;
131 }
132 
134 {
136 
137  AP_HMC5843_BusDriver *bus =
140  if (!bus) {
141  return nullptr;
142  }
143 
144  AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(compass, bus, false, rotation);
145  if (!sensor || !sensor->init()) {
146  delete sensor;
147  return nullptr;
148  }
149 
150  return sensor;
151 }
152 
154 {
155  AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();
156 
157  if (!bus_sem || !bus_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
158  hal.console->printf("HMC5843: Unable to get bus semaphore\n");
159  return false;
160  }
161 
162  // high retries for init
163  _bus->set_retries(10);
164 
165  if (!_bus->configure()) {
166  hal.console->printf("HMC5843: Could not configure the bus\n");
167  goto errout;
168  }
169 
170  if (!_check_whoami()) {
171  hal.console->printf("HMC5843: not a HMC device\n");
172  goto errout;
173  }
174 
175  if (!_calibrate()) {
176  hal.console->printf("HMC5843: Could not calibrate sensor\n");
177  goto errout;
178  }
179 
180  if (!_setup_sampling_mode()) {
181  goto errout;
182  }
183 
184  if (!_bus->start_measurements()) {
185  hal.console->printf("HMC5843: Could not start measurements on bus\n");
186  goto errout;
187  }
188 
189  _initialised = true;
190 
191  // lower retries for run
192  _bus->set_retries(3);
193 
194  bus_sem->give();
195 
196  // perform an initial read
197  read();
198 
200 
201  set_rotation(_compass_instance, _rotation);
202 
203  _bus->set_device_type(DEVTYPE_HMC5883);
204  set_dev_id(_compass_instance, _bus->get_bus_id());
205 
206  if (_force_external) {
208  }
209 
210  // read from sensor at 75Hz
211  _bus->register_periodic_callback(13333,
213 
214  hal.console->printf("HMC5843 found on bus 0x%x\n", (unsigned)_bus->get_bus_id());
215 
216  return true;
217 
218 errout:
219  bus_sem->give();
220  return false;
221 }
222 
223 /*
224  * take a reading from the magnetometer
225  *
226  * bus semaphore has been taken already by HAL
227  */
229 {
230  bool result = _read_sample();
231 
232  // always ask for a new sample
233  _take_sample();
234 
235  if (!result) {
236  return;
237  }
238 
239  // the _mag_N values are in the range -2048 to 2047, so we can
240  // accumulate up to 15 of them in an int16_t. Let's make it 14
241  // for ease of calculation. We expect to do reads at 10Hz, and
242  // we get new data at most 75Hz, so we don't expect to
243  // accumulate more than 8 before a read
244  // get raw_field - sensor frame, uncorrected
245  Vector3f raw_field = Vector3f(_mag_x, _mag_y, _mag_z);
246  raw_field *= _gain_scale;
247 
248  // rotate to the desired orientation
250  raw_field.rotate(ROTATION_YAW_90);
251  }
252 
253  // rotate raw_field from sensor frame to body frame
254  rotate_field(raw_field, _compass_instance);
255 
256  // publish raw_field (uncorrected point sample) for calibration use
258 
259  // correct raw_field for known errors
260  correct_field(raw_field, _compass_instance);
261 
262  if (!field_ok(raw_field)) {
263  return;
264  }
265 
267  return;
268  }
269  _mag_x_accum += raw_field.x;
270  _mag_y_accum += raw_field.y;
271  _mag_z_accum += raw_field.z;
272  _accum_count++;
273  if (_accum_count == 14) {
274  _mag_x_accum /= 2;
275  _mag_y_accum /= 2;
276  _mag_z_accum /= 2;
277  _accum_count = 7;
278  }
279  _sem->give();
280 }
281 
282 /*
283  * Take accumulated reads from the magnetometer or try to read once if no
284  * valid data
285  *
286  * bus semaphore must not be locked
287  */
289 {
290  if (!_initialised) {
291  // someone has tried to enable a compass for the first time
292  // mid-flight .... we can't do that yet (especially as we won't
293  // have the right orientation!)
294  return;
295  }
296 
297  if (!_sem->take_nonblocking()) {
298  return;
299  }
300 
301  if (_accum_count == 0) {
302  _sem->give();
303  return;
304  }
305 
306  Vector3f field(_mag_x_accum * _scaling[0],
307  _mag_y_accum * _scaling[1],
308  _mag_z_accum * _scaling[2]);
309  field /= _accum_count;
310 
311  _accum_count = 0;
312  _mag_x_accum = _mag_y_accum = _mag_z_accum = 0;
313 
314  _sem->give();
315 
317 }
318 
320 {
321  _gain_scale = (1.0f / 1090) * 1000;
322  if (!_bus->register_write(HMC5843_REG_CONFIG_A,
323  HMC5843_CONF_TEMP_ENABLE |
324  HMC5843_OSR_75HZ |
325  HMC5843_SAMPLE_AVERAGING_1) ||
326  !_bus->register_write(HMC5843_REG_CONFIG_B,
327  HMC5883L_GAIN_1_30_GA) ||
328  !_bus->register_write(HMC5843_REG_MODE,
329  HMC5843_MODE_SINGLE)) {
330  return false;
331  }
332  return true;
333 }
334 
335 /*
336  * Read Sensor data - bus semaphore must be taken
337  */
339 {
340  struct PACKED {
341  be16_t rx;
342  be16_t ry;
343  be16_t rz;
344  } val;
345  int16_t rx, ry, rz;
346 
347  if (!_bus->block_read(HMC5843_REG_DATA_OUTPUT_X_MSB, (uint8_t *) &val, sizeof(val))){
348  return false;
349  }
350 
351  rx = be16toh(val.rx);
352  ry = be16toh(val.rz);
353  rz = be16toh(val.ry);
354 
355  if (rx == -4096 || ry == -4096 || rz == -4096) {
356  // no valid data available
357  return false;
358  }
359 
360  _mag_x = -rx;
361  _mag_y = ry;
362  _mag_z = -rz;
363 
364  return true;
365 }
366 
367 
368 /*
369  ask for a new oneshot sample
370  */
372 {
373  _bus->register_write(HMC5843_REG_MODE,
374  HMC5843_MODE_SINGLE);
375 }
376 
378 {
379  uint8_t id[3];
380  if (!_bus->block_read(HMC5843_REG_ID_A, id, 3)) {
381  // can't talk on bus
382  return false;
383  }
384  if (id[0] != 'H' ||
385  id[1] != '4' ||
386  id[2] != '3') {
387  // not a HMC5x83 device
388  return false;
389  }
390 
391  return true;
392 }
393 
395 {
396  uint8_t calibration_gain;
397  int numAttempts = 0, good_count = 0;
398  bool success = false;
399 
400  calibration_gain = HMC5883L_GAIN_2_50_GA;
401 
402  /*
403  * the expected values are based on observation of real sensors
404  */
405  float expected[3] = { 1.16*600, 1.08*600, 1.16*600 };
406 
407  uint8_t base_config = HMC5843_OSR_15HZ;
408  uint8_t num_samples = 0;
409 
410  while (success == 0 && numAttempts < 25 && good_count < 5) {
411  numAttempts++;
412 
413  // force positiveBias (compass should return 715 for all channels)
414  if (!_bus->register_write(HMC5843_REG_CONFIG_A,
415  base_config | HMC5843_OPMODE_POSITIVE_BIAS)) {
416  // compass not responding on the bus
417  continue;
418  }
419 
420  hal.scheduler->delay(50);
421 
422  // set gains
423  if (!_bus->register_write(HMC5843_REG_CONFIG_B, calibration_gain) ||
424  !_bus->register_write(HMC5843_REG_MODE, HMC5843_MODE_SINGLE)) {
425  continue;
426  }
427 
428  // read values from the compass
429  hal.scheduler->delay(50);
430  if (!_read_sample()) {
431  // we didn't read valid values
432  continue;
433  }
434 
435  num_samples++;
436 
437  float cal[3];
438 
439  // hal.console->printf("mag %d %d %d\n", _mag_x, _mag_y, _mag_z);
440 
441  cal[0] = fabsf(expected[0] / _mag_x);
442  cal[1] = fabsf(expected[1] / _mag_y);
443  cal[2] = fabsf(expected[2] / _mag_z);
444 
445  // hal.console->printf("cal=%.2f %.2f %.2f\n", cal[0], cal[1], cal[2]);
446 
447  // we throw away the first two samples as the compass may
448  // still be changing its state from the application of the
449  // strap excitation. After that we accept values in a
450  // reasonable range
451  if (numAttempts <= 2) {
452  continue;
453  }
454 
455 #define IS_CALIBRATION_VALUE_VALID(val) (val > 0.7f && val < 1.35f)
456 
457  if (IS_CALIBRATION_VALUE_VALID(cal[0]) &&
458  IS_CALIBRATION_VALUE_VALID(cal[1]) &&
459  IS_CALIBRATION_VALUE_VALID(cal[2])) {
460  // hal.console->printf("car=%.2f %.2f %.2f good\n", cal[0], cal[1], cal[2]);
461  good_count++;
462 
463  _scaling[0] += cal[0];
464  _scaling[1] += cal[1];
465  _scaling[2] += cal[2];
466  }
467 
468 #undef IS_CALIBRATION_VALUE_VALID
469 
470 #if 0
471  /* useful for debugging */
472  hal.console->printf("MagX: %d MagY: %d MagZ: %d\n", (int)_mag_x, (int)_mag_y, (int)_mag_z);
473  hal.console->printf("CalX: %.2f CalY: %.2f CalZ: %.2f\n", cal[0], cal[1], cal[2]);
474 #endif
475  }
476 
477  _bus->register_write(HMC5843_REG_CONFIG_A, base_config);
478 
479  if (good_count >= 5) {
480  _scaling[0] = _scaling[0] / good_count;
481  _scaling[1] = _scaling[1] / good_count;
482  _scaling[2] = _scaling[2] / good_count;
483  success = true;
484  } else {
485  /* best guess */
486  _scaling[0] = 1.0;
487  _scaling[1] = 1.0;
488  _scaling[2] = 1.0;
489  if (num_samples > 5) {
490  // a sensor can be broken for calibration but still
491  // otherwise workable, accept it if we are reading samples
492  success = true;
493  }
494  }
495 
496 #if 0
497  printf("scaling: %.2f %.2f %.2f\n",
498  _scaling[0], _scaling[1], _scaling[2]);
499 #endif
500 
501  return success;
502 }
503 
504 /* AP_HAL::Device implementation of the HMC5843 */
506  : _dev(std::move(dev))
507 {
508  // set read and auto-increment flags on SPI
509  if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
510  _dev->set_read_flag(0xC0);
511  }
512 }
513 
514 bool AP_HMC5843_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
515 {
516  return _dev->read_registers(reg, buf, size);
517 }
518 
519 bool AP_HMC5843_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)
520 {
521  return _dev->read_registers(reg, val, 1);
522 }
523 
524 bool AP_HMC5843_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val)
525 {
526  return _dev->write_register(reg, val);
527 }
528 
530 {
531  return _dev->get_semaphore();
532 }
533 
534 AP_HAL::Device::PeriodicHandle AP_HMC5843_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
535 {
536  return _dev->register_periodic_callback(period_usec, cb);
537 }
538 
539 
540 /* HMC5843 on an auxiliary bus of IMU driver */
542  uint8_t addr)
543 {
544  /*
545  * Only initialize members. Fails are handled by configure or while
546  * getting the semaphore
547  */
548  _bus = ins.get_auxiliary_bus(backend_id);
549  if (!_bus) {
550  return;
551  }
552 
553  _slave = _bus->request_next_slave(addr);
554 }
555 
557 {
558  /* After started it's owned by AuxiliaryBus */
559  if (!_started) {
560  delete _slave;
561  }
562 }
563 
564 bool AP_HMC5843_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
565 {
566  if (_started) {
567  /*
568  * We can only read a block when reading the block of sample values -
569  * calling with any other value is a mistake
570  */
571  assert(reg == HMC5843_REG_DATA_OUTPUT_X_MSB);
572 
573  int n = _slave->read(buf);
574  return n == static_cast<int>(size);
575  }
576 
577  int r = _slave->passthrough_read(reg, buf, size);
578 
579  return r > 0 && static_cast<uint32_t>(r) == size;
580 }
581 
582 bool AP_HMC5843_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)
583 {
584  return _slave->passthrough_read(reg, val, 1) == 1;
585 }
586 
587 bool AP_HMC5843_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val)
588 {
589  return _slave->passthrough_write(reg, val) == 1;
590 }
591 
593 {
594  return _bus->get_semaphore();
595 }
596 
597 
599 {
600  if (!_bus || !_slave) {
601  return false;
602  }
603  return true;
604 }
605 
607 {
608  if (_bus->register_periodic_read(_slave, HMC5843_REG_DATA_OUTPUT_X_MSB, 6) < 0) {
609  return false;
610  }
611 
612  _started = true;
613 
614  return true;
615 }
616 
617 AP_HAL::Device::PeriodicHandle AP_HMC5843_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
618 {
619  return _bus->register_periodic_callback(period_usec, cb);
620 }
621 
622 // set device type within a device class
624 {
625  _bus->set_device_type(devtype);
626 }
627 
628 // return 24 bit bus identifier
630 {
631  return _bus->get_bus_id();
632 }
633 
634 #endif
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
int printf(const char *fmt,...)
Definition: stdio.c:113
#define HAL_INS_MPU60XX_SPI
Definition: AP_HAL_Boards.h:79
void read() override
AP_HAL::Semaphore * get_semaphore() override
bool register_write(uint8_t reg, uint8_t val) override
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
AP_Compass_HMC5843(Compass &compass, AP_HMC5843_BusDriver *bus, bool force_external, enum Rotation rotation)
void set_device_type(uint8_t devtype) override
Vector3< float > Vector3f
Definition: vector3.h:246
bool register_read(uint8_t reg, uint8_t *val) override
void set_external(uint8_t instance, bool external)
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define HAL_COMPASS_HMC5843_I2C_ADDR
void rotate_field(Vector3f &mag, uint8_t instance)
bool register_read(uint8_t reg, uint8_t *val) override
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
bool field_ok(const Vector3f &field)
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
const char * result
Definition: Printf.cpp:16
void set_dev_id(uint8_t instance, uint32_t dev_id)
Rotation
Definition: rotations.h:27
static AP_InertialSensor ins
Definition: AHRS_Test.cpp:18
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual bool take_nonblocking() WARN_IF_UNUSED=0
bool register_write(uint8_t reg, uint8_t val) override
static uint16_t be16toh(be16_t value)
Definition: sparse-endian.h:83
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
uint8_t register_compass(void) const
AuxiliaryBusSlave * request_next_slave(uint8_t addr)
T y
Definition: vector3.h:67
void * PeriodicHandle
Definition: Device.h:42
T z
Definition: vector3.h:67
AP_HAL::Semaphore * get_semaphore() override
uint32_t get_bus_id(void) const override
virtual bool give()=0
static Compass compass
Definition: AHRS_Test.cpp:20
bool _setup_sampling_mode()
AP_HAL::Semaphore * _sem
AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id, uint8_t addr)
virtual ~AP_Compass_HMC5843()
void rotate(enum Rotation rotation)
Definition: vector3.cpp:28
uint8_t _compass_instance[HIL_NUM_COMPASSES]
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override
void set_rotation(uint8_t instance, enum Rotation rotation)
AuxiliaryBus * get_auxiliary_bus(int16_t backend_id)
#define PACKED
Definition: AP_Common.h:28
static AP_Compass_Backend * probe_mpu6000(Compass &compass, enum Rotation rotation=ROTATION_NONE)
bool is_external(uint8_t instance)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override
void publish_raw_field(const Vector3f &mag, uint8_t instance)
AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr< AP_HAL::Device > dev)
bool start_measurements() override
static AP_InertialSensor * get_instance()
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
T x
Definition: vector3.h:67
uint16_t __ap_bitwise be16_t
Definition: sparse-endian.h:36