AP_Compass_HMC5843.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * AP_Compass_HMC5843.cpp - Arduino Library for HMC5843 I2C magnetometer
  15. * Code by Jordi Muñoz and Jose Julio. DIYDrones.com
  16. *
  17. * Sensor is connected to I2C port
  18. * Sensor is initialized in Continuos mode (10Hz)
  19. *
  20. */
  21. #include <AP_HAL/AP_HAL.h>
  22. #ifdef HAL_COMPASS_HMC5843_I2C_ADDR
  23. #include <assert.h>
  24. #include <utility>
  25. #include <stdio.h>
  26. #include <AP_Math/AP_Math.h>
  27. #include <AP_HAL/AP_HAL.h>
  28. #include <AP_HAL/utility/sparse-endian.h>
  29. #include "AP_Compass_HMC5843.h"
  30. #include <AP_InertialSensor/AP_InertialSensor.h>
  31. #include <AP_InertialSensor/AuxiliaryBus.h>
  32. extern const AP_HAL::HAL& hal;
  33. /*
  34. * Defaul address: 0x1E
  35. */
  36. #define HMC5843_REG_CONFIG_A 0x00
  37. // Valid sample averaging for 5883L
  38. #define HMC5843_SAMPLE_AVERAGING_1 (0x00 << 5)
  39. #define HMC5843_SAMPLE_AVERAGING_2 (0x01 << 5)
  40. #define HMC5843_SAMPLE_AVERAGING_4 (0x02 << 5)
  41. #define HMC5843_SAMPLE_AVERAGING_8 (0x03 << 5)
  42. #define HMC5843_CONF_TEMP_ENABLE (0x80)
  43. // Valid data output rates for 5883L
  44. #define HMC5843_OSR_0_75HZ (0x00 << 2)
  45. #define HMC5843_OSR_1_5HZ (0x01 << 2)
  46. #define HMC5843_OSR_3HZ (0x02 << 2)
  47. #define HMC5843_OSR_7_5HZ (0x03 << 2)
  48. #define HMC5843_OSR_15HZ (0x04 << 2)
  49. #define HMC5843_OSR_30HZ (0x05 << 2)
  50. #define HMC5843_OSR_75HZ (0x06 << 2)
  51. // Sensor operation modes
  52. #define HMC5843_OPMODE_NORMAL 0x00
  53. #define HMC5843_OPMODE_POSITIVE_BIAS 0x01
  54. #define HMC5843_OPMODE_NEGATIVE_BIAS 0x02
  55. #define HMC5843_OPMODE_MASK 0x03
  56. #define HMC5843_REG_CONFIG_B 0x01
  57. #define HMC5883L_GAIN_0_88_GA (0x00 << 5)
  58. #define HMC5883L_GAIN_1_30_GA (0x01 << 5)
  59. #define HMC5883L_GAIN_1_90_GA (0x02 << 5)
  60. #define HMC5883L_GAIN_2_50_GA (0x03 << 5)
  61. #define HMC5883L_GAIN_4_00_GA (0x04 << 5)
  62. #define HMC5883L_GAIN_4_70_GA (0x05 << 5)
  63. #define HMC5883L_GAIN_5_60_GA (0x06 << 5)
  64. #define HMC5883L_GAIN_8_10_GA (0x07 << 5)
  65. #define HMC5843_GAIN_0_70_GA (0x00 << 5)
  66. #define HMC5843_GAIN_1_00_GA (0x01 << 5)
  67. #define HMC5843_GAIN_1_50_GA (0x02 << 5)
  68. #define HMC5843_GAIN_2_00_GA (0x03 << 5)
  69. #define HMC5843_GAIN_3_20_GA (0x04 << 5)
  70. #define HMC5843_GAIN_3_80_GA (0x05 << 5)
  71. #define HMC5843_GAIN_4_50_GA (0x06 << 5)
  72. #define HMC5843_GAIN_6_50_GA (0x07 << 5)
  73. #define HMC5843_REG_MODE 0x02
  74. #define HMC5843_MODE_CONTINUOUS 0x00
  75. #define HMC5843_MODE_SINGLE 0x01
  76. #define HMC5843_REG_DATA_OUTPUT_X_MSB 0x03
  77. #define HMC5843_REG_ID_A 0x0A
  78. AP_Compass_HMC5843::AP_Compass_HMC5843(AP_HMC5843_BusDriver *bus,
  79. bool force_external, enum Rotation rotation)
  80. : _bus(bus)
  81. , _rotation(rotation)
  82. , _force_external(force_external)
  83. {
  84. }
  85. AP_Compass_HMC5843::~AP_Compass_HMC5843()
  86. {
  87. delete _bus;
  88. }
  89. AP_Compass_Backend *AP_Compass_HMC5843::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  90. bool force_external,
  91. enum Rotation rotation)
  92. {
  93. if (!dev) {
  94. return nullptr;
  95. }
  96. AP_HMC5843_BusDriver *bus = new AP_HMC5843_BusDriver_HALDevice(std::move(dev));
  97. if (!bus) {
  98. return nullptr;
  99. }
  100. AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(bus, force_external, rotation);
  101. if (!sensor || !sensor->init()) {
  102. delete sensor;
  103. return nullptr;
  104. }
  105. return sensor;
  106. }
  107. AP_Compass_Backend *AP_Compass_HMC5843::probe_mpu6000(enum Rotation rotation)
  108. {
  109. AP_InertialSensor &ins = *AP_InertialSensor::get_singleton();
  110. AP_HMC5843_BusDriver *bus =
  111. new AP_HMC5843_BusDriver_Auxiliary(ins, HAL_INS_MPU60XX_SPI,
  112. HAL_COMPASS_HMC5843_I2C_ADDR);
  113. if (!bus) {
  114. return nullptr;
  115. }
  116. AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(bus, false, rotation);
  117. if (!sensor || !sensor->init()) {
  118. delete sensor;
  119. return nullptr;
  120. }
  121. return sensor;
  122. }
  123. bool AP_Compass_HMC5843::init()
  124. {
  125. AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();
  126. if (!bus_sem || !bus_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  127. hal.console->printf("HMC5843: Unable to get bus semaphore\n");
  128. return false;
  129. }
  130. // high retries for init
  131. _bus->set_retries(10);
  132. if (!_bus->configure()) {
  133. hal.console->printf("HMC5843: Could not configure the bus\n");
  134. goto errout;
  135. }
  136. if (!_check_whoami()) {
  137. goto errout;
  138. }
  139. if (!_calibrate()) {
  140. hal.console->printf("HMC5843: Could not calibrate sensor\n");
  141. goto errout;
  142. }
  143. if (!_setup_sampling_mode()) {
  144. goto errout;
  145. }
  146. if (!_bus->start_measurements()) {
  147. hal.console->printf("HMC5843: Could not start measurements on bus\n");
  148. goto errout;
  149. }
  150. _initialised = true;
  151. // lower retries for run
  152. _bus->set_retries(3);
  153. bus_sem->give();
  154. // perform an initial read
  155. read();
  156. _compass_instance = register_compass();
  157. set_rotation(_compass_instance, _rotation);
  158. _bus->set_device_type(DEVTYPE_HMC5883);
  159. set_dev_id(_compass_instance, _bus->get_bus_id());
  160. if (_force_external) {
  161. set_external(_compass_instance, true);
  162. }
  163. // read from sensor at 75Hz
  164. _bus->register_periodic_callback(13333,
  165. FUNCTOR_BIND_MEMBER(&AP_Compass_HMC5843::_timer, void));
  166. hal.console->printf("HMC5843 found on bus 0x%x\n", (unsigned)_bus->get_bus_id());
  167. return true;
  168. errout:
  169. bus_sem->give();
  170. return false;
  171. }
  172. /*
  173. * take a reading from the magnetometer
  174. *
  175. * bus semaphore has been taken already by HAL
  176. */
  177. void AP_Compass_HMC5843::_timer()
  178. {
  179. bool result = _read_sample();
  180. // always ask for a new sample
  181. _take_sample();
  182. if (!result) {
  183. return;
  184. }
  185. // get raw_field - sensor frame, uncorrected
  186. Vector3f raw_field = Vector3f(_mag_x, _mag_y, _mag_z);
  187. raw_field *= _gain_scale;
  188. // rotate to the desired orientation
  189. if (is_external(_compass_instance)) {
  190. raw_field.rotate(ROTATION_YAW_90);
  191. }
  192. // We expect to do reads at 10Hz, and we get new data at most 75Hz, so we
  193. // don't expect to accumulate more than 8 before a read; let's make it
  194. // 14 to give more room for the initialization phase
  195. accumulate_sample(raw_field, _compass_instance, 14);
  196. }
  197. /*
  198. * Take accumulated reads from the magnetometer or try to read once if no
  199. * valid data
  200. *
  201. * bus semaphore must not be locked
  202. */
  203. void AP_Compass_HMC5843::read()
  204. {
  205. if (!_initialised) {
  206. // someone has tried to enable a compass for the first time
  207. // mid-flight .... we can't do that yet (especially as we won't
  208. // have the right orientation!)
  209. return;
  210. }
  211. drain_accumulated_samples(_compass_instance, &_scaling);
  212. }
  213. bool AP_Compass_HMC5843::_setup_sampling_mode()
  214. {
  215. _gain_scale = (1.0f / 1090) * 1000;
  216. if (!_bus->register_write(HMC5843_REG_CONFIG_A,
  217. HMC5843_CONF_TEMP_ENABLE |
  218. HMC5843_OSR_75HZ |
  219. HMC5843_SAMPLE_AVERAGING_1) ||
  220. !_bus->register_write(HMC5843_REG_CONFIG_B,
  221. HMC5883L_GAIN_1_30_GA) ||
  222. !_bus->register_write(HMC5843_REG_MODE,
  223. HMC5843_MODE_SINGLE)) {
  224. return false;
  225. }
  226. return true;
  227. }
  228. /*
  229. * Read Sensor data - bus semaphore must be taken
  230. */
  231. bool AP_Compass_HMC5843::_read_sample()
  232. {
  233. struct PACKED {
  234. be16_t rx;
  235. be16_t ry;
  236. be16_t rz;
  237. } val;
  238. int16_t rx, ry, rz;
  239. if (!_bus->block_read(HMC5843_REG_DATA_OUTPUT_X_MSB, (uint8_t *) &val, sizeof(val))){
  240. return false;
  241. }
  242. rx = be16toh(val.rx);
  243. ry = be16toh(val.rz);
  244. rz = be16toh(val.ry);
  245. if (rx == -4096 || ry == -4096 || rz == -4096) {
  246. // no valid data available
  247. return false;
  248. }
  249. _mag_x = -rx;
  250. _mag_y = ry;
  251. _mag_z = -rz;
  252. return true;
  253. }
  254. /*
  255. ask for a new oneshot sample
  256. */
  257. void AP_Compass_HMC5843::_take_sample()
  258. {
  259. _bus->register_write(HMC5843_REG_MODE,
  260. HMC5843_MODE_SINGLE);
  261. }
  262. bool AP_Compass_HMC5843::_check_whoami()
  263. {
  264. uint8_t id[3];
  265. if (!_bus->block_read(HMC5843_REG_ID_A, id, 3)) {
  266. // can't talk on bus
  267. return false;
  268. }
  269. if (id[0] != 'H' ||
  270. id[1] != '4' ||
  271. id[2] != '3') {
  272. // not a HMC5x83 device
  273. return false;
  274. }
  275. return true;
  276. }
  277. bool AP_Compass_HMC5843::_calibrate()
  278. {
  279. uint8_t calibration_gain;
  280. int numAttempts = 0, good_count = 0;
  281. bool success = false;
  282. calibration_gain = HMC5883L_GAIN_2_50_GA;
  283. /*
  284. * the expected values are based on observation of real sensors
  285. */
  286. float expected[3] = { 1.16*600, 1.08*600, 1.16*600 };
  287. uint8_t base_config = HMC5843_OSR_15HZ;
  288. uint8_t num_samples = 0;
  289. while (success == 0 && numAttempts < 25 && good_count < 5) {
  290. numAttempts++;
  291. // force positiveBias (compass should return 715 for all channels)
  292. if (!_bus->register_write(HMC5843_REG_CONFIG_A,
  293. base_config | HMC5843_OPMODE_POSITIVE_BIAS)) {
  294. // compass not responding on the bus
  295. continue;
  296. }
  297. hal.scheduler->delay(50);
  298. // set gains
  299. if (!_bus->register_write(HMC5843_REG_CONFIG_B, calibration_gain) ||
  300. !_bus->register_write(HMC5843_REG_MODE, HMC5843_MODE_SINGLE)) {
  301. continue;
  302. }
  303. // read values from the compass
  304. hal.scheduler->delay(50);
  305. if (!_read_sample()) {
  306. // we didn't read valid values
  307. continue;
  308. }
  309. num_samples++;
  310. float cal[3];
  311. // hal.console->printf("mag %d %d %d\n", _mag_x, _mag_y, _mag_z);
  312. cal[0] = fabsf(expected[0] / _mag_x);
  313. cal[1] = fabsf(expected[1] / _mag_y);
  314. cal[2] = fabsf(expected[2] / _mag_z);
  315. // hal.console->printf("cal=%.2f %.2f %.2f\n", cal[0], cal[1], cal[2]);
  316. // we throw away the first two samples as the compass may
  317. // still be changing its state from the application of the
  318. // strap excitation. After that we accept values in a
  319. // reasonable range
  320. if (numAttempts <= 2) {
  321. continue;
  322. }
  323. #define IS_CALIBRATION_VALUE_VALID(val) (val > 0.7f && val < 1.35f)
  324. if (IS_CALIBRATION_VALUE_VALID(cal[0]) &&
  325. IS_CALIBRATION_VALUE_VALID(cal[1]) &&
  326. IS_CALIBRATION_VALUE_VALID(cal[2])) {
  327. // hal.console->printf("car=%.2f %.2f %.2f good\n", cal[0], cal[1], cal[2]);
  328. good_count++;
  329. _scaling[0] += cal[0];
  330. _scaling[1] += cal[1];
  331. _scaling[2] += cal[2];
  332. }
  333. #undef IS_CALIBRATION_VALUE_VALID
  334. #if 0
  335. /* useful for debugging */
  336. hal.console->printf("MagX: %d MagY: %d MagZ: %d\n", (int)_mag_x, (int)_mag_y, (int)_mag_z);
  337. hal.console->printf("CalX: %.2f CalY: %.2f CalZ: %.2f\n", cal[0], cal[1], cal[2]);
  338. #endif
  339. }
  340. _bus->register_write(HMC5843_REG_CONFIG_A, base_config);
  341. if (good_count >= 5) {
  342. _scaling[0] = _scaling[0] / good_count;
  343. _scaling[1] = _scaling[1] / good_count;
  344. _scaling[2] = _scaling[2] / good_count;
  345. success = true;
  346. } else {
  347. /* best guess */
  348. _scaling[0] = 1.0;
  349. _scaling[1] = 1.0;
  350. _scaling[2] = 1.0;
  351. if (num_samples > 5) {
  352. // a sensor can be broken for calibration but still
  353. // otherwise workable, accept it if we are reading samples
  354. success = true;
  355. }
  356. }
  357. #if 0
  358. printf("scaling: %.2f %.2f %.2f\n",
  359. _scaling[0], _scaling[1], _scaling[2]);
  360. #endif
  361. return success;
  362. }
  363. /* AP_HAL::Device implementation of the HMC5843 */
  364. AP_HMC5843_BusDriver_HALDevice::AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev)
  365. : _dev(std::move(dev))
  366. {
  367. // set read and auto-increment flags on SPI
  368. if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
  369. _dev->set_read_flag(0xC0);
  370. }
  371. }
  372. bool AP_HMC5843_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
  373. {
  374. return _dev->read_registers(reg, buf, size);
  375. }
  376. bool AP_HMC5843_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)
  377. {
  378. return _dev->read_registers(reg, val, 1);
  379. }
  380. bool AP_HMC5843_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val)
  381. {
  382. return _dev->write_register(reg, val);
  383. }
  384. AP_HAL::Semaphore *AP_HMC5843_BusDriver_HALDevice::get_semaphore()
  385. {
  386. return _dev->get_semaphore();
  387. }
  388. AP_HAL::Device::PeriodicHandle AP_HMC5843_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
  389. {
  390. return _dev->register_periodic_callback(period_usec, cb);
  391. }
  392. /* HMC5843 on an auxiliary bus of IMU driver */
  393. AP_HMC5843_BusDriver_Auxiliary::AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
  394. uint8_t addr)
  395. {
  396. /*
  397. * Only initialize members. Fails are handled by configure or while
  398. * getting the semaphore
  399. */
  400. _bus = ins.get_auxiliary_bus(backend_id);
  401. if (!_bus) {
  402. return;
  403. }
  404. _slave = _bus->request_next_slave(addr);
  405. }
  406. AP_HMC5843_BusDriver_Auxiliary::~AP_HMC5843_BusDriver_Auxiliary()
  407. {
  408. /* After started it's owned by AuxiliaryBus */
  409. if (!_started) {
  410. delete _slave;
  411. }
  412. }
  413. bool AP_HMC5843_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
  414. {
  415. if (_started) {
  416. /*
  417. * We can only read a block when reading the block of sample values -
  418. * calling with any other value is a mistake
  419. */
  420. assert(reg == HMC5843_REG_DATA_OUTPUT_X_MSB);
  421. int n = _slave->read(buf);
  422. return n == static_cast<int>(size);
  423. }
  424. int r = _slave->passthrough_read(reg, buf, size);
  425. return r > 0 && static_cast<uint32_t>(r) == size;
  426. }
  427. bool AP_HMC5843_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)
  428. {
  429. return _slave->passthrough_read(reg, val, 1) == 1;
  430. }
  431. bool AP_HMC5843_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val)
  432. {
  433. return _slave->passthrough_write(reg, val) == 1;
  434. }
  435. AP_HAL::Semaphore *AP_HMC5843_BusDriver_Auxiliary::get_semaphore()
  436. {
  437. return _bus->get_semaphore();
  438. }
  439. bool AP_HMC5843_BusDriver_Auxiliary::configure()
  440. {
  441. if (!_bus || !_slave) {
  442. return false;
  443. }
  444. return true;
  445. }
  446. bool AP_HMC5843_BusDriver_Auxiliary::start_measurements()
  447. {
  448. if (_bus->register_periodic_read(_slave, HMC5843_REG_DATA_OUTPUT_X_MSB, 6) < 0) {
  449. return false;
  450. }
  451. _started = true;
  452. return true;
  453. }
  454. AP_HAL::Device::PeriodicHandle AP_HMC5843_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
  455. {
  456. return _bus->register_periodic_callback(period_usec, cb);
  457. }
  458. // set device type within a device class
  459. void AP_HMC5843_BusDriver_Auxiliary::set_device_type(uint8_t devtype)
  460. {
  461. _bus->set_device_type(devtype);
  462. }
  463. // return 24 bit bus identifier
  464. uint32_t AP_HMC5843_BusDriver_Auxiliary::get_bus_id(void) const
  465. {
  466. return _bus->get_bus_id();
  467. }
  468. #endif