AP_GPS_UBLOX.cpp 50 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457
  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. //
  14. // u-blox GPS driver for ArduPilot
  15. // Origin code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
  16. // Substantially rewritten for new GPS driver structure by Andrew Tridgell
  17. //
  18. #include "AP_GPS.h"
  19. #include "AP_GPS_UBLOX.h"
  20. #include <AP_HAL/Util.h>
  21. #include <AP_Logger/AP_Logger.h>
  22. #include <GCS_MAVLink/GCS.h>
  23. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
  24. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
  25. #define UBLOX_SPEED_CHANGE 1
  26. #else
  27. #define UBLOX_SPEED_CHANGE 0
  28. #endif
  29. #define UBLOX_DEBUGGING 0
  30. #define UBLOX_FAKE_3DLOCK 0
  31. #define CONFIGURE_PPS_PIN 0
  32. extern const AP_HAL::HAL& hal;
  33. #ifdef HAL_NO_GCS
  34. #define GCS_SEND_TEXT(severity, format, args...)
  35. #else
  36. #define GCS_SEND_TEXT(severity, format, args...) gcs().send_text(severity, format, ##args)
  37. #endif
  38. #if UBLOX_DEBUGGING
  39. # define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
  40. #else
  41. # define Debug(fmt, args ...)
  42. #endif
  43. AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
  44. AP_GPS_Backend(_gps, _state, _port),
  45. _next_message(STEP_PVT),
  46. _ublox_port(255),
  47. _unconfigured_messages(CONFIG_ALL),
  48. _hardware_generation(UBLOX_UNKNOWN_HARDWARE_GENERATION),
  49. next_fix(AP_GPS::NO_FIX),
  50. noReceivedHdop(true)
  51. {
  52. // stop any config strings that are pending
  53. gps.send_blob_start(state.instance, nullptr, 0);
  54. // start the process of updating the GPS rates
  55. _request_next_config();
  56. #if CONFIGURE_PPS_PIN
  57. _unconfigured_messages |= CONFIG_TP5;
  58. #endif
  59. }
  60. void
  61. AP_GPS_UBLOX::_request_next_config(void)
  62. {
  63. // don't request config if we shouldn't configure the GPS
  64. if (gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE) {
  65. return;
  66. }
  67. // Ensure there is enough space for the largest possible outgoing message
  68. if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+sizeof(struct ubx_cfg_nav_rate)+2)) {
  69. // not enough space - do it next time
  70. return;
  71. }
  72. if (_unconfigured_messages == CONFIG_RATE_SOL && havePvtMsg) {
  73. /*
  74. we don't need SOL if we have PVT and TIMEGPS. This is needed
  75. as F9P doesn't support the SOL message
  76. */
  77. _unconfigured_messages &= ~CONFIG_RATE_SOL;
  78. }
  79. Debug("Unconfigured messages: 0x%x Current message: %u\n", (unsigned)_unconfigured_messages, (unsigned)_next_message);
  80. // check AP_GPS_UBLOX.h for the enum that controls the order.
  81. // This switch statement isn't maintained against the enum in order to reduce code churn
  82. switch (_next_message++) {
  83. case STEP_PVT:
  84. if(!_request_message_rate(CLASS_NAV, MSG_PVT)) {
  85. _next_message--;
  86. }
  87. break;
  88. case STEP_TIMEGPS:
  89. if(!_request_message_rate(CLASS_NAV, MSG_TIMEGPS)) {
  90. _next_message--;
  91. }
  92. break;
  93. case STEP_PORT:
  94. _request_port();
  95. break;
  96. case STEP_POLL_SVINFO:
  97. // not required once we know what generation we are on
  98. if(_hardware_generation == UBLOX_UNKNOWN_HARDWARE_GENERATION) {
  99. if (!_send_message(CLASS_NAV, MSG_NAV_SVINFO, 0, 0)) {
  100. _next_message--;
  101. }
  102. }
  103. break;
  104. case STEP_POLL_SBAS:
  105. if (gps._sbas_mode != 2) {
  106. _send_message(CLASS_CFG, MSG_CFG_SBAS, nullptr, 0);
  107. } else {
  108. _unconfigured_messages &= ~CONFIG_SBAS;
  109. }
  110. break;
  111. case STEP_POLL_NAV:
  112. if (!_send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS, nullptr, 0)) {
  113. _next_message--;
  114. }
  115. break;
  116. case STEP_POLL_GNSS:
  117. if (!_send_message(CLASS_CFG, MSG_CFG_GNSS, nullptr, 0)) {
  118. _next_message--;
  119. }
  120. break;
  121. case STEP_POLL_TP5:
  122. #if CONFIGURE_PPS_PIN
  123. if (!_send_message(CLASS_CFG, MSG_CFG_TP5, nullptr, 0)) {
  124. _next_message--;
  125. }
  126. #endif
  127. break;
  128. case STEP_NAV_RATE:
  129. if (!_send_message(CLASS_CFG, MSG_CFG_RATE, nullptr, 0)) {
  130. _next_message--;
  131. }
  132. break;
  133. case STEP_POSLLH:
  134. if(!_request_message_rate(CLASS_NAV, MSG_POSLLH)) {
  135. _next_message--;
  136. }
  137. break;
  138. case STEP_STATUS:
  139. if(!_request_message_rate(CLASS_NAV, MSG_STATUS)) {
  140. _next_message--;
  141. }
  142. break;
  143. case STEP_SOL:
  144. if(!_request_message_rate(CLASS_NAV, MSG_SOL)) {
  145. _next_message--;
  146. }
  147. break;
  148. case STEP_VELNED:
  149. if(!_request_message_rate(CLASS_NAV, MSG_VELNED)) {
  150. _next_message--;
  151. }
  152. break;
  153. case STEP_DOP:
  154. if(! _request_message_rate(CLASS_NAV, MSG_DOP)) {
  155. _next_message--;
  156. }
  157. break;
  158. case STEP_MON_HW:
  159. if(!_request_message_rate(CLASS_MON, MSG_MON_HW)) {
  160. _next_message--;
  161. }
  162. break;
  163. case STEP_MON_HW2:
  164. if(!_request_message_rate(CLASS_MON, MSG_MON_HW2)) {
  165. _next_message--;
  166. }
  167. break;
  168. case STEP_RAW:
  169. #if UBLOX_RXM_RAW_LOGGING
  170. if(gps._raw_data == 0) {
  171. _unconfigured_messages &= ~CONFIG_RATE_RAW;
  172. } else if(!_request_message_rate(CLASS_RXM, MSG_RXM_RAW)) {
  173. _next_message--;
  174. }
  175. #else
  176. _unconfigured_messages & = ~CONFIG_RATE_RAW;
  177. #endif
  178. break;
  179. case STEP_RAWX:
  180. #if UBLOX_RXM_RAW_LOGGING
  181. if(gps._raw_data == 0) {
  182. _unconfigured_messages &= ~CONFIG_RATE_RAW;
  183. } else if(!_request_message_rate(CLASS_RXM, MSG_RXM_RAWX)) {
  184. _next_message--;
  185. }
  186. #else
  187. _unconfigured_messages & = ~CONFIG_RATE_RAW;
  188. #endif
  189. break;
  190. case STEP_VERSION:
  191. if(!_have_version && !hal.util->get_soft_armed()) {
  192. _request_version();
  193. } else {
  194. _unconfigured_messages &= ~CONFIG_VERSION;
  195. }
  196. // no need to send the initial rates, move to checking only
  197. _next_message = STEP_PVT;
  198. break;
  199. default:
  200. // this case should never be reached, do a full reset if it is hit
  201. _next_message = STEP_PVT;
  202. break;
  203. }
  204. }
  205. void
  206. AP_GPS_UBLOX::_verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate) {
  207. uint8_t desired_rate;
  208. switch(msg_class) {
  209. case CLASS_NAV:
  210. switch(msg_id) {
  211. case MSG_POSLLH:
  212. desired_rate = havePvtMsg ? 0 : RATE_POSLLH;
  213. if(rate == desired_rate) {
  214. _unconfigured_messages &= ~CONFIG_RATE_POSLLH;
  215. } else {
  216. _configure_message_rate(msg_class, msg_id, desired_rate);
  217. _unconfigured_messages |= CONFIG_RATE_POSLLH;
  218. _cfg_needs_save = true;
  219. }
  220. break;
  221. case MSG_STATUS:
  222. desired_rate = havePvtMsg ? 0 : RATE_STATUS;
  223. if(rate == desired_rate) {
  224. _unconfigured_messages &= ~CONFIG_RATE_STATUS;
  225. } else {
  226. _configure_message_rate(msg_class, msg_id, desired_rate);
  227. _unconfigured_messages |= CONFIG_RATE_STATUS;
  228. _cfg_needs_save = true;
  229. }
  230. break;
  231. case MSG_SOL:
  232. desired_rate = havePvtMsg ? 0 : RATE_SOL;
  233. if(rate == desired_rate) {
  234. _unconfigured_messages &= ~CONFIG_RATE_SOL;
  235. } else {
  236. _configure_message_rate(msg_class, msg_id, desired_rate);
  237. _unconfigured_messages |= CONFIG_RATE_SOL;
  238. _cfg_needs_save = true;
  239. }
  240. break;
  241. case MSG_PVT:
  242. if(rate == RATE_PVT) {
  243. _unconfigured_messages &= ~CONFIG_RATE_PVT;
  244. } else {
  245. _configure_message_rate(msg_class, msg_id, RATE_PVT);
  246. _unconfigured_messages |= CONFIG_RATE_PVT;
  247. _cfg_needs_save = true;
  248. }
  249. break;
  250. case MSG_TIMEGPS:
  251. if(rate == RATE_TIMEGPS) {
  252. _unconfigured_messages &= ~CONFIG_RATE_TIMEGPS;
  253. } else {
  254. _configure_message_rate(msg_class, msg_id, RATE_TIMEGPS);
  255. _unconfigured_messages |= CONFIG_RATE_TIMEGPS;
  256. _cfg_needs_save = true;
  257. }
  258. break;
  259. case MSG_VELNED:
  260. desired_rate = havePvtMsg ? 0 : RATE_VELNED;
  261. if(rate == desired_rate) {
  262. _unconfigured_messages &= ~CONFIG_RATE_VELNED;
  263. } else {
  264. _configure_message_rate(msg_class, msg_id, desired_rate);
  265. _unconfigured_messages |= CONFIG_RATE_VELNED;
  266. _cfg_needs_save = true;
  267. }
  268. break;
  269. case MSG_DOP:
  270. if(rate == RATE_DOP) {
  271. _unconfigured_messages &= ~CONFIG_RATE_DOP;
  272. } else {
  273. _configure_message_rate(msg_class, msg_id, RATE_DOP);
  274. _unconfigured_messages |= CONFIG_RATE_DOP;
  275. _cfg_needs_save = true;
  276. }
  277. break;
  278. }
  279. break;
  280. case CLASS_MON:
  281. switch(msg_id) {
  282. case MSG_MON_HW:
  283. if(rate == RATE_HW) {
  284. _unconfigured_messages &= ~CONFIG_RATE_MON_HW;
  285. } else {
  286. _configure_message_rate(msg_class, msg_id, RATE_HW);
  287. _unconfigured_messages |= CONFIG_RATE_MON_HW;
  288. _cfg_needs_save = true;
  289. }
  290. break;
  291. case MSG_MON_HW2:
  292. if(rate == RATE_HW2) {
  293. _unconfigured_messages &= ~CONFIG_RATE_MON_HW2;
  294. } else {
  295. _configure_message_rate(msg_class, msg_id, RATE_HW2);
  296. _unconfigured_messages |= CONFIG_RATE_MON_HW2;
  297. _cfg_needs_save = true;
  298. }
  299. break;
  300. }
  301. break;
  302. #if UBLOX_RXM_RAW_LOGGING
  303. case CLASS_RXM:
  304. switch(msg_id) {
  305. case MSG_RXM_RAW:
  306. if(rate == gps._raw_data) {
  307. _unconfigured_messages &= ~CONFIG_RATE_RAW;
  308. } else {
  309. _configure_message_rate(msg_class, msg_id, gps._raw_data);
  310. _unconfigured_messages |= CONFIG_RATE_RAW;
  311. _cfg_needs_save = true;
  312. }
  313. break;
  314. case MSG_RXM_RAWX:
  315. if(rate == gps._raw_data) {
  316. _unconfigured_messages &= ~CONFIG_RATE_RAW;
  317. } else {
  318. _configure_message_rate(msg_class, msg_id, gps._raw_data);
  319. _unconfigured_messages |= CONFIG_RATE_RAW;
  320. _cfg_needs_save = true;
  321. }
  322. break;
  323. }
  324. break;
  325. #endif // UBLOX_RXM_RAW_LOGGING
  326. }
  327. }
  328. // Requests the ublox driver to identify what port we are using to communicate
  329. void
  330. AP_GPS_UBLOX::_request_port(void)
  331. {
  332. if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+2)) {
  333. // not enough space - do it next time
  334. return;
  335. }
  336. _send_message(CLASS_CFG, MSG_CFG_PRT, nullptr, 0);
  337. }
  338. // Ensure there is enough space for the largest possible outgoing message
  339. // Process bytes available from the stream
  340. //
  341. // The stream is assumed to contain only messages we recognise. If it
  342. // contains other messages, and those messages contain the preamble
  343. // bytes, it is possible for this code to fail to synchronise to the
  344. // stream immediately. Without buffering the entire message and
  345. // re-processing it from the top, this is unavoidable. The parser
  346. // attempts to avoid this when possible.
  347. //
  348. bool
  349. AP_GPS_UBLOX::read(void)
  350. {
  351. uint8_t data;
  352. int16_t numc;
  353. bool parsed = false;
  354. uint32_t millis_now = AP_HAL::millis();
  355. // walk through the gps configuration at 1 message per second
  356. if (millis_now - _last_config_time >= _delay_time) {
  357. _request_next_config();
  358. _last_config_time = millis_now;
  359. if (_unconfigured_messages) { // send the updates faster until fully configured
  360. if (!havePvtMsg && (_unconfigured_messages & CONFIG_REQUIRED_INITIAL)) {
  361. _delay_time = 300;
  362. } else {
  363. _delay_time = 750;
  364. }
  365. } else {
  366. _delay_time = 2000;
  367. }
  368. }
  369. if(!_unconfigured_messages && gps._save_config && !_cfg_saved &&
  370. _num_cfg_save_tries < 5 && (millis_now - _last_cfg_sent_time) > 5000 &&
  371. !hal.util->get_soft_armed()) {
  372. //save the configuration sent until now
  373. if (gps._save_config == 1 ||
  374. (gps._save_config == 2 && _cfg_needs_save)) {
  375. _save_cfg();
  376. }
  377. }
  378. numc = port->available();
  379. for (int16_t i = 0; i < numc; i++) { // Process bytes received
  380. // read the next byte
  381. data = port->read();
  382. reset:
  383. switch(_step) {
  384. // Message preamble detection
  385. //
  386. // If we fail to match any of the expected bytes, we reset
  387. // the state machine and re-consider the failed byte as
  388. // the first byte of the preamble. This improves our
  389. // chances of recovering from a mismatch and makes it less
  390. // likely that we will be fooled by the preamble appearing
  391. // as data in some other message.
  392. //
  393. case 1:
  394. if (PREAMBLE2 == data) {
  395. _step++;
  396. break;
  397. }
  398. _step = 0;
  399. Debug("reset %u", __LINE__);
  400. FALLTHROUGH;
  401. case 0:
  402. if(PREAMBLE1 == data)
  403. _step++;
  404. break;
  405. // Message header processing
  406. //
  407. // We sniff the class and message ID to decide whether we
  408. // are going to gather the message bytes or just discard
  409. // them.
  410. //
  411. // We always collect the length so that we can avoid being
  412. // fooled by preamble bytes in messages.
  413. //
  414. case 2:
  415. _step++;
  416. _class = data;
  417. _ck_b = _ck_a = data; // reset the checksum accumulators
  418. break;
  419. case 3:
  420. _step++;
  421. _ck_b += (_ck_a += data); // checksum byte
  422. _msg_id = data;
  423. break;
  424. case 4:
  425. _step++;
  426. _ck_b += (_ck_a += data); // checksum byte
  427. _payload_length = data; // payload length low byte
  428. break;
  429. case 5:
  430. _step++;
  431. _ck_b += (_ck_a += data); // checksum byte
  432. _payload_length += (uint16_t)(data<<8);
  433. if (_payload_length > sizeof(_buffer)) {
  434. Debug("large payload %u", (unsigned)_payload_length);
  435. // assume any payload bigger then what we know about is noise
  436. _payload_length = 0;
  437. _step = 0;
  438. goto reset;
  439. }
  440. _payload_counter = 0; // prepare to receive payload
  441. if (_payload_length == 0) {
  442. // bypass payload and go straight to checksum
  443. _step++;
  444. }
  445. break;
  446. // Receive message data
  447. //
  448. case 6:
  449. _ck_b += (_ck_a += data); // checksum byte
  450. if (_payload_counter < sizeof(_buffer)) {
  451. _buffer[_payload_counter] = data;
  452. }
  453. if (++_payload_counter == _payload_length)
  454. _step++;
  455. break;
  456. // Checksum and message processing
  457. //
  458. case 7:
  459. _step++;
  460. if (_ck_a != data) {
  461. Debug("bad cka %x should be %x", data, _ck_a);
  462. _step = 0;
  463. goto reset;
  464. }
  465. break;
  466. case 8:
  467. _step = 0;
  468. if (_ck_b != data) {
  469. Debug("bad ckb %x should be %x", data, _ck_b);
  470. break; // bad checksum
  471. }
  472. if (_parse_gps()) {
  473. parsed = true;
  474. }
  475. break;
  476. }
  477. }
  478. return parsed;
  479. }
  480. // Private Methods /////////////////////////////////////////////////////////////
  481. void AP_GPS_UBLOX::log_mon_hw(void)
  482. {
  483. #ifndef HAL_NO_LOGGING
  484. if (!should_log()) {
  485. return;
  486. }
  487. struct log_Ubx1 pkt = {
  488. LOG_PACKET_HEADER_INIT(_ubx_msg_log_index(LOG_GPS_UBX1_MSG)),
  489. time_us : AP_HAL::micros64(),
  490. instance : state.instance,
  491. noisePerMS : _buffer.mon_hw_60.noisePerMS,
  492. jamInd : _buffer.mon_hw_60.jamInd,
  493. aPower : _buffer.mon_hw_60.aPower,
  494. agcCnt : _buffer.mon_hw_60.agcCnt,
  495. config : _unconfigured_messages,
  496. };
  497. if (_payload_length == 68) {
  498. pkt.noisePerMS = _buffer.mon_hw_68.noisePerMS;
  499. pkt.jamInd = _buffer.mon_hw_68.jamInd;
  500. pkt.aPower = _buffer.mon_hw_68.aPower;
  501. pkt.agcCnt = _buffer.mon_hw_68.agcCnt;
  502. }
  503. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  504. #endif
  505. }
  506. void AP_GPS_UBLOX::log_mon_hw2(void)
  507. {
  508. #ifndef HAL_NO_LOGGING
  509. if (!should_log()) {
  510. return;
  511. }
  512. struct log_Ubx2 pkt = {
  513. LOG_PACKET_HEADER_INIT(_ubx_msg_log_index(LOG_GPS_UBX2_MSG)),
  514. time_us : AP_HAL::micros64(),
  515. instance : state.instance,
  516. ofsI : _buffer.mon_hw2.ofsI,
  517. magI : _buffer.mon_hw2.magI,
  518. ofsQ : _buffer.mon_hw2.ofsQ,
  519. magQ : _buffer.mon_hw2.magQ,
  520. };
  521. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  522. #endif
  523. }
  524. #if UBLOX_RXM_RAW_LOGGING
  525. void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw)
  526. {
  527. #ifndef HAL_NO_LOGGING
  528. if (!should_log()) {
  529. return;
  530. }
  531. uint64_t now = AP_HAL::micros64();
  532. for (uint8_t i=0; i<raw.numSV; i++) {
  533. struct log_GPS_RAW pkt = {
  534. LOG_PACKET_HEADER_INIT(LOG_GPS_RAW_MSG),
  535. time_us : now,
  536. iTOW : raw.iTOW,
  537. week : raw.week,
  538. numSV : raw.numSV,
  539. sv : raw.svinfo[i].sv,
  540. cpMes : raw.svinfo[i].cpMes,
  541. prMes : raw.svinfo[i].prMes,
  542. doMes : raw.svinfo[i].doMes,
  543. mesQI : raw.svinfo[i].mesQI,
  544. cno : raw.svinfo[i].cno,
  545. lli : raw.svinfo[i].lli
  546. };
  547. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  548. }
  549. #endif
  550. }
  551. void AP_GPS_UBLOX::log_rxm_rawx(const struct ubx_rxm_rawx &raw)
  552. {
  553. #ifndef HAL_NO_LOGGING
  554. if (!should_log()) {
  555. return;
  556. }
  557. uint64_t now = AP_HAL::micros64();
  558. struct log_GPS_RAWH header = {
  559. LOG_PACKET_HEADER_INIT(LOG_GPS_RAWH_MSG),
  560. time_us : now,
  561. rcvTow : raw.rcvTow,
  562. week : raw.week,
  563. leapS : raw.leapS,
  564. numMeas : raw.numMeas,
  565. recStat : raw.recStat
  566. };
  567. AP::logger().WriteBlock(&header, sizeof(header));
  568. for (uint8_t i=0; i<raw.numMeas; i++) {
  569. struct log_GPS_RAWS pkt = {
  570. LOG_PACKET_HEADER_INIT(LOG_GPS_RAWS_MSG),
  571. time_us : now,
  572. prMes : raw.svinfo[i].prMes,
  573. cpMes : raw.svinfo[i].cpMes,
  574. doMes : raw.svinfo[i].doMes,
  575. gnssId : raw.svinfo[i].gnssId,
  576. svId : raw.svinfo[i].svId,
  577. freqId : raw.svinfo[i].freqId,
  578. locktime : raw.svinfo[i].locktime,
  579. cno : raw.svinfo[i].cno,
  580. prStdev : raw.svinfo[i].prStdev,
  581. cpStdev : raw.svinfo[i].cpStdev,
  582. doStdev : raw.svinfo[i].doStdev,
  583. trkStat : raw.svinfo[i].trkStat
  584. };
  585. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  586. }
  587. #endif
  588. }
  589. #endif // UBLOX_RXM_RAW_LOGGING
  590. void AP_GPS_UBLOX::unexpected_message(void)
  591. {
  592. Debug("Unexpected message 0x%02x 0x%02x", (unsigned)_class, (unsigned)_msg_id);
  593. if (++_disable_counter == 0) {
  594. // disable future sends of this message id, but
  595. // only do this every 256 messages, as some
  596. // message types can't be disabled and we don't
  597. // want to get into an ack war
  598. Debug("Disabling message 0x%02x 0x%02x", (unsigned)_class, (unsigned)_msg_id);
  599. _configure_message_rate(_class, _msg_id, 0);
  600. }
  601. }
  602. bool
  603. AP_GPS_UBLOX::_parse_gps(void)
  604. {
  605. if (_class == CLASS_ACK) {
  606. Debug("ACK %u", (unsigned)_msg_id);
  607. if(_msg_id == MSG_ACK_ACK) {
  608. switch(_buffer.ack.clsID) {
  609. case CLASS_CFG:
  610. switch(_buffer.ack.msgID) {
  611. case MSG_CFG_CFG:
  612. _cfg_saved = true;
  613. _cfg_needs_save = false;
  614. break;
  615. case MSG_CFG_GNSS:
  616. _unconfigured_messages &= ~CONFIG_GNSS;
  617. break;
  618. case MSG_CFG_MSG:
  619. // There is no way to know what MSG config was ack'ed, assume it was the last
  620. // one requested. To verify it rerequest the last config we sent. If we miss
  621. // the actual ack we will catch it next time through the poll loop, but that
  622. // will be a good chunk of time later.
  623. break;
  624. case MSG_CFG_NAV_SETTINGS:
  625. _unconfigured_messages &= ~CONFIG_NAV_SETTINGS;
  626. break;
  627. case MSG_CFG_RATE:
  628. // The GPS will ACK a update rate that is invalid. in order to detect this
  629. // only accept the rate as configured by reading the settings back and
  630. // validating that they all match the target values
  631. break;
  632. case MSG_CFG_SBAS:
  633. _unconfigured_messages &= ~CONFIG_SBAS;
  634. break;
  635. case MSG_CFG_TP5:
  636. _unconfigured_messages &= ~CONFIG_TP5;
  637. break;
  638. }
  639. break;
  640. case CLASS_MON:
  641. switch(_buffer.ack.msgID) {
  642. case MSG_MON_HW:
  643. _unconfigured_messages &= ~CONFIG_RATE_MON_HW;
  644. break;
  645. case MSG_MON_HW2:
  646. _unconfigured_messages &= ~CONFIG_RATE_MON_HW2;
  647. break;
  648. }
  649. }
  650. }
  651. return false;
  652. }
  653. if (_class == CLASS_CFG) {
  654. switch(_msg_id) {
  655. case MSG_CFG_NAV_SETTINGS:
  656. Debug("Got settings %u min_elev %d drLimit %u\n",
  657. (unsigned)_buffer.nav_settings.dynModel,
  658. (int)_buffer.nav_settings.minElev,
  659. (unsigned)_buffer.nav_settings.drLimit);
  660. _buffer.nav_settings.mask = 0;
  661. if (gps._navfilter != AP_GPS::GPS_ENGINE_NONE &&
  662. _buffer.nav_settings.dynModel != gps._navfilter) {
  663. // we've received the current nav settings, change the engine
  664. // settings and send them back
  665. Debug("Changing engine setting from %u to %u\n",
  666. (unsigned)_buffer.nav_settings.dynModel, (unsigned)gps._navfilter);
  667. _buffer.nav_settings.dynModel = gps._navfilter;
  668. _buffer.nav_settings.mask |= 1;
  669. }
  670. if (gps._min_elevation != -100 &&
  671. _buffer.nav_settings.minElev != gps._min_elevation) {
  672. Debug("Changing min elevation to %d\n", (int)gps._min_elevation);
  673. _buffer.nav_settings.minElev = gps._min_elevation;
  674. _buffer.nav_settings.mask |= 2;
  675. }
  676. if (_buffer.nav_settings.mask != 0) {
  677. _send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS,
  678. &_buffer.nav_settings,
  679. sizeof(_buffer.nav_settings));
  680. _unconfigured_messages |= CONFIG_NAV_SETTINGS;
  681. _cfg_needs_save = true;
  682. } else {
  683. _unconfigured_messages &= ~CONFIG_NAV_SETTINGS;
  684. }
  685. return false;
  686. #if UBLOX_GNSS_SETTINGS
  687. case MSG_CFG_GNSS:
  688. if (gps._gnss_mode[state.instance] != 0) {
  689. struct ubx_cfg_gnss start_gnss = _buffer.gnss;
  690. uint8_t gnssCount = 0;
  691. Debug("Got GNSS Settings %u %u %u %u:\n",
  692. (unsigned)_buffer.gnss.msgVer,
  693. (unsigned)_buffer.gnss.numTrkChHw,
  694. (unsigned)_buffer.gnss.numTrkChUse,
  695. (unsigned)_buffer.gnss.numConfigBlocks);
  696. #if UBLOX_DEBUGGING
  697. for(int i = 0; i < _buffer.gnss.numConfigBlocks; i++) {
  698. Debug(" %u %u %u 0x%08x\n",
  699. (unsigned)_buffer.gnss.configBlock[i].gnssId,
  700. (unsigned)_buffer.gnss.configBlock[i].resTrkCh,
  701. (unsigned)_buffer.gnss.configBlock[i].maxTrkCh,
  702. (unsigned)_buffer.gnss.configBlock[i].flags);
  703. }
  704. #endif
  705. for(int i = 0; i < UBLOX_MAX_GNSS_CONFIG_BLOCKS; i++) {
  706. if((gps._gnss_mode[state.instance] & (1 << i)) && i != GNSS_SBAS) {
  707. gnssCount++;
  708. }
  709. }
  710. for(int i = 0; i < _buffer.gnss.numConfigBlocks; i++) {
  711. // Reserve an equal portion of channels for all enabled systems
  712. if(gps._gnss_mode[state.instance] & (1 << _buffer.gnss.configBlock[i].gnssId)) {
  713. if(GNSS_SBAS !=_buffer.gnss.configBlock[i].gnssId) {
  714. _buffer.gnss.configBlock[i].resTrkCh = (_buffer.gnss.numTrkChHw - 3) / (gnssCount * 2);
  715. _buffer.gnss.configBlock[i].maxTrkCh = _buffer.gnss.numTrkChHw;
  716. } else {
  717. _buffer.gnss.configBlock[i].resTrkCh = 1;
  718. _buffer.gnss.configBlock[i].maxTrkCh = 3;
  719. }
  720. _buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags | 0x00000001;
  721. } else {
  722. _buffer.gnss.configBlock[i].resTrkCh = 0;
  723. _buffer.gnss.configBlock[i].maxTrkCh = 0;
  724. _buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags & 0xFFFFFFFE;
  725. }
  726. }
  727. if (memcmp(&start_gnss, &_buffer.gnss, sizeof(start_gnss))) {
  728. _send_message(CLASS_CFG, MSG_CFG_GNSS, &_buffer.gnss, 4 + (8 * _buffer.gnss.numConfigBlocks));
  729. _unconfigured_messages |= CONFIG_GNSS;
  730. _cfg_needs_save = true;
  731. } else {
  732. _unconfigured_messages &= ~CONFIG_GNSS;
  733. }
  734. } else {
  735. _unconfigured_messages &= ~CONFIG_GNSS;
  736. }
  737. return false;
  738. #endif
  739. case MSG_CFG_SBAS:
  740. if (gps._sbas_mode != 2) {
  741. Debug("Got SBAS settings %u %u %u 0x%x 0x%x\n",
  742. (unsigned)_buffer.sbas.mode,
  743. (unsigned)_buffer.sbas.usage,
  744. (unsigned)_buffer.sbas.maxSBAS,
  745. (unsigned)_buffer.sbas.scanmode2,
  746. (unsigned)_buffer.sbas.scanmode1);
  747. if (_buffer.sbas.mode != gps._sbas_mode) {
  748. _buffer.sbas.mode = gps._sbas_mode;
  749. _send_message(CLASS_CFG, MSG_CFG_SBAS,
  750. &_buffer.sbas,
  751. sizeof(_buffer.sbas));
  752. _unconfigured_messages |= CONFIG_SBAS;
  753. _cfg_needs_save = true;
  754. } else {
  755. _unconfigured_messages &= ~CONFIG_SBAS;
  756. }
  757. } else {
  758. _unconfigured_messages &= ~CONFIG_SBAS;
  759. }
  760. return false;
  761. case MSG_CFG_MSG:
  762. if(_payload_length == sizeof(ubx_cfg_msg_rate_6)) {
  763. // can't verify the setting without knowing the port
  764. // request the port again
  765. if(_ublox_port >= UBLOX_MAX_PORTS) {
  766. _request_port();
  767. return false;
  768. }
  769. _verify_rate(_buffer.msg_rate_6.msg_class, _buffer.msg_rate_6.msg_id,
  770. _buffer.msg_rate_6.rates[_ublox_port]);
  771. } else {
  772. _verify_rate(_buffer.msg_rate.msg_class, _buffer.msg_rate.msg_id,
  773. _buffer.msg_rate.rate);
  774. }
  775. return false;
  776. case MSG_CFG_PRT:
  777. _ublox_port = _buffer.prt.portID;
  778. return false;
  779. case MSG_CFG_RATE:
  780. if(_buffer.nav_rate.measure_rate_ms != gps._rate_ms[state.instance] ||
  781. _buffer.nav_rate.nav_rate != 1 ||
  782. _buffer.nav_rate.timeref != 0) {
  783. _configure_rate();
  784. _unconfigured_messages |= CONFIG_RATE_NAV;
  785. _cfg_needs_save = true;
  786. } else {
  787. _unconfigured_messages &= ~CONFIG_RATE_NAV;
  788. }
  789. return false;
  790. #if CONFIGURE_PPS_PIN
  791. case MSG_CFG_TP5: {
  792. // configure the PPS pin for 1Hz, zero delay
  793. Debug("Got TP5 ver=%u 0x%04x %u\n",
  794. (unsigned)_buffer.nav_tp5.version,
  795. (unsigned)_buffer.nav_tp5.flags,
  796. (unsigned)_buffer.nav_tp5.freqPeriod);
  797. const uint16_t desired_flags = 0x003f;
  798. const uint16_t desired_period_hz = 1;
  799. if (_buffer.nav_tp5.flags != desired_flags ||
  800. _buffer.nav_tp5.freqPeriod != desired_period_hz) {
  801. _buffer.nav_tp5.tpIdx = 0;
  802. _buffer.nav_tp5.reserved1[0] = 0;
  803. _buffer.nav_tp5.reserved1[1] = 0;
  804. _buffer.nav_tp5.antCableDelay = 0;
  805. _buffer.nav_tp5.rfGroupDelay = 0;
  806. _buffer.nav_tp5.freqPeriod = desired_period_hz;
  807. _buffer.nav_tp5.freqPeriodLock = desired_period_hz;
  808. _buffer.nav_tp5.pulseLenRatio = 1;
  809. _buffer.nav_tp5.pulseLenRatioLock = 2;
  810. _buffer.nav_tp5.userConfigDelay = 0;
  811. _buffer.nav_tp5.flags = desired_flags;
  812. _send_message(CLASS_CFG, MSG_CFG_TP5,
  813. &_buffer.nav_tp5,
  814. sizeof(_buffer.nav_tp5));
  815. _unconfigured_messages |= CONFIG_TP5;
  816. _cfg_needs_save = true;
  817. } else {
  818. _unconfigured_messages &= ~CONFIG_TP5;
  819. }
  820. return false;
  821. }
  822. #endif // CONFIGURE_PPS_PIN
  823. }
  824. }
  825. if (_class == CLASS_MON) {
  826. switch(_msg_id) {
  827. case MSG_MON_HW:
  828. if (_payload_length == 60 || _payload_length == 68) {
  829. log_mon_hw();
  830. }
  831. break;
  832. case MSG_MON_HW2:
  833. if (_payload_length == 28) {
  834. log_mon_hw2();
  835. }
  836. break;
  837. case MSG_MON_VER:
  838. _have_version = true;
  839. strncpy(_version.hwVersion, _buffer.mon_ver.hwVersion, sizeof(_version.hwVersion));
  840. strncpy(_version.swVersion, _buffer.mon_ver.swVersion, sizeof(_version.swVersion));
  841. GCS_SEND_TEXT(MAV_SEVERITY_INFO,
  842. "u-blox %d HW: %s SW: %s",
  843. state.instance + 1,
  844. _version.hwVersion,
  845. _version.swVersion);
  846. // check for F9. The F9 does not respond to SVINFO, so we need to use MON_VER
  847. // for hardware generation
  848. if (strncmp(_version.hwVersion, "00190000", 8) == 0) {
  849. _hardware_generation = UBLOX_F9;
  850. }
  851. break;
  852. default:
  853. unexpected_message();
  854. }
  855. return false;
  856. }
  857. #if UBLOX_RXM_RAW_LOGGING
  858. if (_class == CLASS_RXM && _msg_id == MSG_RXM_RAW && gps._raw_data != 0) {
  859. log_rxm_raw(_buffer.rxm_raw);
  860. return false;
  861. } else if (_class == CLASS_RXM && _msg_id == MSG_RXM_RAWX && gps._raw_data != 0) {
  862. log_rxm_rawx(_buffer.rxm_rawx);
  863. return false;
  864. }
  865. #endif // UBLOX_RXM_RAW_LOGGING
  866. if (_class != CLASS_NAV) {
  867. unexpected_message();
  868. return false;
  869. }
  870. switch (_msg_id) {
  871. case MSG_POSLLH:
  872. Debug("MSG_POSLLH next_fix=%u", next_fix);
  873. if (havePvtMsg) {
  874. _unconfigured_messages |= CONFIG_RATE_POSLLH;
  875. break;
  876. }
  877. _check_new_itow(_buffer.posllh.itow);
  878. _last_pos_time = _buffer.posllh.itow;
  879. state.location.lng = _buffer.posllh.longitude;
  880. state.location.lat = _buffer.posllh.latitude;
  881. state.location.alt = _buffer.posllh.altitude_msl / 10;
  882. state.status = next_fix;
  883. _new_position = true;
  884. state.horizontal_accuracy = _buffer.posllh.horizontal_accuracy*1.0e-3f;
  885. state.vertical_accuracy = _buffer.posllh.vertical_accuracy*1.0e-3f;
  886. state.have_horizontal_accuracy = true;
  887. state.have_vertical_accuracy = true;
  888. #if UBLOX_FAKE_3DLOCK
  889. state.location.lng = 1491652300L;
  890. state.location.lat = -353632610L;
  891. state.location.alt = 58400;
  892. state.vertical_accuracy = 0;
  893. state.horizontal_accuracy = 0;
  894. #endif
  895. break;
  896. case MSG_STATUS:
  897. Debug("MSG_STATUS fix_status=%u fix_type=%u",
  898. _buffer.status.fix_status,
  899. _buffer.status.fix_type);
  900. _check_new_itow(_buffer.status.itow);
  901. if (havePvtMsg) {
  902. _unconfigured_messages |= CONFIG_RATE_STATUS;
  903. break;
  904. }
  905. if (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) {
  906. if( (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) &&
  907. (_buffer.status.fix_status & AP_GPS_UBLOX::NAV_STATUS_DGPS_USED)) {
  908. next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS;
  909. }else if( _buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) {
  910. next_fix = AP_GPS::GPS_OK_FIX_3D;
  911. }else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) {
  912. next_fix = AP_GPS::GPS_OK_FIX_2D;
  913. }else{
  914. next_fix = AP_GPS::NO_FIX;
  915. state.status = AP_GPS::NO_FIX;
  916. }
  917. }else{
  918. next_fix = AP_GPS::NO_FIX;
  919. state.status = AP_GPS::NO_FIX;
  920. }
  921. #if UBLOX_FAKE_3DLOCK
  922. state.status = AP_GPS::GPS_OK_FIX_3D;
  923. next_fix = state.status;
  924. #endif
  925. break;
  926. case MSG_DOP:
  927. Debug("MSG_DOP");
  928. noReceivedHdop = false;
  929. _check_new_itow(_buffer.dop.itow);
  930. state.hdop = _buffer.dop.hDOP;
  931. state.vdop = _buffer.dop.vDOP;
  932. #if UBLOX_FAKE_3DLOCK
  933. state.hdop = 130;
  934. state.hdop = 170;
  935. #endif
  936. break;
  937. case MSG_SOL:
  938. Debug("MSG_SOL fix_status=%u fix_type=%u",
  939. _buffer.solution.fix_status,
  940. _buffer.solution.fix_type);
  941. _check_new_itow(_buffer.solution.itow);
  942. if (havePvtMsg) {
  943. state.time_week = _buffer.solution.week;
  944. break;
  945. }
  946. if (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) {
  947. if( (_buffer.solution.fix_type == AP_GPS_UBLOX::FIX_3D) &&
  948. (_buffer.solution.fix_status & AP_GPS_UBLOX::NAV_STATUS_DGPS_USED)) {
  949. next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS;
  950. }else if( _buffer.solution.fix_type == AP_GPS_UBLOX::FIX_3D) {
  951. next_fix = AP_GPS::GPS_OK_FIX_3D;
  952. }else if (_buffer.solution.fix_type == AP_GPS_UBLOX::FIX_2D) {
  953. next_fix = AP_GPS::GPS_OK_FIX_2D;
  954. }else{
  955. next_fix = AP_GPS::NO_FIX;
  956. state.status = AP_GPS::NO_FIX;
  957. }
  958. }else{
  959. next_fix = AP_GPS::NO_FIX;
  960. state.status = AP_GPS::NO_FIX;
  961. }
  962. if(noReceivedHdop) {
  963. state.hdop = _buffer.solution.position_DOP;
  964. }
  965. state.num_sats = _buffer.solution.satellites;
  966. if (next_fix >= AP_GPS::GPS_OK_FIX_2D) {
  967. state.last_gps_time_ms = AP_HAL::millis();
  968. state.time_week_ms = _buffer.solution.itow;
  969. state.time_week = _buffer.solution.week;
  970. }
  971. #if UBLOX_FAKE_3DLOCK
  972. next_fix = state.status;
  973. state.num_sats = 10;
  974. state.time_week = 1721;
  975. state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
  976. state.last_gps_time_ms = AP_HAL::millis();
  977. state.hdop = 130;
  978. #endif
  979. break;
  980. case MSG_PVT:
  981. Debug("MSG_PVT");
  982. havePvtMsg = true;
  983. // position
  984. _check_new_itow(_buffer.pvt.itow);
  985. _last_pos_time = _buffer.pvt.itow;
  986. state.location.lng = _buffer.pvt.lon;
  987. state.location.lat = _buffer.pvt.lat;
  988. state.location.alt = _buffer.pvt.h_msl / 10;
  989. switch (_buffer.pvt.fix_type)
  990. {
  991. case 0:
  992. state.status = AP_GPS::NO_FIX;
  993. break;
  994. case 1:
  995. state.status = AP_GPS::NO_FIX;
  996. break;
  997. case 2:
  998. state.status = AP_GPS::GPS_OK_FIX_2D;
  999. break;
  1000. case 3:
  1001. state.status = AP_GPS::GPS_OK_FIX_3D;
  1002. if (_buffer.pvt.flags & 0b00000010) // diffsoln
  1003. state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
  1004. if (_buffer.pvt.flags & 0b01000000) // carrsoln - float
  1005. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
  1006. if (_buffer.pvt.flags & 0b10000000) // carrsoln - fixed
  1007. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
  1008. break;
  1009. case 4:
  1010. GCS_SEND_TEXT(MAV_SEVERITY_INFO,
  1011. "Unexpected state %d", _buffer.pvt.flags);
  1012. state.status = AP_GPS::GPS_OK_FIX_3D;
  1013. break;
  1014. case 5:
  1015. state.status = AP_GPS::NO_FIX;
  1016. break;
  1017. default:
  1018. state.status = AP_GPS::NO_FIX;
  1019. break;
  1020. }
  1021. next_fix = state.status;
  1022. _new_position = true;
  1023. state.horizontal_accuracy = _buffer.pvt.h_acc*1.0e-3f;
  1024. state.vertical_accuracy = _buffer.pvt.v_acc*1.0e-3f;
  1025. state.have_horizontal_accuracy = true;
  1026. state.have_vertical_accuracy = true;
  1027. // SVs
  1028. state.num_sats = _buffer.pvt.num_sv;
  1029. // velocity
  1030. _last_vel_time = _buffer.pvt.itow;
  1031. state.ground_speed = _buffer.pvt.gspeed*0.001f; // m/s
  1032. state.ground_course = wrap_360(_buffer.pvt.head_mot * 1.0e-5f); // Heading 2D deg * 100000
  1033. state.have_vertical_velocity = true;
  1034. state.velocity.x = _buffer.pvt.velN * 0.001f;
  1035. state.velocity.y = _buffer.pvt.velE * 0.001f;
  1036. state.velocity.z = _buffer.pvt.velD * 0.001f;
  1037. state.have_speed_accuracy = true;
  1038. state.speed_accuracy = _buffer.pvt.s_acc*0.001f;
  1039. _new_speed = true;
  1040. // dop
  1041. if(noReceivedHdop) {
  1042. state.hdop = _buffer.pvt.p_dop;
  1043. state.vdop = _buffer.pvt.p_dop;
  1044. }
  1045. state.last_gps_time_ms = AP_HAL::millis();
  1046. // time
  1047. state.time_week_ms = _buffer.pvt.itow;
  1048. #if UBLOX_FAKE_3DLOCK
  1049. state.location.lng = 1491652300L;
  1050. state.location.lat = -353632610L;
  1051. state.location.alt = 58400;
  1052. state.vertical_accuracy = 0;
  1053. state.horizontal_accuracy = 0;
  1054. state.status = AP_GPS::GPS_OK_FIX_3D;
  1055. state.num_sats = 10;
  1056. state.time_week = 1721;
  1057. state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
  1058. state.last_gps_time_ms = AP_HAL::millis();
  1059. state.hdop = 130;
  1060. state.speed_accuracy = 0;
  1061. next_fix = state.status;
  1062. #endif
  1063. break;
  1064. case MSG_TIMEGPS:
  1065. Debug("MSG_TIMEGPS");
  1066. _check_new_itow(_buffer.timegps.itow);
  1067. if (_buffer.timegps.valid & UBX_TIMEGPS_VALID_WEEK_MASK) {
  1068. state.time_week = _buffer.timegps.week;
  1069. }
  1070. break;
  1071. case MSG_VELNED:
  1072. Debug("MSG_VELNED");
  1073. if (havePvtMsg) {
  1074. _unconfigured_messages |= CONFIG_RATE_VELNED;
  1075. break;
  1076. }
  1077. _check_new_itow(_buffer.velned.itow);
  1078. _last_vel_time = _buffer.velned.itow;
  1079. state.ground_speed = _buffer.velned.speed_2d*0.01f; // m/s
  1080. state.ground_course = wrap_360(_buffer.velned.heading_2d * 1.0e-5f); // Heading 2D deg * 100000
  1081. state.have_vertical_velocity = true;
  1082. state.velocity.x = _buffer.velned.ned_north * 0.01f;
  1083. state.velocity.y = _buffer.velned.ned_east * 0.01f;
  1084. state.velocity.z = _buffer.velned.ned_down * 0.01f;
  1085. state.ground_course = wrap_360(degrees(atan2f(state.velocity.y, state.velocity.x)));
  1086. state.ground_speed = norm(state.velocity.y, state.velocity.x);
  1087. state.have_speed_accuracy = true;
  1088. state.speed_accuracy = _buffer.velned.speed_accuracy*0.01f;
  1089. #if UBLOX_FAKE_3DLOCK
  1090. state.speed_accuracy = 0;
  1091. #endif
  1092. _new_speed = true;
  1093. break;
  1094. case MSG_NAV_SVINFO:
  1095. {
  1096. Debug("MSG_NAV_SVINFO\n");
  1097. static const uint8_t HardwareGenerationMask = 0x07;
  1098. _check_new_itow(_buffer.svinfo_header.itow);
  1099. _hardware_generation = _buffer.svinfo_header.globalFlags & HardwareGenerationMask;
  1100. switch (_hardware_generation) {
  1101. case UBLOX_5:
  1102. case UBLOX_6:
  1103. // only 7 and newer support CONFIG_GNSS
  1104. _unconfigured_messages &= ~CONFIG_GNSS;
  1105. break;
  1106. case UBLOX_7:
  1107. case UBLOX_M8:
  1108. #if UBLOX_SPEED_CHANGE
  1109. port->begin(4000000U);
  1110. Debug("Changed speed to 4Mhz for SPI-driven UBlox\n");
  1111. #endif
  1112. break;
  1113. default:
  1114. hal.console->printf("Wrong Ublox Hardware Version%u\n", _hardware_generation);
  1115. break;
  1116. };
  1117. _unconfigured_messages &= ~CONFIG_VERSION;
  1118. /* We don't need that anymore */
  1119. _configure_message_rate(CLASS_NAV, MSG_NAV_SVINFO, 0);
  1120. break;
  1121. }
  1122. default:
  1123. Debug("Unexpected NAV message 0x%02x", (unsigned)_msg_id);
  1124. if (++_disable_counter == 0) {
  1125. Debug("Disabling NAV message 0x%02x", (unsigned)_msg_id);
  1126. _configure_message_rate(CLASS_NAV, _msg_id, 0);
  1127. }
  1128. return false;
  1129. }
  1130. // we only return true when we get new position and speed data
  1131. // this ensures we don't use stale data
  1132. if (_new_position && _new_speed && _last_vel_time == _last_pos_time) {
  1133. _new_speed = _new_position = false;
  1134. return true;
  1135. }
  1136. return false;
  1137. }
  1138. // UBlox auto configuration
  1139. /*
  1140. * update checksum for a set of bytes
  1141. */
  1142. void
  1143. AP_GPS_UBLOX::_update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b)
  1144. {
  1145. while (len--) {
  1146. ck_a += *data;
  1147. ck_b += ck_a;
  1148. data++;
  1149. }
  1150. }
  1151. /*
  1152. * send a ublox message
  1153. */
  1154. bool
  1155. AP_GPS_UBLOX::_send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint16_t size)
  1156. {
  1157. if (port->txspace() < (sizeof(struct ubx_header) + 2 + size)) {
  1158. return false;
  1159. }
  1160. struct ubx_header header;
  1161. uint8_t ck_a=0, ck_b=0;
  1162. header.preamble1 = PREAMBLE1;
  1163. header.preamble2 = PREAMBLE2;
  1164. header.msg_class = msg_class;
  1165. header.msg_id = msg_id;
  1166. header.length = size;
  1167. _update_checksum((uint8_t *)&header.msg_class, sizeof(header)-2, ck_a, ck_b);
  1168. _update_checksum((uint8_t *)msg, size, ck_a, ck_b);
  1169. port->write((const uint8_t *)&header, sizeof(header));
  1170. port->write((const uint8_t *)msg, size);
  1171. port->write((const uint8_t *)&ck_a, 1);
  1172. port->write((const uint8_t *)&ck_b, 1);
  1173. return true;
  1174. }
  1175. /*
  1176. * requests the given message rate for a specific message class
  1177. * and msg_id
  1178. * returns true if it sent the request, false if waiting on knowing the port
  1179. */
  1180. bool
  1181. AP_GPS_UBLOX::_request_message_rate(uint8_t msg_class, uint8_t msg_id)
  1182. {
  1183. // Without knowing what communication port is being used it isn't possible to verify
  1184. // always ensure we have a port before sending the request
  1185. if(_ublox_port >= UBLOX_MAX_PORTS) {
  1186. _request_port();
  1187. return false;
  1188. } else {
  1189. struct ubx_cfg_msg msg;
  1190. msg.msg_class = msg_class;
  1191. msg.msg_id = msg_id;
  1192. return _send_message(CLASS_CFG, MSG_CFG_MSG, &msg, sizeof(msg));
  1193. }
  1194. }
  1195. /*
  1196. * configure a UBlox GPS for the given message rate for a specific
  1197. * message class and msg_id
  1198. */
  1199. bool
  1200. AP_GPS_UBLOX::_configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
  1201. {
  1202. if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+sizeof(struct ubx_cfg_msg_rate)+2)) {
  1203. return false;
  1204. }
  1205. struct ubx_cfg_msg_rate msg;
  1206. msg.msg_class = msg_class;
  1207. msg.msg_id = msg_id;
  1208. msg.rate = rate;
  1209. return _send_message(CLASS_CFG, MSG_CFG_MSG, &msg, sizeof(msg));
  1210. }
  1211. /*
  1212. * save gps configurations to non-volatile memory sent until the call of
  1213. * this message
  1214. */
  1215. void
  1216. AP_GPS_UBLOX::_save_cfg()
  1217. {
  1218. ubx_cfg_cfg save_cfg;
  1219. save_cfg.clearMask = 0;
  1220. save_cfg.saveMask = SAVE_CFG_ALL;
  1221. save_cfg.loadMask = 0;
  1222. _send_message(CLASS_CFG, MSG_CFG_CFG, &save_cfg, sizeof(save_cfg));
  1223. _last_cfg_sent_time = AP_HAL::millis();
  1224. _num_cfg_save_tries++;
  1225. GCS_SEND_TEXT(MAV_SEVERITY_INFO,
  1226. "GPS: u-blox %d saving config",
  1227. state.instance + 1);
  1228. }
  1229. /*
  1230. detect a Ublox GPS. Adds one byte, and returns true if the stream
  1231. matches a UBlox
  1232. */
  1233. bool
  1234. AP_GPS_UBLOX::_detect(struct UBLOX_detect_state &state, uint8_t data)
  1235. {
  1236. reset:
  1237. switch (state.step) {
  1238. case 1:
  1239. if (PREAMBLE2 == data) {
  1240. state.step++;
  1241. break;
  1242. }
  1243. state.step = 0;
  1244. FALLTHROUGH;
  1245. case 0:
  1246. if (PREAMBLE1 == data)
  1247. state.step++;
  1248. break;
  1249. case 2:
  1250. state.step++;
  1251. state.ck_b = state.ck_a = data;
  1252. break;
  1253. case 3:
  1254. state.step++;
  1255. state.ck_b += (state.ck_a += data);
  1256. break;
  1257. case 4:
  1258. state.step++;
  1259. state.ck_b += (state.ck_a += data);
  1260. state.payload_length = data;
  1261. break;
  1262. case 5:
  1263. state.step++;
  1264. state.ck_b += (state.ck_a += data);
  1265. state.payload_counter = 0;
  1266. break;
  1267. case 6:
  1268. state.ck_b += (state.ck_a += data);
  1269. if (++state.payload_counter == state.payload_length)
  1270. state.step++;
  1271. break;
  1272. case 7:
  1273. state.step++;
  1274. if (state.ck_a != data) {
  1275. state.step = 0;
  1276. goto reset;
  1277. }
  1278. break;
  1279. case 8:
  1280. state.step = 0;
  1281. if (state.ck_b == data) {
  1282. // a valid UBlox packet
  1283. return true;
  1284. } else {
  1285. goto reset;
  1286. }
  1287. }
  1288. return false;
  1289. }
  1290. void
  1291. AP_GPS_UBLOX::_request_version(void)
  1292. {
  1293. _send_message(CLASS_MON, MSG_MON_VER, nullptr, 0);
  1294. }
  1295. void
  1296. AP_GPS_UBLOX::_configure_rate(void)
  1297. {
  1298. struct ubx_cfg_nav_rate msg;
  1299. // require a minimum measurement rate of 5Hz
  1300. msg.measure_rate_ms = gps.get_rate_ms(state.instance);
  1301. msg.nav_rate = 1;
  1302. msg.timeref = 0; // UTC time
  1303. _send_message(CLASS_CFG, MSG_CFG_RATE, &msg, sizeof(msg));
  1304. }
  1305. static const char *reasons[] = {"navigation rate",
  1306. "posllh rate",
  1307. "status rate",
  1308. "solution rate",
  1309. "velned rate",
  1310. "dop rate",
  1311. "hw monitor rate",
  1312. "hw2 monitor rate",
  1313. "raw rate",
  1314. "version",
  1315. "navigation settings",
  1316. "GNSS settings",
  1317. "SBAS settings",
  1318. "PVT rate",
  1319. "time pulse settings",
  1320. "TIMEGPS rate"};
  1321. static_assert((1 << ARRAY_SIZE(reasons)) == CONFIG_LAST, "UBLOX: Missing configuration description");
  1322. void
  1323. AP_GPS_UBLOX::broadcast_configuration_failure_reason(void) const {
  1324. for (uint8_t i = 0; i < ARRAY_SIZE(reasons); i++) {
  1325. if (_unconfigured_messages & (1 << i)) {
  1326. GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %u: u-blox %s configuration 0x%02x",
  1327. (unsigned int)(state.instance + 1), reasons[i], (unsigned int)_unconfigured_messages);
  1328. break;
  1329. }
  1330. }
  1331. }
  1332. /*
  1333. return velocity lag in seconds
  1334. */
  1335. bool AP_GPS_UBLOX::get_lag(float &lag_sec) const
  1336. {
  1337. switch (_hardware_generation) {
  1338. case UBLOX_UNKNOWN_HARDWARE_GENERATION:
  1339. lag_sec = 0.22f;
  1340. // always bail out in this case, it's used to indicate we have yet to receive a valid
  1341. // hardware generation, however the user may have inhibited us detecting the generation
  1342. // so if we aren't allowed to do configuration, we will accept this as the default delay
  1343. return gps._auto_config != AP_GPS::GPS_AUTO_CONFIG_ENABLE;
  1344. case UBLOX_5:
  1345. case UBLOX_6:
  1346. default:
  1347. lag_sec = 0.22f;
  1348. break;
  1349. case UBLOX_7:
  1350. case UBLOX_M8:
  1351. // based on flight logs the 7 and 8 series seem to produce about 120ms lag
  1352. lag_sec = 0.12f;
  1353. break;
  1354. case UBLOX_F9:
  1355. // F9 lag not verified yet from flight log, but likely to be at least
  1356. // as good as M8
  1357. lag_sec = 0.12f;
  1358. break;
  1359. };
  1360. return true;
  1361. }
  1362. void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const
  1363. {
  1364. #ifndef HAL_NO_LOGGING
  1365. AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages();
  1366. if (_have_version) {
  1367. AP::logger().Write_MessageF("u-blox %d HW: %s SW: %s",
  1368. state.instance+1,
  1369. _version.hwVersion,
  1370. _version.swVersion);
  1371. }
  1372. #endif
  1373. }
  1374. // uBlox specific check_new_itow(), handling message length
  1375. void AP_GPS_UBLOX::_check_new_itow(uint32_t itow)
  1376. {
  1377. check_new_itow(itow, _payload_length + sizeof(ubx_header) + 2);
  1378. }