AP_RangeFinder_NMEA.h 2.6 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273
  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. #pragma once
  14. #include "RangeFinder.h"
  15. #include "RangeFinder_Backend.h"
  16. class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend
  17. {
  18. public:
  19. // constructor
  20. AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state,
  21. AP_RangeFinder_Params &_params,
  22. uint8_t serial_instance);
  23. // static detection function
  24. static bool detect(uint8_t serial_instance);
  25. // update state
  26. void update(void) override;
  27. protected:
  28. virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
  29. return MAV_DISTANCE_SENSOR_ULTRASOUND;
  30. }
  31. private:
  32. /// enum for handled messages
  33. enum sentence_types : uint8_t {
  34. SONAR_UNKNOWN = 0,
  35. SONAR_DBT,
  36. SONAR_DPT
  37. };
  38. // get a reading
  39. bool get_reading(uint16_t &reading_cm);
  40. // add a single character to the buffer and attempt to decode
  41. // returns true if a complete sentence was successfully decoded
  42. // distance should be pulled directly from _distance_m member
  43. bool decode(char c);
  44. // decode the just-completed term
  45. // returns true if new sentence has just passed checksum test and is validated
  46. bool decode_latest_term();
  47. AP_HAL::UARTDriver *uart = nullptr; // pointer to serial uart
  48. // message decoding related members
  49. char _term[15]; // buffer for the current term within the current sentence
  50. uint8_t _term_offset; // offset within the _term buffer where the next character should be placed
  51. uint8_t _term_number; // term index within the current sentence
  52. float _distance_m; // distance in meters parsed from a term, -1 if no distance
  53. uint8_t _checksum; // checksum accumulator
  54. bool _term_is_checksum; // current term is the checksum
  55. sentence_types _sentence_type; // the sentence type currently being processed
  56. };