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_GPS/AP_GPS_NOVA.h
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*/1415// Novatel/Tersus/ComNav GPS driver for ArduPilot.16// Code by Michael Oborne17// Derived from http://www.novatel.com/assets/Documents/Manuals/om-20000129.pdf1819#pragma once2021#include "AP_GPS.h"22#include "GPS_Backend.h"2324#if AP_GPS_NOVA_ENABLED25class AP_GPS_NOVA : public AP_GPS_Backend26{27public:28AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);2930AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }3132// Methods33bool read() override;3435const char *name() const override { return "NOVA"; }3637private:3839bool parse(uint8_t temp);40bool process_message();4142static const uint8_t NOVA_PREAMBLE1 = 0xaa;43static const uint8_t NOVA_PREAMBLE2 = 0x44;44static const uint8_t NOVA_PREAMBLE3 = 0x12;4546// do we have new position information?47bool _new_position:1;48// do we have new speed information?49bool _new_speed:1;5051uint32_t _last_vel_time;5253uint8_t _init_blob_index = 0;54uint32_t _init_blob_time = 0;55static const char* const _initialisation_blob[4];5657uint32_t crc_error_counter = 0;5859struct PACKED nova_header60{61// 062uint8_t preamble[3];63// 364uint8_t headerlength;65// 466uint16_t messageid;67// 668uint8_t messagetype;69//770uint8_t portaddr;71//872uint16_t messagelength;73//1074uint16_t sequence;75//1276uint8_t idletime;77//1378uint8_t timestatus;79//1480uint16_t week;81//1682uint32_t tow;83//2084uint32_t recvstatus;85// 2486uint16_t resv;87//2688uint16_t recvswver;89};9091struct PACKED psrdop92{93float gdop;94float pdop;95float hdop;96float htdop;97float tdop;98float cutoff;99uint32_t svcount;100// extra data for individual prns101};102103struct PACKED bestpos104{105uint32_t solstat; ///< Solution status106uint32_t postype; ///< Position type107double lat; ///< latitude (deg)108double lng; ///< longitude (deg)109double hgt; ///< height above mean sea level (m)110float undulation; ///< relationship between the geoid and the ellipsoid (m)111uint32_t datumid; ///< datum id number112float latsdev; ///< latitude standard deviation (m)113float lngsdev; ///< longitude standard deviation (m)114float hgtsdev; ///< height standard deviation (m)115// 4 bytes116uint8_t stnid[4]; ///< base station id117float diffage; ///< differential position age (sec)118float sol_age; ///< solution age (sec)119uint8_t svstracked; ///< number of satellites tracked120uint8_t svsused; ///< number of satellites used in solution121uint8_t svsl1; ///< number of GPS plus GLONASS L1 satellites used in solution122uint8_t svsmultfreq; ///< number of GPS plus GLONASS L2 satellites used in solution123uint8_t resv; ///< reserved124uint8_t extsolstat; ///< extended solution status - OEMV and greater only125uint8_t galbeisigmask;126uint8_t gpsglosigmask;127};128129struct PACKED bestvel130{131uint32_t solstat;132uint32_t veltype;133float latency;134float age;135double horspd;136double trkgnd;137// + up138double vertspd;139float resv;140};141142union PACKED msgbuffer {143bestvel bestvelu;144bestpos bestposu;145psrdop psrdopu;146uint8_t bytes[256];147};148149union PACKED msgheader {150nova_header nova_headeru;151uint8_t data[28];152};153154struct PACKED nova_msg_parser155{156enum157{158PREAMBLE1 = 0,159PREAMBLE2,160PREAMBLE3,161HEADERLENGTH,162HEADERDATA,163DATA,164CRC1,165CRC2,166CRC3,167CRC4,168} nova_state;169170msgbuffer data;171uint32_t crc;172msgheader header;173uint16_t read;174} nova_msg;175};176#endif177178179