AP_IRLock_I2C.cpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172
  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_IRLock_I2C.cpp
  15. *
  16. * Based on AP_IRLock_PX4 by MLandes
  17. *
  18. * See: http://irlock.com/pages/serial-communication-protocol
  19. */
  20. #include <AP_HAL/AP_HAL.h>
  21. #include "AP_IRLock_I2C.h"
  22. #include <stdio.h>
  23. #include <utility>
  24. #include <AP_HAL/I2CDevice.h>
  25. extern const AP_HAL::HAL& hal;
  26. #define IRLOCK_I2C_ADDRESS 0x54
  27. #define IRLOCK_SYNC 0xAA55AA55
  28. void AP_IRLock_I2C::init(int8_t bus)
  29. {
  30. if (bus < 0) {
  31. // default to i2c external bus
  32. bus = 1;
  33. }
  34. dev = std::move(hal.i2c_mgr->get_device(bus, IRLOCK_I2C_ADDRESS));
  35. if (!dev) {
  36. return;
  37. }
  38. // read at 50Hz
  39. printf("Starting IRLock on I2C\n");
  40. dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&AP_IRLock_I2C::read_frames, void));
  41. }
  42. /*
  43. synchronise with frame start. We expect 0xAA55AA55 at the start of
  44. a frame
  45. */
  46. bool AP_IRLock_I2C::sync_frame_start(void)
  47. {
  48. uint32_t sync_word;
  49. if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) {
  50. return false;
  51. }
  52. // record sensor successfully responded to I2C request
  53. _last_read_ms = AP_HAL::millis();
  54. uint8_t count=40;
  55. while (count-- && sync_word != IRLOCK_SYNC && sync_word != 0) {
  56. uint8_t sync_byte;
  57. if (!dev->transfer(nullptr, 0, &sync_byte, 1)) {
  58. return false;
  59. }
  60. if (sync_byte == 0) {
  61. break;
  62. }
  63. sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24);
  64. }
  65. return sync_word == IRLOCK_SYNC;
  66. }
  67. /*
  68. converts IRLOCK pixels to a position on a normal plane 1m in front of the lens
  69. based on a characterization of IR-LOCK with the standard lens, focused such that 2.38mm of threads are exposed
  70. */
  71. void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y)
  72. {
  73. ret_x = (-0.00293875727162397f*pix_x + 0.470201163459835f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) +
  74. 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f);
  75. ret_y = (-0.003056843086277f*pix_y + 0.3056843086277f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) +
  76. 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f);
  77. }
  78. /*
  79. read a frame from sensor
  80. */
  81. bool AP_IRLock_I2C::read_block(struct frame &irframe)
  82. {
  83. if (!dev->transfer(nullptr, 0, (uint8_t*)&irframe, sizeof(irframe))) {
  84. return false;
  85. }
  86. // record sensor successfully responded to I2C request
  87. _last_read_ms = AP_HAL::millis();
  88. /* check crc */
  89. uint32_t crc = irframe.signature + irframe.pixel_x + irframe.pixel_y + irframe.pixel_size_x + irframe.pixel_size_y;
  90. if (crc != irframe.checksum) {
  91. // printf("bad crc 0x%04x 0x%04x\n", crc, irframe.checksum);
  92. return false;
  93. }
  94. return true;
  95. }
  96. void AP_IRLock_I2C::read_frames(void)
  97. {
  98. if (!sync_frame_start()) {
  99. return;
  100. }
  101. struct frame irframe;
  102. if (!read_block(irframe)) {
  103. return;
  104. }
  105. int16_t corner1_pix_x = irframe.pixel_x - irframe.pixel_size_x/2;
  106. int16_t corner1_pix_y = irframe.pixel_y - irframe.pixel_size_y/2;
  107. int16_t corner2_pix_x = irframe.pixel_x + irframe.pixel_size_x/2;
  108. int16_t corner2_pix_y = irframe.pixel_y + irframe.pixel_size_y/2;
  109. float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y;
  110. pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y);
  111. pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y);
  112. {
  113. WITH_SEMAPHORE(sem);
  114. /* convert to angles */
  115. _target_info.timestamp = AP_HAL::millis();
  116. _target_info.pos_x = 0.5f*(corner1_pos_x+corner2_pos_x);
  117. _target_info.pos_y = 0.5f*(corner1_pos_y+corner2_pos_y);
  118. _target_info.pos_z = 1.0f;
  119. }
  120. #if 0
  121. // debugging
  122. static uint32_t lastt;
  123. if (_target_info.timestamp - lastt > 2000) {
  124. lastt = _target_info.timestamp;
  125. printf("pos_x:%.5f pos_y:%.5f size_x:%.6f size_y:%.5f\n",
  126. _target_info.pos_x, _target_info.pos_y,
  127. (corner2_pos_x-corner1_pos_x), (corner2_pos_y-corner1_pos_y));
  128. }
  129. #endif
  130. }
  131. // retrieve latest sensor data - returns true if new data is available
  132. bool AP_IRLock_I2C::update()
  133. {
  134. bool new_data = false;
  135. if (!dev) {
  136. return false;
  137. }
  138. WITH_SEMAPHORE(sem);
  139. if (_last_update_ms != _target_info.timestamp) {
  140. new_data = true;
  141. }
  142. _last_update_ms = _target_info.timestamp;
  143. _flags.healthy = (AP_HAL::millis() - _last_read_ms < 100);
  144. // return true if new data found
  145. return new_data;
  146. }