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.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15* NMEA Sensor driver for VHW ans MTW messages over Serial16* https://gpsd.gitlab.io/gpsd/NMEA.html#_vhw_water_speed_and_heading17* https://gpsd.gitlab.io/gpsd/NMEA.html#_mtw_mean_temperature_of_water18*/1920#include "AP_Airspeed_NMEA.h"2122#if AP_AIRSPEED_NMEA_ENABLED2324#include <AP_Vehicle/AP_Vehicle_Type.h>25#if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub)2627#include "AP_Airspeed.h"28#include <AP_SerialManager/AP_SerialManager.h>2930#define TIMEOUT_MS 20003132bool AP_Airspeed_NMEA::init()33{34const AP_SerialManager& serial_manager = AP::serialmanager();3536_uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_AirSpeed, 0);37if (_uart == nullptr) {38return false;39}4041set_bus_id(AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SERIAL,0,0,0));4243_uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_AirSpeed, 0));4445// make sure this sensor cannot be used in the EKF46set_use(0);4748// must set use zero offset to pass offset check for health49set_use_zero_offset();5051return true;52}5354// read the from the sensor55bool AP_Airspeed_NMEA::get_airspeed(float &airspeed)56{57if (_uart == nullptr) {58return false;59}6061uint32_t now = AP_HAL::millis();6263// read any available lines from the sensor64float sum = 0.0f;65uint16_t count = 0;66int16_t nbytes = _uart->available();67while (nbytes-- > 0) {68int16_t c = _uart->read();69if (c==-1) {70return false;71}72if (decode(char(c))) {73_last_update_ms = now;74if (_sentence_type == TYPE_VHW) {75sum += _speed;76count++;77} else {78_temp_sum += _temp;79_temp_count++;80}81}82}8384if (count == 0) {85// Cant return false because updates are too slow, return previous reading86// Could return false after some timeout, however testing shows that the DST800 just stops sending the message at zero speed87airspeed = _last_speed;88} else {89// return average of all measurements90airspeed = sum / count;91_last_speed = airspeed;92}9394return (now - _last_update_ms) < TIMEOUT_MS;95}9697// return the current temperature in degrees C98// the main update is done in the get_pressure function99// this just reports the value100bool AP_Airspeed_NMEA::get_temperature(float &temperature)101{102if (_uart == nullptr) {103return false;104}105106if (_temp_count == 0) {107temperature = _last_temp;108} else {109// return average of all measurements110temperature = _temp_sum / _temp_count;111_last_temp = temperature;112_temp_count = 0;113_temp_sum = 0;114}115116return true;117}118119120// add a single character to the buffer and attempt to decode121// returns true if a complete sentence was successfully decoded122bool AP_Airspeed_NMEA::decode(char c)123{124switch (c) {125case ',':126// end of a term, add to checksum127_checksum ^= c;128FALLTHROUGH;129case '\r':130case '\n':131case '*':132{133if (!_sentence_done && _sentence_valid) {134// null terminate and decode latest term135_term[_term_offset] = 0;136bool valid_sentence = decode_latest_term();137138// move onto next term139_term_number++;140_term_offset = 0;141_term_is_checksum = (c == '*');142return valid_sentence;143}144return false;145}146147case '$': // sentence begin148_term_number = 0;149_term_offset = 0;150_checksum = 0;151_term_is_checksum = false;152_sentence_done = false;153_sentence_valid = true;154return false;155}156157// ordinary characters are added to term158if (_term_offset < sizeof(_term) - 1) {159_term[_term_offset++] = c;160}161if (!_term_is_checksum) {162_checksum ^= c;163}164165return false;166}167168// decode the most recently consumed term169// returns true if new sentence has just passed checksum test and is validated170bool AP_Airspeed_NMEA::decode_latest_term()171{172// handle the last term in a message173if (_term_is_checksum) {174_sentence_done = true;175uint8_t nibble_high = 0;176uint8_t nibble_low = 0;177if (!hex_to_uint8(_term[0], nibble_high) || !hex_to_uint8(_term[1], nibble_low)) {178return false;179}180const uint8_t checksum = (nibble_high << 4u) | nibble_low;181return checksum == _checksum;182}183184// the first term determines the sentence type185if (_term_number == 0) {186// the first two letters of the NMEA term are the talker ID.187// we accept any two characters here.188// actually expecting YX for MTW and VW for VHW189if (_term[0] < 'A' || _term[0] > 'Z' ||190_term[1] < 'A' || _term[1] > 'Z') {191return false;192}193const char *term_type = &_term[2];194if (strcmp(term_type, "MTW") == 0) {195_sentence_type = TPYE_MTW;196} else if (strcmp(term_type, "VHW") == 0) {197_sentence_type = TYPE_VHW;198} else {199_sentence_valid = false;200}201return false;202}203204if (_sentence_type == TPYE_MTW) {205// parse MTW messages206if (_term_number == 1) {207_temp = strtof(_term, NULL);208}209} else if (_sentence_type == TYPE_VHW) {210// parse VHW messages211if (_term_number == 7) {212_speed = strtof(_term, NULL) * KM_PER_HOUR_TO_M_PER_SEC;213}214}215216return false;217}218219#endif // APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub)220221#endif // AP_AIRSPEED_NMEA_ENABLED222223224