AP_RangeFinder_uLanding.cpp 7.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220
  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_HAL/AP_HAL.h>
  14. #include "AP_RangeFinder_uLanding.h"
  15. #include <AP_SerialManager/AP_SerialManager.h>
  16. #include <ctype.h>
  17. #define ULANDING_HDR 254 // Header Byte from uLanding (0xFE)
  18. #define ULANDING_HDR_V0 72 // Header Byte for beta V0 of uLanding (0x48)
  19. #define ULANDING_BAUD 115200
  20. #define ULANDING_BUFSIZE_RX 128
  21. #define ULANDING_BUFSIZE_TX 128
  22. extern const AP_HAL::HAL& hal;
  23. /*
  24. The constructor also initialises the rangefinder. Note that this
  25. constructor is not called until detect() returns true, so we
  26. already know that we should setup the rangefinder
  27. */
  28. AP_RangeFinder_uLanding::AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State &_state,
  29. AP_RangeFinder_Params &_params,
  30. uint8_t serial_instance) :
  31. AP_RangeFinder_Backend(_state, _params)
  32. {
  33. uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
  34. if (uart != nullptr) {
  35. uart->begin(ULANDING_BAUD, ULANDING_BUFSIZE_RX, ULANDING_BUFSIZE_TX);
  36. }
  37. }
  38. /*
  39. detect if a uLanding rangefinder is connected. We'll detect by
  40. trying to take a reading on Serial. If we get a result the sensor is
  41. there.
  42. */
  43. bool AP_RangeFinder_uLanding::detect(uint8_t serial_instance)
  44. {
  45. return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
  46. }
  47. /*
  48. detect uLanding Firmware Version
  49. */
  50. bool AP_RangeFinder_uLanding::detect_version(void)
  51. {
  52. if (_version_known) {
  53. // return true if we've already detected the uLanding version
  54. return true;
  55. } else if (uart == nullptr) {
  56. return false;
  57. }
  58. bool hdr_found = false;
  59. uint8_t byte1 = 0;
  60. uint8_t count = 0;
  61. // read any available data from uLanding
  62. int16_t nbytes = uart->available();
  63. while (nbytes-- > 0) {
  64. uint8_t c = uart->read();
  65. if (((c == ULANDING_HDR_V0) || (c == ULANDING_HDR)) && !hdr_found) {
  66. byte1 = c;
  67. hdr_found = true;
  68. count++;
  69. } else if (hdr_found) {
  70. if (byte1 == ULANDING_HDR_V0) {
  71. if (++count < 4) {
  72. /* need to collect 4 bytes to check for recurring
  73. * header byte in the old 3-byte data format
  74. */
  75. continue;
  76. } else {
  77. if (c == byte1) {
  78. // if header byte is recurring, set uLanding Version
  79. _version = 0;
  80. _header = ULANDING_HDR_V0;
  81. _version_known = true;
  82. return true;
  83. } else {
  84. /* if V0 header byte didn't occur again on 4th byte,
  85. * start the search again for a header byte
  86. */
  87. count = 0;
  88. byte1 = 0;
  89. hdr_found = false;
  90. }
  91. }
  92. } else {
  93. if ((c & 0x80) || (c == ULANDING_HDR_V0)) {
  94. /* Though unlikely, it is possible we could find ULANDING_HDR
  95. * in a data byte from the old 3-byte format. In this case,
  96. * either the next byte is another data byte (which by default
  97. * is of the form 0x1xxxxxxx), or the next byte is the old
  98. * header byte (ULANDING_HDR_V0). In this case, start the search
  99. * again for a header byte.
  100. */
  101. count = 0;
  102. byte1 = 0;
  103. hdr_found = false;
  104. } else {
  105. /* if this second byte passes the above if statement, this byte
  106. * is the version number
  107. */
  108. _version = c;
  109. _header = ULANDING_HDR;
  110. _version_known = true;
  111. return true;
  112. }
  113. }
  114. }
  115. }
  116. /* return false if we've gone through all available data
  117. * and haven't detected a uLanding firmware version
  118. */
  119. return false;
  120. }
  121. // read - return last value measured by sensor
  122. bool AP_RangeFinder_uLanding::get_reading(uint16_t &reading_cm)
  123. {
  124. if (uart == nullptr) {
  125. return false;
  126. }
  127. if (!detect_version()) {
  128. // return false if uLanding version check failed
  129. return false;
  130. }
  131. // read any available lines from the uLanding
  132. float sum = 0;
  133. uint16_t count = 0;
  134. bool hdr_found = false;
  135. int16_t nbytes = uart->available();
  136. while (nbytes-- > 0) {
  137. uint8_t c = uart->read();
  138. if ((c == _header) && !hdr_found) {
  139. // located header byte
  140. _linebuf_len = 0;
  141. hdr_found = true;
  142. }
  143. // decode index information
  144. if (hdr_found) {
  145. _linebuf[_linebuf_len++] = c;
  146. if ((_linebuf_len < (sizeof(_linebuf)/sizeof(_linebuf[0]))) ||
  147. (_version == 0 && _linebuf_len < 3)) {
  148. /* don't process _linebuf until we've collected six bytes of data
  149. * (or 3 bytes for Version 0 firmware)
  150. */
  151. continue;
  152. } else {
  153. if (_version == 0 && _header != ULANDING_HDR) {
  154. // parse data for Firmware Version #0
  155. sum += (_linebuf[2]&0x7F)*128 + (_linebuf[1]&0x7F);
  156. count++;
  157. } else {
  158. // evaluate checksum
  159. if (((_linebuf[1] + _linebuf[2] + _linebuf[3] + _linebuf[4]) & 0xFF) == _linebuf[5]) {
  160. // if checksum passed, parse data for Firmware Version #1
  161. sum += _linebuf[3]*256 + _linebuf[2];
  162. count++;
  163. }
  164. }
  165. hdr_found = false;
  166. _linebuf_len = 0;
  167. }
  168. }
  169. }
  170. if (count == 0) {
  171. return false;
  172. }
  173. reading_cm = sum / count;
  174. if (_version == 0 && _header != ULANDING_HDR) {
  175. reading_cm *= 2.5f;
  176. }
  177. return true;
  178. }
  179. /*
  180. update the state of the sensor
  181. */
  182. void AP_RangeFinder_uLanding::update(void)
  183. {
  184. if (get_reading(state.distance_cm)) {
  185. state.last_reading_ms = AP_HAL::millis();
  186. // update range_valid state based on distance measured
  187. update_status();
  188. } else if (AP_HAL::millis() - state.last_reading_ms > 200) {
  189. set_status(RangeFinder::RangeFinder_NoData);
  190. }
  191. }