AP_GPS_NOVA.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317
  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. #include "AP_GPS.h"
  17. #include "AP_GPS_NOVA.h"
  18. #include <AP_Logger/AP_Logger.h>
  19. extern const AP_HAL::HAL& hal;
  20. #define NOVA_DEBUGGING 0
  21. #if NOVA_DEBUGGING
  22. #include <cstdio>
  23. # define Debug(fmt, args ...) \
  24. do { \
  25. printf("%s:%d: " fmt "\n", \
  26. __FUNCTION__, __LINE__, \
  27. ## args); \
  28. hal.scheduler->delay(1); \
  29. } while(0)
  30. #else
  31. # define Debug(fmt, args ...)
  32. #endif
  33. AP_GPS_NOVA::AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::GPS_State &_state,
  34. AP_HAL::UARTDriver *_port) :
  35. AP_GPS_Backend(_gps, _state, _port)
  36. {
  37. nova_msg.nova_state = nova_msg_parser::PREAMBLE1;
  38. const char *init_str = _initialisation_blob[0];
  39. const char *init_str1 = _initialisation_blob[1];
  40. port->write((const uint8_t*)init_str, strlen(init_str));
  41. port->write((const uint8_t*)init_str1, strlen(init_str1));
  42. }
  43. // Process all bytes available from the stream
  44. //
  45. bool
  46. AP_GPS_NOVA::read(void)
  47. {
  48. uint32_t now = AP_HAL::millis();
  49. if (_init_blob_index < (sizeof(_initialisation_blob) / sizeof(_initialisation_blob[0]))) {
  50. const char *init_str = _initialisation_blob[_init_blob_index];
  51. if (now > _init_blob_time) {
  52. port->write((const uint8_t*)init_str, strlen(init_str));
  53. _init_blob_time = now + 200;
  54. _init_blob_index++;
  55. }
  56. }
  57. bool ret = false;
  58. while (port->available() > 0) {
  59. uint8_t temp = port->read();
  60. ret |= parse(temp);
  61. }
  62. return ret;
  63. }
  64. bool
  65. AP_GPS_NOVA::parse(uint8_t temp)
  66. {
  67. switch (nova_msg.nova_state)
  68. {
  69. default:
  70. case nova_msg_parser::PREAMBLE1:
  71. if (temp == NOVA_PREAMBLE1)
  72. nova_msg.nova_state = nova_msg_parser::PREAMBLE2;
  73. nova_msg.read = 0;
  74. break;
  75. case nova_msg_parser::PREAMBLE2:
  76. if (temp == NOVA_PREAMBLE2)
  77. {
  78. nova_msg.nova_state = nova_msg_parser::PREAMBLE3;
  79. }
  80. else
  81. {
  82. nova_msg.nova_state = nova_msg_parser::PREAMBLE1;
  83. }
  84. break;
  85. case nova_msg_parser::PREAMBLE3:
  86. if (temp == NOVA_PREAMBLE3)
  87. {
  88. nova_msg.nova_state = nova_msg_parser::HEADERLENGTH;
  89. }
  90. else
  91. {
  92. nova_msg.nova_state = nova_msg_parser::PREAMBLE1;
  93. }
  94. break;
  95. case nova_msg_parser::HEADERLENGTH:
  96. Debug("NOVA HEADERLENGTH\n");
  97. nova_msg.header.data[0] = NOVA_PREAMBLE1;
  98. nova_msg.header.data[1] = NOVA_PREAMBLE2;
  99. nova_msg.header.data[2] = NOVA_PREAMBLE3;
  100. nova_msg.header.data[3] = temp;
  101. nova_msg.header.nova_headeru.headerlength = temp;
  102. nova_msg.nova_state = nova_msg_parser::HEADERDATA;
  103. nova_msg.read = 4;
  104. break;
  105. case nova_msg_parser::HEADERDATA:
  106. if (nova_msg.read >= sizeof(nova_msg.header.data)) {
  107. Debug("parse header overflow length=%u\n", (unsigned)nova_msg.read);
  108. nova_msg.nova_state = nova_msg_parser::PREAMBLE1;
  109. break;
  110. }
  111. nova_msg.header.data[nova_msg.read] = temp;
  112. nova_msg.read++;
  113. if (nova_msg.read >= nova_msg.header.nova_headeru.headerlength)
  114. {
  115. nova_msg.nova_state = nova_msg_parser::DATA;
  116. }
  117. break;
  118. case nova_msg_parser::DATA:
  119. if (nova_msg.read >= sizeof(nova_msg.data)) {
  120. Debug("parse data overflow length=%u msglength=%u\n", (unsigned)nova_msg.read,nova_msg.header.nova_headeru.messagelength);
  121. nova_msg.nova_state = nova_msg_parser::PREAMBLE1;
  122. break;
  123. }
  124. nova_msg.data.bytes[nova_msg.read - nova_msg.header.nova_headeru.headerlength] = temp;
  125. nova_msg.read++;
  126. if (nova_msg.read >= (nova_msg.header.nova_headeru.messagelength + nova_msg.header.nova_headeru.headerlength))
  127. {
  128. Debug("NOVA DATA exit\n");
  129. nova_msg.nova_state = nova_msg_parser::CRC1;
  130. }
  131. break;
  132. case nova_msg_parser::CRC1:
  133. nova_msg.crc = (uint32_t) (temp << 0);
  134. nova_msg.nova_state = nova_msg_parser::CRC2;
  135. break;
  136. case nova_msg_parser::CRC2:
  137. nova_msg.crc += (uint32_t) (temp << 8);
  138. nova_msg.nova_state = nova_msg_parser::CRC3;
  139. break;
  140. case nova_msg_parser::CRC3:
  141. nova_msg.crc += (uint32_t) (temp << 16);
  142. nova_msg.nova_state = nova_msg_parser::CRC4;
  143. break;
  144. case nova_msg_parser::CRC4:
  145. nova_msg.crc += (uint32_t) (temp << 24);
  146. nova_msg.nova_state = nova_msg_parser::PREAMBLE1;
  147. uint32_t crc = CalculateBlockCRC32((uint32_t)nova_msg.header.nova_headeru.headerlength, (uint8_t *)&nova_msg.header.data, (uint32_t)0);
  148. crc = CalculateBlockCRC32((uint32_t)nova_msg.header.nova_headeru.messagelength, (uint8_t *)&nova_msg.data, crc);
  149. if (nova_msg.crc == crc)
  150. {
  151. return process_message();
  152. }
  153. else
  154. {
  155. Debug("crc failed");
  156. crc_error_counter++;
  157. }
  158. break;
  159. }
  160. return false;
  161. }
  162. bool
  163. AP_GPS_NOVA::process_message(void)
  164. {
  165. uint16_t messageid = nova_msg.header.nova_headeru.messageid;
  166. Debug("NOVA process_message messid=%u\n",messageid);
  167. check_new_itow(nova_msg.header.nova_headeru.tow, nova_msg.header.nova_headeru.messagelength + nova_msg.header.nova_headeru.headerlength);
  168. if (messageid == 42) // bestpos
  169. {
  170. const bestpos &bestposu = nova_msg.data.bestposu;
  171. state.time_week = nova_msg.header.nova_headeru.week;
  172. state.time_week_ms = (uint32_t) nova_msg.header.nova_headeru.tow;
  173. state.last_gps_time_ms = AP_HAL::millis();
  174. state.location.lat = (int32_t) (bestposu.lat * (double)1e7);
  175. state.location.lng = (int32_t) (bestposu.lng * (double)1e7);
  176. state.location.alt = (int32_t) (bestposu.hgt * 100);
  177. state.num_sats = bestposu.svsused;
  178. state.horizontal_accuracy = (float) ((bestposu.latsdev + bestposu.lngsdev)/2);
  179. state.vertical_accuracy = (float) bestposu.hgtsdev;
  180. state.have_horizontal_accuracy = true;
  181. state.have_vertical_accuracy = true;
  182. state.rtk_age_ms = bestposu.diffage * 1000;
  183. state.rtk_num_sats = bestposu.svsused;
  184. if (bestposu.solstat == 0) // have a solution
  185. {
  186. switch (bestposu.postype)
  187. {
  188. case 16:
  189. state.status = AP_GPS::GPS_OK_FIX_3D;
  190. break;
  191. case 17: // psrdiff
  192. case 18: // waas
  193. case 20: // omnistar
  194. case 68: // ppp_converg
  195. case 69: // ppp
  196. state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
  197. break;
  198. case 32: // l1 float
  199. case 33: // iono float
  200. case 34: // narrow float
  201. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
  202. break;
  203. case 48: // l1 int
  204. case 50: // narrow int
  205. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
  206. break;
  207. case 0: // NONE
  208. case 1: // FIXEDPOS
  209. case 2: // FIXEDHEIGHT
  210. default:
  211. state.status = AP_GPS::NO_FIX;
  212. break;
  213. }
  214. }
  215. else
  216. {
  217. state.status = AP_GPS::NO_FIX;
  218. }
  219. _new_position = true;
  220. }
  221. if (messageid == 99) // bestvel
  222. {
  223. const bestvel &bestvelu = nova_msg.data.bestvelu;
  224. state.ground_speed = (float) bestvelu.horspd;
  225. state.ground_course = (float) bestvelu.trkgnd;
  226. fill_3d_velocity();
  227. state.velocity.z = -(float) bestvelu.vertspd;
  228. state.have_vertical_velocity = true;
  229. _last_vel_time = (uint32_t) nova_msg.header.nova_headeru.tow;
  230. _new_speed = true;
  231. }
  232. if (messageid == 174) // psrdop
  233. {
  234. const psrdop &psrdopu = nova_msg.data.psrdopu;
  235. state.hdop = (uint16_t) (psrdopu.hdop*100);
  236. state.vdop = (uint16_t) (psrdopu.htdop*100);
  237. return false;
  238. }
  239. // ensure out position and velocity stay insync
  240. if (_new_position && _new_speed && _last_vel_time == state.time_week_ms) {
  241. _new_speed = _new_position = false;
  242. return true;
  243. }
  244. return false;
  245. }
  246. void
  247. AP_GPS_NOVA::inject_data(const uint8_t *data, uint16_t len)
  248. {
  249. if (port->txspace() > len) {
  250. last_injected_data_ms = AP_HAL::millis();
  251. port->write(data, len);
  252. } else {
  253. Debug("NOVA: Not enough TXSPACE");
  254. }
  255. }
  256. #define CRC32_POLYNOMIAL 0xEDB88320L
  257. uint32_t AP_GPS_NOVA::CRC32Value(uint32_t icrc)
  258. {
  259. int i;
  260. uint32_t crc = icrc;
  261. for ( i = 8 ; i > 0; i-- )
  262. {
  263. if ( crc & 1 )
  264. crc = ( crc >> 1 ) ^ CRC32_POLYNOMIAL;
  265. else
  266. crc >>= 1;
  267. }
  268. return crc;
  269. }
  270. uint32_t AP_GPS_NOVA::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc)
  271. {
  272. while ( length-- != 0 )
  273. {
  274. crc = ((crc >> 8) & 0x00FFFFFFL) ^ (CRC32Value(((uint32_t) crc ^ *buffer++) & 0xff));
  275. }
  276. return( crc );
  277. }