AP_Compass_AK09916.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446
  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. #include "AP_Compass_AK09916.h"
  19. #include <assert.h>
  20. #include <AP_HAL/AP_HAL.h>
  21. #include <utility>
  22. #include <AP_Math/AP_Math.h>
  23. #include <stdio.h>
  24. #include <AP_InertialSensor/AP_InertialSensor_Invensensev2.h>
  25. #include <GCS_MAVLink/GCS.h>
  26. #ifdef HAL_NO_GCS
  27. #define GCS_SEND_TEXT(severity, format, args...)
  28. #else
  29. #define GCS_SEND_TEXT(severity, format, args...) gcs().send_text(severity, format, ##args)
  30. #endif
  31. #define REG_COMPANY_ID 0x00
  32. #define REG_DEVICE_ID 0x01
  33. #define REG_ST1 0x10
  34. #define REG_HXL 0x11
  35. #define REG_HXH 0x12
  36. #define REG_HYL 0x13
  37. #define REG_HYH 0x14
  38. #define REG_HZL 0x15
  39. #define REG_HZH 0x16
  40. #define REG_TMPS 0x17
  41. #define REG_ST2 0x18
  42. #define REG_CNTL1 0x30
  43. #define REG_CNTL2 0x31
  44. #define REG_CNTL3 0x32
  45. #define REG_ICM_WHOAMI 0x00
  46. #define REG_ICM_PWR_MGMT_1 0x06
  47. #define REG_ICM_INT_PIN_CFG 0x0f
  48. #define ICM_WHOAMI_VAL 0xEA
  49. #define AK09916_Device_ID 0x09
  50. #define AK09916_MILLIGAUSS_SCALE 10.0f
  51. extern const AP_HAL::HAL &hal;
  52. struct PACKED sample_regs {
  53. uint8_t st1;
  54. int16_t val[3];
  55. uint8_t tmps;
  56. uint8_t st2;
  57. };
  58. AP_Compass_AK09916::AP_Compass_AK09916(AP_AK09916_BusDriver *bus,
  59. bool force_external,
  60. enum Rotation rotation)
  61. : _bus(bus)
  62. , _force_external(force_external)
  63. , _rotation(rotation)
  64. {
  65. }
  66. AP_Compass_AK09916::~AP_Compass_AK09916()
  67. {
  68. delete _bus;
  69. }
  70. AP_Compass_Backend *AP_Compass_AK09916::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  71. bool force_external,
  72. enum Rotation rotation)
  73. {
  74. if (!dev) {
  75. return nullptr;
  76. }
  77. AP_AK09916_BusDriver *bus = new AP_AK09916_BusDriver_HALDevice(std::move(dev));
  78. if (!bus) {
  79. return nullptr;
  80. }
  81. AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(bus, force_external, rotation);
  82. if (!sensor || !sensor->init()) {
  83. delete sensor;
  84. return nullptr;
  85. }
  86. return sensor;
  87. }
  88. AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  89. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
  90. bool force_external,
  91. enum Rotation rotation)
  92. {
  93. if (!dev || !dev_icm) {
  94. return nullptr;
  95. }
  96. if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  97. return nullptr;
  98. }
  99. /* Allow ICM20x48 to shortcut auxiliary bus and host bus */
  100. uint8_t rval;
  101. uint16_t whoami;
  102. uint8_t retries = 5;
  103. if (!dev_icm->read_registers(REG_ICM_WHOAMI, &rval, 1) ||
  104. rval != ICM_WHOAMI_VAL) {
  105. // not an ICM_WHOAMI
  106. goto fail;
  107. }
  108. do {
  109. // reset then bring sensor out of sleep mode
  110. if (!dev_icm->write_register(REG_ICM_PWR_MGMT_1, 0x80)) {
  111. goto fail;
  112. }
  113. hal.scheduler->delay(10);
  114. if (!dev_icm->write_register(REG_ICM_PWR_MGMT_1, 0x00)) {
  115. goto fail;
  116. }
  117. hal.scheduler->delay(10);
  118. // see if ICM20948 is sleeping
  119. if (!dev_icm->read_registers(REG_ICM_PWR_MGMT_1, &rval, 1)) {
  120. goto fail;
  121. }
  122. if ((rval & 0x40) == 0) {
  123. break;
  124. }
  125. } while (retries--);
  126. if (rval & 0x40) {
  127. // it didn't come out of sleep
  128. goto fail;
  129. }
  130. // initially force i2c bypass off
  131. dev_icm->write_register(REG_ICM_INT_PIN_CFG, 0x00);
  132. hal.scheduler->delay(1);
  133. // now check if a AK09916 shows up on the bus. If it does then
  134. // we have both a real AK09916 and a ICM20948 with an embedded
  135. // AK09916. In that case we will fail the driver load and use
  136. // the main AK09916 driver
  137. if (dev->read_registers(REG_COMPANY_ID, (uint8_t *)&whoami, 2)) {
  138. // a device is replying on the AK09916 I2C address, don't
  139. // load the ICM20948
  140. GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ICM20948: AK09916 bus conflict\n");
  141. goto fail;
  142. }
  143. // now force bypass on
  144. dev_icm->write_register(REG_ICM_INT_PIN_CFG, 0x02);
  145. hal.scheduler->delay(1);
  146. dev->get_semaphore()->give();
  147. return probe(std::move(dev), force_external, rotation);
  148. fail:
  149. dev->get_semaphore()->give();
  150. return nullptr;
  151. }
  152. AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(uint8_t inv2_instance,
  153. enum Rotation rotation)
  154. {
  155. AP_InertialSensor &ins = AP::ins();
  156. AP_AK09916_BusDriver *bus =
  157. new AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_SPI, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR);
  158. if (!bus) {
  159. return nullptr;
  160. }
  161. AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(bus, false, rotation);
  162. if (!sensor || !sensor->init()) {
  163. delete sensor;
  164. return nullptr;
  165. }
  166. return sensor;
  167. }
  168. bool AP_Compass_AK09916::init()
  169. {
  170. AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();
  171. if (!bus_sem || !_bus->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  172. GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AK09916: Unable to get bus semaphore\n");
  173. return false;
  174. }
  175. if (!_bus->configure()) {
  176. GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AK09916: Could not configure the bus\n");
  177. goto fail;
  178. }
  179. if (!_reset()) {
  180. GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AK09916: Reset Failed\n");
  181. goto fail;
  182. }
  183. if (!_check_id()) {
  184. GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AK09916: Wrong id\n");
  185. goto fail;
  186. }
  187. if (!_setup_mode()) {
  188. GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AK09916: Could not setup mode\n");
  189. goto fail;
  190. }
  191. if (!_bus->start_measurements()) {
  192. GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AK09916: Could not start measurements\n");
  193. goto fail;
  194. }
  195. _initialized = true;
  196. /* register the compass instance in the frontend */
  197. _compass_instance = register_compass();
  198. if (_force_external) {
  199. set_external(_compass_instance, true);
  200. }
  201. set_rotation(_compass_instance, _rotation);
  202. _bus->set_device_type(DEVTYPE_AK09916);
  203. set_dev_id(_compass_instance, _bus->get_bus_id());
  204. bus_sem->give();
  205. _bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK09916::_update, void));
  206. return true;
  207. fail:
  208. bus_sem->give();
  209. return false;
  210. }
  211. void AP_Compass_AK09916::read()
  212. {
  213. if (!_initialized) {
  214. return;
  215. }
  216. drain_accumulated_samples(_compass_instance);
  217. }
  218. void AP_Compass_AK09916::_make_adc_sensitivity_adjustment(Vector3f& field) const
  219. {
  220. static const float ADC_16BIT_RESOLUTION = 0.15f;
  221. field *= ADC_16BIT_RESOLUTION;
  222. }
  223. void AP_Compass_AK09916::_update()
  224. {
  225. struct sample_regs regs = {0};
  226. Vector3f raw_field;
  227. if (!_bus->block_read(REG_ST1, (uint8_t *) &regs, sizeof(regs))) {
  228. return;
  229. }
  230. if (!(regs.st1 & 0x01)) {
  231. return;
  232. }
  233. /* Check for overflow. See AK09916's datasheet*/
  234. if ((regs.st2 & 0x08)) {
  235. return;
  236. }
  237. raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);
  238. if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {
  239. return;
  240. }
  241. _make_adc_sensitivity_adjustment(raw_field);
  242. raw_field *= AK09916_MILLIGAUSS_SCALE;
  243. accumulate_sample(raw_field, _compass_instance, 10);
  244. }
  245. bool AP_Compass_AK09916::_check_id()
  246. {
  247. for (int i = 0; i < 5; i++) {
  248. uint8_t deviceid = 0;
  249. /* Read AK09916's id */
  250. if (_bus->register_read(REG_DEVICE_ID, &deviceid) &&
  251. deviceid == AK09916_Device_ID) {
  252. return true;
  253. }
  254. }
  255. return false;
  256. }
  257. bool AP_Compass_AK09916::_setup_mode() {
  258. return _bus->register_write(REG_CNTL2, 0x08); //Continuous Mode 2
  259. }
  260. bool AP_Compass_AK09916::_reset()
  261. {
  262. return _bus->register_write(REG_CNTL3, 0x01); //Soft Reset
  263. }
  264. /* AP_HAL::I2CDevice implementation of the AK09916 */
  265. AP_AK09916_BusDriver_HALDevice::AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
  266. : _dev(std::move(dev))
  267. {
  268. }
  269. bool AP_AK09916_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
  270. {
  271. return _dev->read_registers(reg, buf, size);
  272. }
  273. bool AP_AK09916_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)
  274. {
  275. return _dev->read_registers(reg, val, 1);
  276. }
  277. bool AP_AK09916_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val)
  278. {
  279. return _dev->write_register(reg, val);
  280. }
  281. AP_HAL::Semaphore *AP_AK09916_BusDriver_HALDevice::get_semaphore()
  282. {
  283. return _dev->get_semaphore();
  284. }
  285. AP_HAL::Device::PeriodicHandle AP_AK09916_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
  286. {
  287. return _dev->register_periodic_callback(period_usec, cb);
  288. }
  289. /* AK09916 on an auxiliary bus of IMU driver */
  290. AP_AK09916_BusDriver_Auxiliary::AP_AK09916_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
  291. uint8_t backend_instance, uint8_t addr)
  292. {
  293. /*
  294. * Only initialize members. Fails are handled by configure or while
  295. * getting the semaphore
  296. */
  297. _bus = ins.get_auxiliary_bus(backend_id, backend_instance);
  298. if (!_bus) {
  299. return;
  300. }
  301. _slave = _bus->request_next_slave(addr);
  302. }
  303. AP_AK09916_BusDriver_Auxiliary::~AP_AK09916_BusDriver_Auxiliary()
  304. {
  305. /* After started it's owned by AuxiliaryBus */
  306. if (!_started) {
  307. delete _slave;
  308. }
  309. }
  310. bool AP_AK09916_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
  311. {
  312. if (_started) {
  313. /*
  314. * We can only read a block when reading the block of sample values -
  315. * calling with any other value is a mistake
  316. */
  317. assert(reg == REG_ST1);
  318. int n = _slave->read(buf);
  319. return n == static_cast<int>(size);
  320. }
  321. int r = _slave->passthrough_read(reg, buf, size);
  322. return r > 0 && static_cast<uint32_t>(r) == size;
  323. }
  324. bool AP_AK09916_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)
  325. {
  326. return _slave->passthrough_read(reg, val, 1) == 1;
  327. }
  328. bool AP_AK09916_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val)
  329. {
  330. return _slave->passthrough_write(reg, val) == 1;
  331. }
  332. AP_HAL::Semaphore *AP_AK09916_BusDriver_Auxiliary::get_semaphore()
  333. {
  334. return _bus ? _bus->get_semaphore() : nullptr;
  335. }
  336. bool AP_AK09916_BusDriver_Auxiliary::configure()
  337. {
  338. if (!_bus || !_slave) {
  339. return false;
  340. }
  341. return true;
  342. }
  343. bool AP_AK09916_BusDriver_Auxiliary::start_measurements()
  344. {
  345. if (_bus->register_periodic_read(_slave, REG_ST1, sizeof(sample_regs)) < 0) {
  346. return false;
  347. }
  348. _started = true;
  349. return true;
  350. }
  351. AP_HAL::Device::PeriodicHandle AP_AK09916_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
  352. {
  353. return _bus->register_periodic_callback(period_usec, cb);
  354. }
  355. // set device type within a device class
  356. void AP_AK09916_BusDriver_Auxiliary::set_device_type(uint8_t devtype)
  357. {
  358. _bus->set_device_type(devtype);
  359. }
  360. // return 24 bit bus identifier
  361. uint32_t AP_AK09916_BusDriver_Auxiliary::get_bus_id(void) const
  362. {
  363. return _bus->get_bus_id();
  364. }