AP_RangeFinder_LightWareSerial.cpp 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128
  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. extern const AP_HAL::HAL& hal;
  18. #define LIGHTWARE_DIST_MAX_CM 10000
  19. #define LIGHTWARE_OUT_OF_RANGE_ADD_CM 100
  20. /*
  21. The constructor also initialises the rangefinder. Note that this
  22. constructor is not called until detect() returns true, so we
  23. already know that we should setup the rangefinder
  24. */
  25. AP_RangeFinder_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state,
  26. AP_RangeFinder_Params &_params,
  27. uint8_t serial_instance) :
  28. AP_RangeFinder_Backend(_state, _params)
  29. {
  30. const AP_SerialManager &serial_manager = AP::serialmanager();
  31. uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
  32. if (uart != nullptr) {
  33. uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
  34. }
  35. }
  36. /*
  37. detect if a Lightware rangefinder is connected. We'll detect by
  38. trying to take a reading on Serial. If we get a result the sensor is
  39. there.
  40. */
  41. bool AP_RangeFinder_LightWareSerial::detect(uint8_t serial_instance)
  42. {
  43. return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
  44. }
  45. // read - return last value measured by sensor
  46. bool AP_RangeFinder_LightWareSerial::get_reading(uint16_t &reading_cm)
  47. {
  48. if (uart == nullptr) {
  49. return false;
  50. }
  51. float sum = 0; // sum of all readings taken
  52. uint16_t valid_count = 0; // number of valid readings
  53. uint16_t invalid_count = 0; // number of invalid readings
  54. // read any available lines from the lidar
  55. int16_t nbytes = uart->available();
  56. while (nbytes-- > 0) {
  57. char c = uart->read();
  58. if (c == '\r') {
  59. linebuf[linebuf_len] = 0;
  60. const float dist = (float)atof(linebuf);
  61. if (!is_negative(dist)) {
  62. sum += dist;
  63. valid_count++;
  64. } else {
  65. invalid_count++;
  66. }
  67. linebuf_len = 0;
  68. } else if (isdigit(c) || c == '.' || c == '-') {
  69. linebuf[linebuf_len++] = c;
  70. if (linebuf_len == sizeof(linebuf)) {
  71. // too long, discard the line
  72. linebuf_len = 0;
  73. }
  74. }
  75. }
  76. uint32_t now = AP_HAL::millis();
  77. if (last_init_ms == 0 ||
  78. (now - last_init_ms > 1000 &&
  79. now - state.last_reading_ms > 1000)) {
  80. // send enough serial transitions to trigger LW20 into serial
  81. // mode. It starts in dual I2C/serial mode, and wants to see
  82. // enough transitions to switch into serial mode.
  83. uart->write("www\r\n");
  84. last_init_ms = now;
  85. } else {
  86. uart->write('d');
  87. }
  88. // return average of all valid readings
  89. if (valid_count > 0) {
  90. reading_cm = 100 * sum / valid_count;
  91. return true;
  92. }
  93. // all readings were invalid so return out-of-range-high value
  94. if (invalid_count > 0) {
  95. reading_cm = MIN(MAX(LIGHTWARE_DIST_MAX_CM, max_distance_cm() + LIGHTWARE_OUT_OF_RANGE_ADD_CM), UINT16_MAX);
  96. return true;
  97. }
  98. // no readings so return false
  99. return false;
  100. }
  101. /*
  102. update the state of the sensor
  103. */
  104. void AP_RangeFinder_LightWareSerial::update(void)
  105. {
  106. if (get_reading(state.distance_cm)) {
  107. // update range_valid state based on distance measured
  108. state.last_reading_ms = AP_HAL::millis();
  109. update_status();
  110. } else if (AP_HAL::millis() - state.last_reading_ms > 200) {
  111. set_status(RangeFinder::RangeFinder_NoData);
  112. }
  113. }