AP_RangeFinder_NMEA.cpp 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183
  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_LightWareSerial.h"
  15. #include <AP_SerialManager/AP_SerialManager.h>
  16. #include <ctype.h>
  17. #include "AP_RangeFinder_NMEA.h"
  18. extern const AP_HAL::HAL& hal;
  19. // constructor initialises the rangefinder
  20. // Note this is called after detect() returns true, so we
  21. // already know that we should setup the rangefinder
  22. AP_RangeFinder_NMEA::AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state,
  23. AP_RangeFinder_Params &_params,
  24. uint8_t serial_instance) :
  25. AP_RangeFinder_Backend(_state, _params),
  26. _distance_m(-1.0f)
  27. {
  28. const AP_SerialManager &serial_manager = AP::serialmanager();
  29. uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
  30. if (uart != nullptr) {
  31. uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
  32. }
  33. }
  34. // detect if a NMEA rangefinder by looking to see if the user has configured it
  35. bool AP_RangeFinder_NMEA::detect(uint8_t serial_instance)
  36. {
  37. return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
  38. }
  39. // update the state of the sensor
  40. void AP_RangeFinder_NMEA::update(void)
  41. {
  42. uint32_t now = AP_HAL::millis();
  43. if (get_reading(state.distance_cm)) {
  44. // update range_valid state based on distance measured
  45. state.last_reading_ms = now;
  46. update_status();
  47. } else if ((now - state.last_reading_ms) > 3000) {
  48. set_status(RangeFinder::RangeFinder_NoData);
  49. }
  50. }
  51. // return last value measured by sensor
  52. bool AP_RangeFinder_NMEA::get_reading(uint16_t &reading_cm)
  53. {
  54. if (uart == nullptr) {
  55. return false;
  56. }
  57. // read any available lines from the lidar
  58. float sum = 0.0f;
  59. uint16_t count = 0;
  60. int16_t nbytes = uart->available();
  61. while (nbytes-- > 0) {
  62. char c = uart->read();
  63. if (decode(c)) {
  64. sum += _distance_m;
  65. count++;
  66. }
  67. }
  68. // return false on failure
  69. if (count == 0) {
  70. return false;
  71. }
  72. // return average of all measurements
  73. reading_cm = 100.0f * sum / count;
  74. return true;
  75. }
  76. // add a single character to the buffer and attempt to decode
  77. // returns true if a complete sentence was successfully decoded
  78. bool AP_RangeFinder_NMEA::decode(char c)
  79. {
  80. switch (c) {
  81. case ',':
  82. // end of a term, add to checksum
  83. _checksum ^= c;
  84. FALLTHROUGH;
  85. case '\r':
  86. case '\n':
  87. case '*':
  88. {
  89. // null terminate and decode latest term
  90. _term[_term_offset] = 0;
  91. bool valid_sentence = decode_latest_term();
  92. // move onto next term
  93. _term_number++;
  94. _term_offset = 0;
  95. _term_is_checksum = (c == '*');
  96. return valid_sentence;
  97. }
  98. case '$': // sentence begin
  99. _sentence_type = SONAR_UNKNOWN;
  100. _term_number = 0;
  101. _term_offset = 0;
  102. _checksum = 0;
  103. _term_is_checksum = false;
  104. _distance_m = -1.0f;
  105. return false;
  106. }
  107. // ordinary characters are added to term
  108. if (_term_offset < sizeof(_term) - 1) {
  109. _term[_term_offset++] = c;
  110. }
  111. if (!_term_is_checksum) {
  112. _checksum ^= c;
  113. }
  114. return false;
  115. }
  116. // decode the most recently consumed term
  117. // returns true if new sentence has just passed checksum test and is validated
  118. bool AP_RangeFinder_NMEA::decode_latest_term()
  119. {
  120. // handle the last term in a message
  121. if (_term_is_checksum) {
  122. uint8_t nibble_high = 0;
  123. uint8_t nibble_low = 0;
  124. if (!hex_to_uint8(_term[0], nibble_high) || !hex_to_uint8(_term[1], nibble_low)) {
  125. return false;
  126. }
  127. const uint8_t checksum = (nibble_high << 4u) | nibble_low;
  128. return ((checksum == _checksum) &&
  129. !is_negative(_distance_m) &&
  130. (_sentence_type == SONAR_DBT || _sentence_type == SONAR_DPT));
  131. }
  132. // the first term determines the sentence type
  133. if (_term_number == 0) {
  134. // the first two letters of the NMEA term are the talker ID.
  135. // we accept any two characters here.
  136. if (_term[0] < 'A' || _term[0] > 'Z' ||
  137. _term[1] < 'A' || _term[1] > 'Z') {
  138. _sentence_type = SONAR_UNKNOWN;
  139. return false;
  140. }
  141. const char *term_type = &_term[2];
  142. if (strcmp(term_type, "DBT") == 0) {
  143. _sentence_type = SONAR_DBT;
  144. } else if (strcmp(term_type, "DPT") == 0) {
  145. _sentence_type = SONAR_DPT;
  146. } else {
  147. _sentence_type = SONAR_UNKNOWN;
  148. }
  149. return false;
  150. }
  151. if (_sentence_type == SONAR_DBT) {
  152. // parse DBT messages
  153. if (_term_number == 3) {
  154. _distance_m = atof(_term);
  155. }
  156. } else if (_sentence_type == SONAR_DPT) {
  157. // parse DPT messages
  158. if (_term_number == 1) {
  159. _distance_m = atof(_term);
  160. }
  161. }
  162. return false;
  163. }