AP_GPS_SBF.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425
  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. // Septentrio GPS driver for ArduPilot.
  15. // Code by Michael Oborne
  16. //
  17. #define ALLOW_DOUBLE_MATH_FUNCTIONS
  18. #include "AP_GPS.h"
  19. #include "AP_GPS_SBF.h"
  20. #include <GCS_MAVLink/GCS.h>
  21. extern const AP_HAL::HAL& hal;
  22. #define SBF_DEBUGGING 0
  23. #if SBF_DEBUGGING
  24. # define Debug(fmt, args ...) \
  25. do { \
  26. hal.console->printf("%s:%d: " fmt "\n", \
  27. __FUNCTION__, __LINE__, \
  28. ## args); \
  29. hal.scheduler->delay(1); \
  30. } while(0)
  31. #else
  32. # define Debug(fmt, args ...)
  33. #endif
  34. #define SBF_EXCESS_COMMAND_BYTES 5 // 2 start bytes + validity byte + space byte + endline byte
  35. #define RX_ERROR_MASK (CONGESTION | \
  36. MISSEDEVENT | \
  37. CPUOVERLOAD | \
  38. INVALIDCONFIG | \
  39. OUTOFGEOFENCE)
  40. AP_GPS_SBF::AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state,
  41. AP_HAL::UARTDriver *_port) :
  42. AP_GPS_Backend(_gps, _state, _port)
  43. {
  44. sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
  45. port->write((const uint8_t*)_port_enable, strlen(_port_enable));
  46. _config_last_ack_time = AP_HAL::millis();
  47. }
  48. // Process all bytes available from the stream
  49. //
  50. bool
  51. AP_GPS_SBF::read(void)
  52. {
  53. bool ret = false;
  54. uint32_t available_bytes = port->available();
  55. for (uint32_t i = 0; i < available_bytes; i++) {
  56. uint8_t temp = port->read();
  57. ret |= parse(temp);
  58. }
  59. if (gps._auto_config != AP_GPS::GPS_AUTO_CONFIG_DISABLE) {
  60. if (_init_blob_index < ARRAY_SIZE(_initialisation_blob)) {
  61. uint32_t now = AP_HAL::millis();
  62. const char *init_str = _initialisation_blob[_init_blob_index];
  63. if (now > _init_blob_time) {
  64. if (now > _config_last_ack_time + 2500) {
  65. // try to enable input on the GPS port if we have not made progress on configuring it
  66. Debug("SBF Sending port enable");
  67. port->write((const uint8_t*)_port_enable, strlen(_port_enable));
  68. _config_last_ack_time = now;
  69. } else {
  70. Debug("SBF sending init string: %s", init_str);
  71. port->write((const uint8_t*)init_str, strlen(init_str));
  72. }
  73. _init_blob_time = now + 1000;
  74. }
  75. } else if (gps._raw_data == 2) { // only manage disarm/rearms when the user opts into it
  76. if (hal.util->get_soft_armed()) {
  77. _has_been_armed = true;
  78. } else if (_has_been_armed && (RxState & SBF_DISK_MOUNTED)) {
  79. // since init is done at this point and unmounting should be rate limited,
  80. // take over the _init_blob_time variable
  81. uint32_t now = AP_HAL::millis();
  82. if (now > _init_blob_time) {
  83. unmount_disk();
  84. _init_blob_time = now + 1000;
  85. }
  86. }
  87. }
  88. }
  89. return ret;
  90. }
  91. bool
  92. AP_GPS_SBF::parse(uint8_t temp)
  93. {
  94. switch (sbf_msg.sbf_state)
  95. {
  96. default:
  97. case sbf_msg_parser_t::PREAMBLE1:
  98. if (temp == SBF_PREAMBLE1) {
  99. sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE2;
  100. sbf_msg.read = 0;
  101. }
  102. break;
  103. case sbf_msg_parser_t::PREAMBLE2:
  104. if (temp == SBF_PREAMBLE2) {
  105. sbf_msg.sbf_state = sbf_msg_parser_t::CRC1;
  106. } else if (temp == 'R') {
  107. Debug("SBF got a response\n");
  108. sbf_msg.sbf_state = sbf_msg_parser_t::COMMAND_LINE;
  109. }
  110. else
  111. {
  112. sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
  113. }
  114. break;
  115. case sbf_msg_parser_t::CRC1:
  116. sbf_msg.crc = temp;
  117. sbf_msg.sbf_state = sbf_msg_parser_t::CRC2;
  118. break;
  119. case sbf_msg_parser_t::CRC2:
  120. sbf_msg.crc += (uint16_t)(temp << 8);
  121. sbf_msg.sbf_state = sbf_msg_parser_t::BLOCKID1;
  122. break;
  123. case sbf_msg_parser_t::BLOCKID1:
  124. sbf_msg.blockid = temp;
  125. sbf_msg.sbf_state = sbf_msg_parser_t::BLOCKID2;
  126. break;
  127. case sbf_msg_parser_t::BLOCKID2:
  128. sbf_msg.blockid += (uint16_t)(temp << 8);
  129. sbf_msg.sbf_state = sbf_msg_parser_t::LENGTH1;
  130. break;
  131. case sbf_msg_parser_t::LENGTH1:
  132. sbf_msg.length = temp;
  133. sbf_msg.sbf_state = sbf_msg_parser_t::LENGTH2;
  134. break;
  135. case sbf_msg_parser_t::LENGTH2:
  136. sbf_msg.length += (uint16_t)(temp << 8);
  137. sbf_msg.sbf_state = sbf_msg_parser_t::DATA;
  138. if (sbf_msg.length % 4 != 0) {
  139. sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
  140. Debug("bad packet length=%u\n", (unsigned)sbf_msg.length);
  141. }
  142. if (sbf_msg.length < 8) {
  143. Debug("bad packet length=%u\n", (unsigned)sbf_msg.length);
  144. sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
  145. crc_error_counter++; // this is a probable buffer overflow, but this
  146. // indicates not enough bytes to do a crc
  147. break;
  148. }
  149. break;
  150. case sbf_msg_parser_t::DATA:
  151. if (sbf_msg.read < sizeof(sbf_msg.data)) {
  152. sbf_msg.data.bytes[sbf_msg.read] = temp;
  153. }
  154. sbf_msg.read++;
  155. if (sbf_msg.read >= (sbf_msg.length - 8)) {
  156. if (sbf_msg.read > sizeof(sbf_msg.data)) {
  157. // not interested in these large messages
  158. sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
  159. break;
  160. }
  161. uint16_t crc = crc16_ccitt((uint8_t*)&sbf_msg.blockid, 2, 0);
  162. crc = crc16_ccitt((uint8_t*)&sbf_msg.length, 2, crc);
  163. crc = crc16_ccitt((uint8_t*)&sbf_msg.data, sbf_msg.length - 8, crc);
  164. sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
  165. if (sbf_msg.crc == crc) {
  166. return process_message();
  167. } else {
  168. Debug("crc fail\n");
  169. crc_error_counter++;
  170. }
  171. }
  172. break;
  173. case sbf_msg_parser_t::COMMAND_LINE:
  174. if (sbf_msg.read < (sizeof(sbf_msg.data) - 1)) {
  175. sbf_msg.data.bytes[sbf_msg.read] = temp;
  176. } else {
  177. // we don't have enough buffer to compare the commands
  178. // most probable cause is that a user injected a longer command then
  179. // we have buffer for, or it could be a corruption, either way we
  180. // simply ignore the result
  181. sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
  182. break;
  183. }
  184. sbf_msg.read++;
  185. if (temp == '\n') {
  186. sbf_msg.data.bytes[sbf_msg.read] = 0;
  187. // received the result, lets assess it
  188. if (sbf_msg.data.bytes[0] == ':') {
  189. // valid command, determine if it was the one we were trying
  190. // to send in the configuration sequence
  191. if (_init_blob_index < ARRAY_SIZE(_initialisation_blob)) {
  192. if (!strncmp(_initialisation_blob[_init_blob_index], (char *)(sbf_msg.data.bytes + 2),
  193. sbf_msg.read - SBF_EXCESS_COMMAND_BYTES)) {
  194. Debug("SBF Ack Command: %s\n", sbf_msg.data.bytes);
  195. _init_blob_index++;
  196. _config_last_ack_time = AP_HAL::millis();
  197. } else {
  198. Debug("SBF Ack command (unexpected): %s\n", sbf_msg.data.bytes);
  199. }
  200. }
  201. } else {
  202. // rejected command, send it out as a debug
  203. Debug("SBF NACK Command: %s\n", sbf_msg.data.bytes);
  204. }
  205. // resume normal parsing
  206. sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
  207. break;
  208. }
  209. break;
  210. }
  211. return false;
  212. }
  213. bool
  214. AP_GPS_SBF::process_message(void)
  215. {
  216. uint16_t blockid = (sbf_msg.blockid & 8191u);
  217. Debug("BlockID %d", blockid);
  218. switch (blockid) {
  219. case PVTGeodetic:
  220. {
  221. const msg4007 &temp = sbf_msg.data.msg4007u;
  222. // Update time state
  223. if (temp.WNc != 65535) {
  224. state.time_week = temp.WNc;
  225. state.time_week_ms = (uint32_t)(temp.TOW);
  226. }
  227. check_new_itow(temp.TOW, sbf_msg.length);
  228. state.last_gps_time_ms = AP_HAL::millis();
  229. // Update velocity state (don't use −2·10^10)
  230. if (temp.Vn > -200000) {
  231. state.velocity.x = (float)(temp.Vn);
  232. state.velocity.y = (float)(temp.Ve);
  233. state.velocity.z = (float)(-temp.Vu);
  234. state.have_vertical_velocity = true;
  235. float ground_vector_sq = state.velocity[0] * state.velocity[0] + state.velocity[1] * state.velocity[1];
  236. state.ground_speed = (float)safe_sqrt(ground_vector_sq);
  237. state.ground_course = wrap_360(degrees(atan2f(state.velocity[1], state.velocity[0])));
  238. state.rtk_age_ms = temp.MeanCorrAge * 10;
  239. // value is expressed as twice the rms error = int16 * 0.01/2
  240. state.horizontal_accuracy = (float)temp.HAccuracy * 0.005f;
  241. state.vertical_accuracy = (float)temp.VAccuracy * 0.005f;
  242. state.have_horizontal_accuracy = true;
  243. state.have_vertical_accuracy = true;
  244. }
  245. // Update position state (don't use -2·10^10)
  246. if (temp.Latitude > -200000) {
  247. state.location.lat = (int32_t)(temp.Latitude * RAD_TO_DEG_DOUBLE * (double)1e7);
  248. state.location.lng = (int32_t)(temp.Longitude * RAD_TO_DEG_DOUBLE * (double)1e7);
  249. state.location.alt = (int32_t)(((float)temp.Height - temp.Undulation) * 1e2f);
  250. }
  251. if (temp.NrSV != 255) {
  252. state.num_sats = temp.NrSV;
  253. }
  254. Debug("temp.Mode=0x%02x\n", (unsigned)temp.Mode);
  255. switch (temp.Mode & 15) {
  256. case 0: // no pvt
  257. state.status = AP_GPS::NO_FIX;
  258. break;
  259. case 1: // standalone
  260. state.status = AP_GPS::GPS_OK_FIX_3D;
  261. break;
  262. case 2: // dgps
  263. state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
  264. break;
  265. case 3: // fixed location
  266. state.status = AP_GPS::GPS_OK_FIX_3D;
  267. break;
  268. case 4: // rtk fixed
  269. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
  270. break;
  271. case 5: // rtk float
  272. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
  273. break;
  274. case 6: // sbas
  275. state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
  276. break;
  277. case 7: // moving rtk fixed
  278. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
  279. break;
  280. case 8: // moving rtk float
  281. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
  282. break;
  283. }
  284. if ((temp.Mode & 64) > 0) { // gps is in base mode
  285. state.status = AP_GPS::NO_FIX;
  286. } else if ((temp.Mode & 128) > 0) { // gps only has 2d fix
  287. state.status = AP_GPS::GPS_OK_FIX_2D;
  288. }
  289. return true;
  290. }
  291. case DOP:
  292. {
  293. const msg4001 &temp = sbf_msg.data.msg4001u;
  294. check_new_itow(temp.TOW, sbf_msg.length);
  295. state.hdop = temp.HDOP;
  296. state.vdop = temp.VDOP;
  297. break;
  298. }
  299. case ReceiverStatus:
  300. {
  301. const msg4014 &temp = sbf_msg.data.msg4014u;
  302. check_new_itow(temp.TOW, sbf_msg.length);
  303. RxState = temp.RxState;
  304. if ((RxError & RX_ERROR_MASK) != (temp.RxError & RX_ERROR_MASK)) {
  305. gcs().send_text(MAV_SEVERITY_INFO, "GPS %u: SBF error changed (0x%08x/0x%08x)", (unsigned int)(state.instance + 1),
  306. (unsigned int)(RxError & RX_ERROR_MASK), (unsigned int)(temp.RxError & RX_ERROR_MASK));
  307. }
  308. RxError = temp.RxError;
  309. break;
  310. }
  311. case VelCovGeodetic:
  312. {
  313. const msg5908 &temp = sbf_msg.data.msg5908u;
  314. check_new_itow(temp.TOW, sbf_msg.length);
  315. // select the maximum variance, as the EKF will apply it to all the columns in it's estimate
  316. // FIXME: Support returning the covariance matrix to the EKF
  317. float max_variance_squared = MAX(temp.Cov_VnVn, MAX(temp.Cov_VeVe, temp.Cov_VuVu));
  318. if (is_positive(max_variance_squared)) {
  319. state.have_speed_accuracy = true;
  320. state.speed_accuracy = sqrt(max_variance_squared);
  321. } else {
  322. state.have_speed_accuracy = false;
  323. }
  324. break;
  325. }
  326. }
  327. return false;
  328. }
  329. void AP_GPS_SBF::broadcast_configuration_failure_reason(void) const
  330. {
  331. if (gps._auto_config != AP_GPS::GPS_AUTO_CONFIG_DISABLE &&
  332. _init_blob_index < ARRAY_SIZE(_initialisation_blob)) {
  333. gcs().send_text(MAV_SEVERITY_INFO, "GPS %u: SBF is not fully configured (%u/%u)", state.instance + 1,
  334. _init_blob_index, (unsigned)ARRAY_SIZE(_initialisation_blob));
  335. }
  336. }
  337. bool AP_GPS_SBF::is_configured (void) {
  338. return (gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE ||
  339. _init_blob_index >= ARRAY_SIZE(_initialisation_blob));
  340. }
  341. bool AP_GPS_SBF::is_healthy (void) const {
  342. return (RxError & RX_ERROR_MASK) == 0;
  343. }
  344. void AP_GPS_SBF::mount_disk (void) const {
  345. const char* command = "emd, DSK1, Mount\n";
  346. Debug("Mounting disk");
  347. port->write((const uint8_t*)command, strlen(command));
  348. }
  349. void AP_GPS_SBF::unmount_disk (void) const {
  350. const char* command = "emd, DSK1, Unmount\n";
  351. Debug("Unmounting disk");
  352. port->write((const uint8_t*)command, strlen(command));
  353. }
  354. bool AP_GPS_SBF::prepare_for_arming(void) {
  355. bool is_logging = true; // assume that its logging until proven otherwise
  356. if (gps._raw_data) {
  357. if (!(RxState & SBF_DISK_MOUNTED)){
  358. is_logging = false;
  359. gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF disk is not mounted", state.instance + 1);
  360. // simply attempt to mount the disk, no need to check if the command was
  361. // ACK/NACK'd as we don't continuously attempt to remount the disk
  362. gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: Attempting to mount disk", state.instance + 1);
  363. mount_disk();
  364. // reset the flag to indicate if we should be logging
  365. _has_been_armed = false;
  366. }
  367. else if (RxState & SBF_DISK_FULL) {
  368. is_logging = false;
  369. gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF disk is full", state.instance + 1);
  370. }
  371. else if (!(RxState & SBF_DISK_ACTIVITY)) {
  372. is_logging = false;
  373. gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF is not currently logging", state.instance + 1);
  374. }
  375. }
  376. return is_logging;
  377. }