AP_RangeFinder_MaxsonarSerialLV.cpp 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103
  1. /*
  2. * Copyright (C) 2016 Intel Corporation. All rights reserved.
  3. *
  4. * This file is free software: you can redistribute it and/or modify it
  5. * under the terms of the GNU General Public License as published by the
  6. * Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This file is distributed in the hope that it will be useful, but
  10. * WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  12. * See the GNU General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU General Public License along
  15. * with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #include <AP_HAL/AP_HAL.h>
  18. #include <AP_SerialManager/AP_SerialManager.h>
  19. #include <ctype.h>
  20. #include "AP_RangeFinder_MaxsonarSerialLV.h"
  21. #define MAXSONAR_SERIAL_LV_BAUD_RATE 9600
  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_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
  29. AP_RangeFinder_Params &_params,
  30. uint8_t serial_instance) :
  31. AP_RangeFinder_Backend(_state, _params)
  32. {
  33. const AP_SerialManager &serial_manager = AP::serialmanager();
  34. uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
  35. if (uart != nullptr) {
  36. uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
  37. }
  38. }
  39. /*
  40. detect if a MaxSonar rangefinder is connected. We'll detect by
  41. trying to take a reading on Serial. If we get a result the sensor is
  42. there.
  43. */
  44. bool AP_RangeFinder_MaxsonarSerialLV::detect(uint8_t serial_instance)
  45. {
  46. return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
  47. }
  48. // read - return last value measured by sensor
  49. bool AP_RangeFinder_MaxsonarSerialLV::get_reading(uint16_t &reading_cm)
  50. {
  51. if (uart == nullptr) {
  52. return false;
  53. }
  54. int32_t sum = 0;
  55. int16_t nbytes = uart->available();
  56. uint16_t count = 0;
  57. while (nbytes-- > 0) {
  58. char c = uart->read();
  59. if (c == '\r') {
  60. linebuf[linebuf_len] = 0;
  61. sum += (int)atoi(linebuf);
  62. count++;
  63. linebuf_len = 0;
  64. } else if (isdigit(c)) {
  65. linebuf[linebuf_len++] = c;
  66. if (linebuf_len == sizeof(linebuf)) {
  67. // too long, discard the line
  68. linebuf_len = 0;
  69. }
  70. }
  71. }
  72. if (count == 0) {
  73. return false;
  74. }
  75. // This sonar gives the metrics in inches, so we have to transform this to centimeters
  76. reading_cm = 2.54f * sum / count;
  77. return true;
  78. }
  79. /*
  80. update the state of the sensor
  81. */
  82. void AP_RangeFinder_MaxsonarSerialLV::update(void)
  83. {
  84. if (get_reading(state.distance_cm)) {
  85. // update range_valid state based on distance measured
  86. state.last_reading_ms = AP_HAL::millis();
  87. update_status();
  88. } else if (AP_HAL::millis() - state.last_reading_ms > 500) {
  89. set_status(RangeFinder::RangeFinder_NoData);
  90. }
  91. }