Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_NMEA.h
Views: 1798
#pragma once12#include "AP_Airspeed_config.h"34#if AP_AIRSPEED_NMEA_ENABLED56#include "AP_Airspeed_Backend.h"7#include <AP_HAL/AP_HAL.h>89class AP_Airspeed_NMEA : public AP_Airspeed_Backend10{11public:1213using AP_Airspeed_Backend::AP_Airspeed_Backend;1415// probe and initialise the sensor16bool init(void) override;1718// this reads airspeed directly19bool has_airspeed() override {return true;}2021// read the from the sensor22bool get_airspeed(float &airspeed) override;2324// return the current temperature in degrees C25bool get_temperature(float &temperature) override;262728private:29// pointer to serial uart30AP_HAL::UARTDriver *_uart = nullptr;3132// add a single character to the buffer and attempt to decode33// returns true if a complete sentence was successfully decoded34// distance should be pulled directly from _distance_m member35bool decode(char c);3637// decode the just-completed term38// returns true if new sentence has just passed checksum test and is validated39bool decode_latest_term();4041// enum for handled messages42enum sentence_types : uint8_t {43TPYE_MTW = 0,44TYPE_VHW,45};464748// message decoding related members49char _term[15]; // buffer for the current term within the current sentence50uint8_t _term_offset; // offset within the _term buffer where the next character should be placed51uint8_t _term_number; // term index within the current sentence52float _speed; // speed in m/s53float _temp; // temp in deg c54uint8_t _checksum; // checksum accumulator55bool _term_is_checksum; // current term is the checksum56bool _sentence_done; // has the current term already been decoded57bool _sentence_valid; // is the decodeing valid so far58sentence_types _sentence_type; // the sentence type currently being processed5960// Store the temp ready for a temp request61float _temp_sum;62uint16_t _temp_count;6364// store last sent speed and temp as update rate is slow65float _last_temp;66float _last_speed;6768// time last message was received69uint32_t _last_update_ms;70};7172#endif // AP_AIRSPEED_NMEA_ENABLED737475