123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187 |
- #pragma once
- #include "AP_GPS.h"
- #include "GPS_Backend.h"
- class AP_GPS_NOVA : public AP_GPS_Backend
- {
- public:
- AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
- AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
-
- bool read() override;
- void inject_data(const uint8_t *data, uint16_t len) override;
- const char *name() const override { return "NOVA"; }
- private:
- bool parse(uint8_t temp);
- bool process_message();
- uint32_t CRC32Value(uint32_t icrc);
- uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc);
- static const uint8_t NOVA_PREAMBLE1 = 0xaa;
- static const uint8_t NOVA_PREAMBLE2 = 0x44;
- static const uint8_t NOVA_PREAMBLE3 = 0x12;
-
- bool _new_position:1;
-
- bool _new_speed:1;
-
- uint32_t _last_vel_time;
-
- uint8_t _init_blob_index = 0;
- uint32_t _init_blob_time = 0;
- const char* _initialisation_blob[6] = {
- "\r\n\r\nunlogall\r\n",
- "log bestposb ontime 0.2 0 nohold\r\n",
- "log bestvelb ontime 0.2 0 nohold\r\n",
- "log psrdopb onchanged\r\n",
- "log psrdopb ontime 0.2\r\n",
- "log psrdopb\r\n"
- };
-
- uint32_t crc_error_counter = 0;
- uint32_t last_injected_data_ms = 0;
- struct PACKED nova_header
- {
-
- uint8_t preamble[3];
-
- uint8_t headerlength;
-
- uint16_t messageid;
-
- uint8_t messagetype;
-
- uint8_t portaddr;
-
- uint16_t messagelength;
-
- uint16_t sequence;
-
- uint8_t idletime;
-
- uint8_t timestatus;
-
- uint16_t week;
-
- uint32_t tow;
-
- uint32_t recvstatus;
-
- uint16_t resv;
-
- uint16_t recvswver;
- };
- struct PACKED psrdop
- {
- float gdop;
- float pdop;
- float hdop;
- float htdop;
- float tdop;
- float cutoff;
- uint32_t svcount;
-
- };
- struct PACKED bestpos
- {
- uint32_t solstat;
- uint32_t postype;
- double lat;
- double lng;
- double hgt;
- float undulation;
- uint32_t datumid;
- float latsdev;
- float lngsdev;
- float hgtsdev;
-
- uint8_t stnid[4];
- float diffage;
- float sol_age;
- uint8_t svstracked;
- uint8_t svsused;
- uint8_t svsl1;
- uint8_t svsmultfreq;
- uint8_t resv;
- uint8_t extsolstat;
- uint8_t galbeisigmask;
- uint8_t gpsglosigmask;
- };
- struct PACKED bestvel
- {
- uint32_t solstat;
- uint32_t veltype;
- float latency;
- float age;
- double horspd;
- double trkgnd;
-
- double vertspd;
- float resv;
- };
-
- union PACKED msgbuffer {
- bestvel bestvelu;
- bestpos bestposu;
- psrdop psrdopu;
- uint8_t bytes[256];
- };
-
- union PACKED msgheader {
- nova_header nova_headeru;
- uint8_t data[28];
- };
- struct PACKED nova_msg_parser
- {
- enum
- {
- PREAMBLE1 = 0,
- PREAMBLE2,
- PREAMBLE3,
- HEADERLENGTH,
- HEADERDATA,
- DATA,
- CRC1,
- CRC2,
- CRC3,
- CRC4,
- } nova_state;
-
- msgbuffer data;
- uint32_t crc;
- msgheader header;
- uint16_t read;
- } nova_msg;
- };
|