AP_Compass_MAG3110.cpp 7.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222
  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. #include <utility>
  14. #include <AP_HAL/AP_HAL.h>
  15. #include <AP_Math/AP_Math.h>
  16. #include <stdio.h>
  17. #include "AP_Compass_MAG3110.h"
  18. extern const AP_HAL::HAL &hal;
  19. /*
  20. EN:
  21. at first glance, the magnetometer MAG3110 consists only of flaws:
  22.     * noisy, with a bad characteristic, with very large difference on axes
  23.     * it can't be calibrated in any way, you just have to believe what he has been measured
  24.     * There are no adjustments and settings, it just sends data with some unknown sensitivity. Or does not sends :)
  25.     * One and a half setup registers, in which only the frequency of operation and the number of averagings are specified
  26.     
  27.     This is a device, wooden to the waist. But of all these shortcomings, its sole and basic virtue arises:
  28.     * He will never comes buggy or clevers.
  29.     
  30.     And since we do not need much from a magnetometer and it is required to calibrate the Ardupilot itself, the device
  31.     appears in a completely new light - as a reliable info "north is there." What we really need.
  32. RUS:
  33. на первый взгляд, магнитометр MAG3110 состоит из одних лишь недостатков:
  34. * шумный, с кривой характеристикой,
  35. * никак не калибруется, приходится просто верить тому что он намерял
  36. * нет никаких регулировок и настроек, он просто выдает данные с некой неизвестной чувствительностью. Или не выдает :)
  37. * полтора настроечных регистра, в которых задается только частота работы и количество усреднений
  38. Такой вот девайс, по пояс деревянный. Но из всех этих недостатков проистекает его единственное и основное достоинство:
  39. * он никогда не глючит и не умничает.
  40. А так как нам от магнитометра особо много и не требуется, а калибровать Ардупилот и сам умеет, то девайс
  41. предстает в совсем новом свете - как надежный указатель "север там". Что нам собственно и надо.
  42. */
  43. /*
  44. the vector length filter can help with noise on the bus, but may
  45. interfere with higher level processing. It should really be moved
  46. into the AP_Compass_backend code, with a parameter to enable it.
  47. */
  48. #ifndef MAG3110_ENABLE_LEN_FILTER
  49. #define MAG3110_ENABLE_LEN_FILTER 0
  50. #endif
  51. // Registers
  52. #define MAG3110_MAG_REG_STATUS 0x00
  53. #define MAG3110_MAG_REG_HXL 0x01
  54. #define MAG3110_MAG_REG_HXH 0x02
  55. #define MAG3110_MAG_REG_HYL 0x03
  56. #define MAG3110_MAG_REG_HYH 0x04
  57. #define MAG3110_MAG_REG_HZL 0x05
  58. #define MAG3110_MAG_REG_HZH 0x06
  59. #define MAG3110_MAG_REG_WHO_AM_I 0x07
  60. #define MAG3110_MAG_REG_SYSMODE 0x08
  61. #define MAG3110_MAG_REG_CTRL_REG1 0x10
  62. #define MAG3110_MAG_REG_CTRL_REG2 0x11
  63. #define BIT_STATUS_REG_DATA_READY (1 << 3)
  64. AP_Compass_MAG3110::AP_Compass_MAG3110(AP_HAL::OwnPtr<AP_HAL::Device> dev)
  65. : _dev(std::move(dev))
  66. {
  67. }
  68. AP_Compass_Backend *AP_Compass_MAG3110::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  69. enum Rotation rotation)
  70. {
  71. if (!dev) {
  72. return nullptr;
  73. }
  74. AP_Compass_MAG3110 *sensor = new AP_Compass_MAG3110(std::move(dev));
  75. if (!sensor || !sensor->init(rotation)) {
  76. delete sensor;
  77. return nullptr;
  78. }
  79. return sensor;
  80. }
  81. bool AP_Compass_MAG3110::init(enum Rotation rotation)
  82. {
  83. bool success = _hardware_init();
  84. if (!success) {
  85. return false;
  86. }
  87. _initialised = true;
  88. // perform an initial read
  89. read();
  90. /* register the compass instance in the frontend */
  91. _compass_instance = register_compass();
  92. set_rotation(_compass_instance, rotation);
  93. _dev->set_device_type(DEVTYPE_MAG3110);
  94. set_dev_id(_compass_instance, _dev->get_bus_id());
  95. set_external(_compass_instance, true);
  96. // read at 75Hz
  97. _dev->register_periodic_callback(13333, FUNCTOR_BIND_MEMBER(&AP_Compass_MAG3110::_update, void));
  98. return true;
  99. }
  100. bool AP_Compass_MAG3110::_hardware_init()
  101. {
  102. AP_HAL::Semaphore *bus_sem = _dev->get_semaphore();
  103. if (!bus_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  104. AP_HAL::panic("MAG3110: Unable to get semaphore");
  105. }
  106. // initially run the bus at low speed
  107. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  108. bool ret=false;
  109. _dev->set_retries(5);
  110. uint8_t sig = 0;
  111. bool ack = _dev->read_registers(MAG3110_MAG_REG_WHO_AM_I, &sig, 1);
  112. if (!ack || sig != 0xC4) goto exit;
  113. ack = _dev->write_register(MAG3110_MAG_REG_CTRL_REG1, 0x01); // active mode 80 Hz ODR with OSR = 1
  114. if (!ack) goto exit;
  115. hal.scheduler->delay(20);
  116. ack = _dev->write_register(MAG3110_MAG_REG_CTRL_REG2, 0xA0); // AUTO_MRST_EN + RAW
  117. if (!ack) goto exit;
  118. ret = true;
  119. _dev->set_retries(3);
  120. printf("MAG3110 found on bus 0x%x\n", (uint16_t)_dev->get_bus_id());
  121. exit:
  122. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  123. bus_sem->give();
  124. return ret;
  125. }
  126. // Read Sensor data
  127. bool AP_Compass_MAG3110::_read_sample()
  128. {
  129. {
  130. uint8_t status;
  131. bool ack = _dev->read_registers(MAG3110_MAG_REG_STATUS, &status, 1);
  132. if (!ack || (status & BIT_STATUS_REG_DATA_READY) == 0) {
  133. return false;
  134. }
  135. }
  136. uint8_t buf[6];
  137. bool ack = _dev->read_registers(MAG3110_MAG_REG_HXL, buf, 6);
  138. if (!ack) {
  139. return false;
  140. }
  141. _mag_x = (int16_t)(buf[0] << 8 | buf[1]);
  142. _mag_y = (int16_t)(buf[2] << 8 | buf[3]);
  143. _mag_z = (int16_t)(buf[4] << 8 | buf[5]);
  144. return true;
  145. }
  146. #define MAG_SCALE (1.0f/10000 / 0.0001f * 1000) // 1 Tesla full scale of +-10000, 1 Gauss = 0,0001 Tesla, library needs milliGauss
  147. void AP_Compass_MAG3110::_update()
  148. {
  149. if (!_read_sample()) {
  150. return;
  151. }
  152. Vector3f raw_field = Vector3f((float)_mag_x, (float)_mag_y, (float)_mag_z) * MAG_SCALE;
  153. accumulate_sample(raw_field, _compass_instance);
  154. }
  155. // Read Sensor data
  156. void AP_Compass_MAG3110::read()
  157. {
  158. if (!_initialised) {
  159. return;
  160. }
  161. drain_accumulated_samples(_compass_instance);
  162. }