AP_RangeFinder_PulsedLightLRF.cpp 7.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224
  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 "AP_RangeFinder_PulsedLightLRF.h"
  14. #include <utility>
  15. #include <stdio.h>
  16. #include <AP_HAL/AP_HAL.h>
  17. #include <AP_HAL/utility/sparse-endian.h>
  18. extern const AP_HAL::HAL& hal;
  19. /* LL40LS Registers addresses */
  20. #define LL40LS_MEASURE_REG 0x00 /* Measure range register */
  21. #define LL40LS_SIG_COUNT_VAL 0x02
  22. #define LL40LS_DISTHIGH_REG 0x0F /* High byte of distance register, auto increment */
  23. #define LL40LS_COUNT 0x11
  24. #define LL40LS_HW_VERSION 0x41
  25. #define LL40LS_INTERVAL 0x45
  26. #define LL40LS_SW_VERSION 0x4f
  27. // bit values
  28. #define LL40LS_MSRREG_RESET 0x00 /* reset to power on defaults */
  29. #define LL40LS_AUTO_INCREMENT 0x80
  30. #define LL40LS_COUNT_CONTINUOUS 0xff
  31. #define LL40LS_MSRREG_ACQUIRE 0x04 /* Value to initiate a measurement, varies based on sensor revision */
  32. // i2c address
  33. #define LL40LS_ADDR 0x62
  34. /*
  35. The constructor also initializes the rangefinder. Note that this
  36. constructor is not called until detect() returns true, so we
  37. already know that we should setup the rangefinder
  38. */
  39. AP_RangeFinder_PulsedLightLRF::AP_RangeFinder_PulsedLightLRF(uint8_t bus,
  40. RangeFinder::RangeFinder_State &_state,
  41. AP_RangeFinder_Params &_params,
  42. RangeFinder::RangeFinder_Type _rftype)
  43. : AP_RangeFinder_Backend(_state, _params)
  44. , _dev(hal.i2c_mgr->get_device(bus, LL40LS_ADDR))
  45. , rftype(_rftype)
  46. {
  47. }
  48. /*
  49. detect if a PulsedLight rangefinder is connected. We'll detect by
  50. look for the version registers
  51. */
  52. AP_RangeFinder_Backend *AP_RangeFinder_PulsedLightLRF::detect(uint8_t bus,
  53. RangeFinder::RangeFinder_State &_state,
  54. AP_RangeFinder_Params &_params,
  55. RangeFinder::RangeFinder_Type rftype)
  56. {
  57. AP_RangeFinder_PulsedLightLRF *sensor
  58. = new AP_RangeFinder_PulsedLightLRF(bus, _state, _params, rftype);
  59. if (!sensor ||
  60. !sensor->init()) {
  61. delete sensor;
  62. return nullptr;
  63. }
  64. return sensor;
  65. }
  66. /*
  67. called at 50Hz
  68. */
  69. void AP_RangeFinder_PulsedLightLRF::timer(void)
  70. {
  71. if (check_reg_counter++ == 10) {
  72. check_reg_counter = 0;
  73. if (!_dev->check_next_register()) {
  74. // re-send the acquire. this handles the case of power
  75. // cycling while running in continuous mode
  76. _dev->write_register(LL40LS_MEASURE_REG, LL40LS_MSRREG_ACQUIRE);
  77. }
  78. }
  79. switch (phase) {
  80. case PHASE_COLLECT: {
  81. be16_t val;
  82. // read the high and low byte distance registers
  83. if (_dev->read_registers(LL40LS_DISTHIGH_REG | LL40LS_AUTO_INCREMENT, (uint8_t*)&val, sizeof(val))) {
  84. uint16_t _distance_cm = be16toh(val);
  85. // remove momentary spikes
  86. if (abs(_distance_cm - last_distance_cm) < 100) {
  87. state.distance_cm = _distance_cm;
  88. state.last_reading_ms = AP_HAL::millis();
  89. update_status();
  90. }
  91. last_distance_cm = _distance_cm;
  92. } else {
  93. set_status(RangeFinder::RangeFinder_NoData);
  94. }
  95. if (!v2_hardware) {
  96. // for v2 hw we use continuous mode
  97. phase = PHASE_MEASURE;
  98. }
  99. if (!v3hp_hardware) {
  100. // for v3hp hw we start PHASE_MEASURE immediately after PHASE_COLLECT
  101. break;
  102. }
  103. }
  104. FALLTHROUGH;
  105. case PHASE_MEASURE:
  106. if (_dev->write_register(LL40LS_MEASURE_REG, LL40LS_MSRREG_ACQUIRE)) {
  107. phase = PHASE_COLLECT;
  108. }
  109. break;
  110. }
  111. }
  112. /*
  113. a table of settings for a lidar
  114. */
  115. struct settings_table {
  116. uint8_t reg;
  117. uint8_t value;
  118. };
  119. /*
  120. register setup table for V1 Lidar
  121. */
  122. static const struct settings_table settings_v1[] = {
  123. { LL40LS_MEASURE_REG, LL40LS_MSRREG_RESET },
  124. };
  125. /*
  126. register setup table for V2 Lidar
  127. */
  128. static const struct settings_table settings_v2[] = {
  129. { LL40LS_INTERVAL, 0x28 }, // 0x28 == 50Hz
  130. { LL40LS_COUNT, LL40LS_COUNT_CONTINUOUS },
  131. { LL40LS_MEASURE_REG, LL40LS_MSRREG_ACQUIRE },
  132. };
  133. /*
  134. register setup table for V3HP Lidar
  135. */
  136. static const struct settings_table settings_v3hp[] = {
  137. { LL40LS_SIG_COUNT_VAL, 0x80 }, // 0x80 = 128 acquisitions
  138. };
  139. /*
  140. initialise the sensor to required settings
  141. */
  142. bool AP_RangeFinder_PulsedLightLRF::init(void)
  143. {
  144. if (!_dev || !_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  145. return false;
  146. }
  147. _dev->set_retries(3);
  148. // LidarLite needs split transfers
  149. _dev->set_split_transfers(true);
  150. if (rftype == RangeFinder::RangeFinder_TYPE_PLI2CV3) {
  151. v2_hardware = true;
  152. } else if (rftype == RangeFinder::RangeFinder_TYPE_PLI2CV3HP) {
  153. v3hp_hardware = true;
  154. } else {
  155. // auto-detect v1 vs v2
  156. if (!(_dev->read_registers(LL40LS_HW_VERSION, &hw_version, 1) &&
  157. hw_version > 0 &&
  158. _dev->read_registers(LL40LS_SW_VERSION, &sw_version, 1) &&
  159. sw_version > 0)) {
  160. printf("PulsedLightI2C: bad version 0x%02x 0x%02x\n", (unsigned)hw_version, (unsigned)sw_version);
  161. // invalid version information
  162. goto failed;
  163. }
  164. v2_hardware = (hw_version >= 0x15);
  165. }
  166. const struct settings_table *table;
  167. uint8_t num_settings;
  168. if (v2_hardware) {
  169. table = settings_v2;
  170. num_settings = sizeof(settings_v2) / sizeof(settings_table);
  171. phase = PHASE_COLLECT;
  172. } else if (v3hp_hardware) {
  173. table = settings_v3hp;
  174. num_settings = sizeof(settings_v3hp) / sizeof(settings_table);
  175. phase = PHASE_MEASURE;
  176. } else {
  177. table = settings_v1;
  178. num_settings = sizeof(settings_v1) / sizeof(settings_table);
  179. phase = PHASE_MEASURE;
  180. }
  181. _dev->setup_checked_registers(num_settings);
  182. for (uint8_t i = 0; i < num_settings; i++) {
  183. if (!_dev->write_register(table[i].reg, table[i].value, true)) {
  184. goto failed;
  185. }
  186. }
  187. printf("Found LidarLite device=0x%x v2=%d v3hp=%d\n", _dev->get_bus_id(), (int)v2_hardware, (int)v3hp_hardware);
  188. _dev->get_semaphore()->give();
  189. _dev->register_periodic_callback(20000,
  190. FUNCTOR_BIND_MEMBER(&AP_RangeFinder_PulsedLightLRF::timer, void));
  191. return true;
  192. failed:
  193. _dev->get_semaphore()->give();
  194. return false;
  195. }