AP_RangeFinder_TeraRangerI2C.cpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196
  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. driver for TeraRanger I2C rangefinders
  15. */
  16. #include "AP_RangeFinder_TeraRangerI2C.h"
  17. #include <utility>
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_Math/crc.h>
  20. extern const AP_HAL::HAL& hal;
  21. // registers
  22. #define TR_MEASURE 0x00
  23. #define TR_WHOAMI 0x01
  24. #define TR_WHOAMI_VALUE 0xA1
  25. /*
  26. The constructor also initializes the rangefinder. Note that this
  27. constructor is not called until detect() returns true, so we
  28. already know that we should setup the rangefinder
  29. */
  30. AP_RangeFinder_TeraRangerI2C::AP_RangeFinder_TeraRangerI2C(RangeFinder::RangeFinder_State &_state,
  31. AP_RangeFinder_Params &_params,
  32. AP_HAL::OwnPtr<AP_HAL::I2CDevice> i2c_dev)
  33. : AP_RangeFinder_Backend(_state, _params)
  34. , dev(std::move(i2c_dev))
  35. {
  36. }
  37. /*
  38. detect if a TeraRanger rangefinder is connected. We'll detect by
  39. trying to take a reading on I2C. If we get a result the sensor is
  40. there.
  41. */
  42. AP_RangeFinder_Backend *AP_RangeFinder_TeraRangerI2C::detect(RangeFinder::RangeFinder_State &_state,
  43. AP_RangeFinder_Params &_params,
  44. AP_HAL::OwnPtr<AP_HAL::I2CDevice> i2c_dev)
  45. {
  46. if (!i2c_dev) {
  47. return nullptr;
  48. }
  49. AP_RangeFinder_TeraRangerI2C *sensor = new AP_RangeFinder_TeraRangerI2C(_state, _params, std::move(i2c_dev));
  50. if (!sensor) {
  51. return nullptr;
  52. }
  53. if (!sensor->init()) {
  54. delete sensor;
  55. return nullptr;
  56. }
  57. return sensor;
  58. }
  59. /*
  60. initialise sensor
  61. */
  62. bool AP_RangeFinder_TeraRangerI2C::init(void)
  63. {
  64. if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  65. return false;
  66. }
  67. dev->set_retries(10);
  68. // check WHOAMI
  69. uint8_t whoami;
  70. if (!dev->read_registers(TR_WHOAMI, &whoami, 1) ||
  71. whoami != TR_WHOAMI_VALUE) {
  72. dev->get_semaphore()->give();
  73. return false;
  74. }
  75. if (!measure()) {
  76. dev->get_semaphore()->give();
  77. return false;
  78. }
  79. // give time for the sensor to process the request
  80. hal.scheduler->delay(70);
  81. uint16_t _distance_cm;
  82. if (!collect_raw(_distance_cm)) {
  83. dev->get_semaphore()->give();
  84. return false;
  85. }
  86. dev->get_semaphore()->give();
  87. dev->set_retries(1);
  88. dev->register_periodic_callback(10000,
  89. FUNCTOR_BIND_MEMBER(&AP_RangeFinder_TeraRangerI2C::timer, void));
  90. return true;
  91. }
  92. // measure() - ask sensor to make a range reading
  93. bool AP_RangeFinder_TeraRangerI2C::measure()
  94. {
  95. uint8_t cmd = TR_MEASURE;
  96. return dev->transfer(&cmd, 1, nullptr, 0);
  97. }
  98. // collect_raw() - return last value measured by sensor
  99. bool AP_RangeFinder_TeraRangerI2C::collect_raw(uint16_t &raw_distance)
  100. {
  101. uint8_t d[3];
  102. // Take range reading
  103. if (!dev->transfer(nullptr, 0, d, sizeof(d))) {
  104. return false;
  105. }
  106. // Check for CRC
  107. if (d[2] != crc_crc8(d, 2)) {
  108. return false;
  109. } else {
  110. raw_distance = ((uint16_t(d[0]) << 8) | d[1]);
  111. return true;
  112. }
  113. }
  114. // Checks for error code and if correct converts to cm
  115. bool AP_RangeFinder_TeraRangerI2C::process_raw_measure(uint16_t raw_distance, uint16_t &output_distance_cm)
  116. {
  117. // Check for error codes
  118. if (raw_distance == 0xFFFF) {
  119. // Too far away is unreliable so we dont enforce max range here
  120. return false;
  121. } else if (raw_distance == 0x0000) {
  122. // Too close
  123. output_distance_cm = params.min_distance_cm;
  124. return true;
  125. } else if (raw_distance == 0x0001) {
  126. // Unable to measure
  127. return false;
  128. } else {
  129. output_distance_cm = raw_distance/10; // Conversion to centimeters
  130. return true;
  131. }
  132. }
  133. /*
  134. timer called at 100Hz, EVO sensors max freq is 100..240Hz
  135. */
  136. void AP_RangeFinder_TeraRangerI2C::timer(void)
  137. {
  138. // Take a reading
  139. uint16_t _raw_distance = 0;
  140. uint16_t _distance_cm = 0;
  141. if (collect_raw(_raw_distance)) {
  142. WITH_SEMAPHORE(_sem);
  143. if (process_raw_measure(_raw_distance, _distance_cm)){
  144. accum.sum += _distance_cm;
  145. accum.count++;
  146. }
  147. }
  148. // and immediately ask for a new reading
  149. measure();
  150. }
  151. /*
  152. update the state of the sensor
  153. */
  154. void AP_RangeFinder_TeraRangerI2C::update(void)
  155. {
  156. WITH_SEMAPHORE(_sem);
  157. if (accum.count > 0) {
  158. state.distance_cm = accum.sum / accum.count;
  159. state.last_reading_ms = AP_HAL::millis();
  160. accum.sum = 0;
  161. accum.count = 0;
  162. update_status();
  163. } else if (AP_HAL::millis() - state.last_reading_ms > 200) {
  164. set_status(RangeFinder::RangeFinder_NoData);
  165. }
  166. }