12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273 |
- #pragma once
- #include "RangeFinder.h"
- #include "RangeFinder_Backend.h"
- class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend
- {
- public:
-
- AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state,
- AP_RangeFinder_Params &_params,
- uint8_t serial_instance);
-
- static bool detect(uint8_t serial_instance);
-
- void update(void) override;
- protected:
- virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
- return MAV_DISTANCE_SENSOR_ULTRASOUND;
- }
- private:
-
- enum sentence_types : uint8_t {
- SONAR_UNKNOWN = 0,
- SONAR_DBT,
- SONAR_DPT
- };
-
- bool get_reading(uint16_t &reading_cm);
-
-
-
- bool decode(char c);
-
-
- bool decode_latest_term();
- AP_HAL::UARTDriver *uart = nullptr;
-
- char _term[15];
- uint8_t _term_offset;
- uint8_t _term_number;
- float _distance_m;
- uint8_t _checksum;
- bool _term_is_checksum;
- sentence_types _sentence_type;
- };
|