AP_GPS_NOVA.h 5.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. // Novatel/Tersus/ComNav GPS driver for ArduPilot.
  14. // Code by Michael Oborne
  15. // Derived from http://www.novatel.com/assets/Documents/Manuals/om-20000129.pdf
  16. #pragma once
  17. #include "AP_GPS.h"
  18. #include "GPS_Backend.h"
  19. class AP_GPS_NOVA : public AP_GPS_Backend
  20. {
  21. public:
  22. AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
  23. AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
  24. // Methods
  25. bool read() override;
  26. void inject_data(const uint8_t *data, uint16_t len) override;
  27. const char *name() const override { return "NOVA"; }
  28. private:
  29. bool parse(uint8_t temp);
  30. bool process_message();
  31. uint32_t CRC32Value(uint32_t icrc);
  32. uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc);
  33. static const uint8_t NOVA_PREAMBLE1 = 0xaa;
  34. static const uint8_t NOVA_PREAMBLE2 = 0x44;
  35. static const uint8_t NOVA_PREAMBLE3 = 0x12;
  36. // do we have new position information?
  37. bool _new_position:1;
  38. // do we have new speed information?
  39. bool _new_speed:1;
  40. uint32_t _last_vel_time;
  41. uint8_t _init_blob_index = 0;
  42. uint32_t _init_blob_time = 0;
  43. const char* _initialisation_blob[6] = {
  44. "\r\n\r\nunlogall\r\n", // cleanup enviroment
  45. "log bestposb ontime 0.2 0 nohold\r\n", // get bestpos
  46. "log bestvelb ontime 0.2 0 nohold\r\n", // get bestvel
  47. "log psrdopb onchanged\r\n", // tersus
  48. "log psrdopb ontime 0.2\r\n", // comnav
  49. "log psrdopb\r\n" // poll message, as dop only changes when a sat is dropped/added to the visible list
  50. };
  51. uint32_t crc_error_counter = 0;
  52. uint32_t last_injected_data_ms = 0;
  53. struct PACKED nova_header
  54. {
  55. // 0
  56. uint8_t preamble[3];
  57. // 3
  58. uint8_t headerlength;
  59. // 4
  60. uint16_t messageid;
  61. // 6
  62. uint8_t messagetype;
  63. //7
  64. uint8_t portaddr;
  65. //8
  66. uint16_t messagelength;
  67. //10
  68. uint16_t sequence;
  69. //12
  70. uint8_t idletime;
  71. //13
  72. uint8_t timestatus;
  73. //14
  74. uint16_t week;
  75. //16
  76. uint32_t tow;
  77. //20
  78. uint32_t recvstatus;
  79. // 24
  80. uint16_t resv;
  81. //26
  82. uint16_t recvswver;
  83. };
  84. struct PACKED psrdop
  85. {
  86. float gdop;
  87. float pdop;
  88. float hdop;
  89. float htdop;
  90. float tdop;
  91. float cutoff;
  92. uint32_t svcount;
  93. // extra data for individual prns
  94. };
  95. struct PACKED bestpos
  96. {
  97. uint32_t solstat; ///< Solution status
  98. uint32_t postype; ///< Position type
  99. double lat; ///< latitude (deg)
  100. double lng; ///< longitude (deg)
  101. double hgt; ///< height above mean sea level (m)
  102. float undulation; ///< relationship between the geoid and the ellipsoid (m)
  103. uint32_t datumid; ///< datum id number
  104. float latsdev; ///< latitude standard deviation (m)
  105. float lngsdev; ///< longitude standard deviation (m)
  106. float hgtsdev; ///< height standard deviation (m)
  107. // 4 bytes
  108. uint8_t stnid[4]; ///< base station id
  109. float diffage; ///< differential position age (sec)
  110. float sol_age; ///< solution age (sec)
  111. uint8_t svstracked; ///< number of satellites tracked
  112. uint8_t svsused; ///< number of satellites used in solution
  113. uint8_t svsl1; ///< number of GPS plus GLONASS L1 satellites used in solution
  114. uint8_t svsmultfreq; ///< number of GPS plus GLONASS L2 satellites used in solution
  115. uint8_t resv; ///< reserved
  116. uint8_t extsolstat; ///< extended solution status - OEMV and greater only
  117. uint8_t galbeisigmask;
  118. uint8_t gpsglosigmask;
  119. };
  120. struct PACKED bestvel
  121. {
  122. uint32_t solstat;
  123. uint32_t veltype;
  124. float latency;
  125. float age;
  126. double horspd;
  127. double trkgnd;
  128. // + up
  129. double vertspd;
  130. float resv;
  131. };
  132. union PACKED msgbuffer {
  133. bestvel bestvelu;
  134. bestpos bestposu;
  135. psrdop psrdopu;
  136. uint8_t bytes[256];
  137. };
  138. union PACKED msgheader {
  139. nova_header nova_headeru;
  140. uint8_t data[28];
  141. };
  142. struct PACKED nova_msg_parser
  143. {
  144. enum
  145. {
  146. PREAMBLE1 = 0,
  147. PREAMBLE2,
  148. PREAMBLE3,
  149. HEADERLENGTH,
  150. HEADERDATA,
  151. DATA,
  152. CRC1,
  153. CRC2,
  154. CRC3,
  155. CRC4,
  156. } nova_state;
  157. msgbuffer data;
  158. uint32_t crc;
  159. msgheader header;
  160. uint16_t read;
  161. } nova_msg;
  162. };