AP_GPS_GSOF.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346
  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. // Trimble 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_GSOF.h"
  20. #include <AP_Logger/AP_Logger.h>
  21. extern const AP_HAL::HAL& hal;
  22. #define gsof_DEBUGGING 0
  23. #if gsof_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. AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state,
  35. AP_HAL::UARTDriver *_port) :
  36. AP_GPS_Backend(_gps, _state, _port)
  37. {
  38. gsof_msg.gsof_state = gsof_msg_parser_t::STARTTX;
  39. // baud request for port 0
  40. requestBaud(0);
  41. // baud request for port 3
  42. requestBaud(3);
  43. uint32_t now = AP_HAL::millis();
  44. gsofmsg_time = now + 110;
  45. }
  46. // Process all bytes available from the stream
  47. //
  48. bool
  49. AP_GPS_GSOF::read(void)
  50. {
  51. uint32_t now = AP_HAL::millis();
  52. if (gsofmsgreq_index < (sizeof(gsofmsgreq))) {
  53. if (now > gsofmsg_time) {
  54. requestGSOF(gsofmsgreq[gsofmsgreq_index], 0);
  55. requestGSOF(gsofmsgreq[gsofmsgreq_index], 3);
  56. gsofmsg_time = now + 110;
  57. gsofmsgreq_index++;
  58. }
  59. }
  60. bool ret = false;
  61. while (port->available() > 0) {
  62. uint8_t temp = port->read();
  63. ret |= parse(temp);
  64. }
  65. return ret;
  66. }
  67. bool
  68. AP_GPS_GSOF::parse(uint8_t temp)
  69. {
  70. switch (gsof_msg.gsof_state)
  71. {
  72. default:
  73. case gsof_msg_parser_t::STARTTX:
  74. if (temp == GSOF_STX)
  75. {
  76. gsof_msg.starttx = temp;
  77. gsof_msg.gsof_state = gsof_msg_parser_t::STATUS;
  78. gsof_msg.read = 0;
  79. gsof_msg.checksumcalc = 0;
  80. }
  81. break;
  82. case gsof_msg_parser_t::STATUS:
  83. gsof_msg.status = temp;
  84. gsof_msg.gsof_state = gsof_msg_parser_t::PACKETTYPE;
  85. gsof_msg.checksumcalc += temp;
  86. break;
  87. case gsof_msg_parser_t::PACKETTYPE:
  88. gsof_msg.packettype = temp;
  89. gsof_msg.gsof_state = gsof_msg_parser_t::LENGTH;
  90. gsof_msg.checksumcalc += temp;
  91. break;
  92. case gsof_msg_parser_t::LENGTH:
  93. gsof_msg.length = temp;
  94. gsof_msg.gsof_state = gsof_msg_parser_t::DATA;
  95. gsof_msg.checksumcalc += temp;
  96. break;
  97. case gsof_msg_parser_t::DATA:
  98. gsof_msg.data[gsof_msg.read] = temp;
  99. gsof_msg.read++;
  100. gsof_msg.checksumcalc += temp;
  101. if (gsof_msg.read >= gsof_msg.length)
  102. {
  103. gsof_msg.gsof_state = gsof_msg_parser_t::CHECKSUM;
  104. }
  105. break;
  106. case gsof_msg_parser_t::CHECKSUM:
  107. gsof_msg.checksum = temp;
  108. gsof_msg.gsof_state = gsof_msg_parser_t::ENDTX;
  109. if (gsof_msg.checksum == gsof_msg.checksumcalc)
  110. {
  111. return process_message();
  112. }
  113. break;
  114. case gsof_msg_parser_t::ENDTX:
  115. gsof_msg.endtx = temp;
  116. gsof_msg.gsof_state = gsof_msg_parser_t::STARTTX;
  117. break;
  118. }
  119. return false;
  120. }
  121. void
  122. AP_GPS_GSOF::requestBaud(uint8_t portindex)
  123. {
  124. uint8_t buffer[19] = {0x02,0x00,0x64,0x0d,0x00,0x00,0x00, // application file record
  125. 0x03, 0x00, 0x01, 0x00, // file control information block
  126. 0x02, 0x04, portindex, 0x07, 0x00,0x00, // serial port baud format
  127. 0x00,0x03
  128. }; // checksum
  129. buffer[4] = packetcount++;
  130. uint8_t checksum = 0;
  131. for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) {
  132. checksum += buffer[a];
  133. }
  134. buffer[17] = checksum;
  135. port->write((const uint8_t*)buffer, sizeof(buffer));
  136. }
  137. void
  138. AP_GPS_GSOF::requestGSOF(uint8_t messagetype, uint8_t portindex)
  139. {
  140. uint8_t buffer[21] = {0x02,0x00,0x64,0x0f,0x00,0x00,0x00, // application file record
  141. 0x03,0x00,0x01,0x00, // file control information block
  142. 0x07,0x06,0x0a,portindex,0x01,0x00,0x01,0x00, // output message record
  143. 0x00,0x03
  144. }; // checksum
  145. buffer[4] = packetcount++;
  146. buffer[17] = messagetype;
  147. uint8_t checksum = 0;
  148. for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) {
  149. checksum += buffer[a];
  150. }
  151. buffer[19] = checksum;
  152. port->write((const uint8_t*)buffer, sizeof(buffer));
  153. }
  154. double
  155. AP_GPS_GSOF::SwapDouble(uint8_t* src, uint32_t pos)
  156. {
  157. union {
  158. double d;
  159. char bytes[sizeof(double)];
  160. } doubleu;
  161. doubleu.bytes[0] = src[pos + 7];
  162. doubleu.bytes[1] = src[pos + 6];
  163. doubleu.bytes[2] = src[pos + 5];
  164. doubleu.bytes[3] = src[pos + 4];
  165. doubleu.bytes[4] = src[pos + 3];
  166. doubleu.bytes[5] = src[pos + 2];
  167. doubleu.bytes[6] = src[pos + 1];
  168. doubleu.bytes[7] = src[pos + 0];
  169. return doubleu.d;
  170. }
  171. float
  172. AP_GPS_GSOF::SwapFloat(uint8_t* src, uint32_t pos)
  173. {
  174. union {
  175. float f;
  176. char bytes[sizeof(float)];
  177. } floatu;
  178. floatu.bytes[0] = src[pos + 3];
  179. floatu.bytes[1] = src[pos + 2];
  180. floatu.bytes[2] = src[pos + 1];
  181. floatu.bytes[3] = src[pos + 0];
  182. return floatu.f;
  183. }
  184. uint32_t
  185. AP_GPS_GSOF::SwapUint32(uint8_t* src, uint32_t pos)
  186. {
  187. union {
  188. uint32_t u;
  189. char bytes[sizeof(uint32_t)];
  190. } uint32u;
  191. uint32u.bytes[0] = src[pos + 3];
  192. uint32u.bytes[1] = src[pos + 2];
  193. uint32u.bytes[2] = src[pos + 1];
  194. uint32u.bytes[3] = src[pos + 0];
  195. return uint32u.u;
  196. }
  197. uint16_t
  198. AP_GPS_GSOF::SwapUint16(uint8_t* src, uint32_t pos)
  199. {
  200. union {
  201. uint16_t u;
  202. char bytes[sizeof(uint16_t)];
  203. } uint16u;
  204. uint16u.bytes[0] = src[pos + 1];
  205. uint16u.bytes[1] = src[pos + 0];
  206. return uint16u.u;
  207. }
  208. bool
  209. AP_GPS_GSOF::process_message(void)
  210. {
  211. //http://www.trimble.com/OEM_ReceiverHelp/V4.81/en/default.html#welcome.html
  212. if (gsof_msg.packettype == 0x40) { // GSOF
  213. #if gsof_DEBUGGING
  214. uint8_t trans_number = gsof_msg.data[0];
  215. uint8_t pageidx = gsof_msg.data[1];
  216. uint8_t maxpageidx = gsof_msg.data[2];
  217. Debug("GSOF page: %u of %u (trans_number=%u)",
  218. pageidx, maxpageidx, trans_number);
  219. #endif
  220. int valid = 0;
  221. // want 1 2 8 9 12
  222. for (uint32_t a = 3; a < gsof_msg.length; a++)
  223. {
  224. uint8_t output_type = gsof_msg.data[a];
  225. a++;
  226. uint8_t output_length = gsof_msg.data[a];
  227. a++;
  228. //Debug("GSOF type: " + output_type + " len: " + output_length);
  229. if (output_type == 1) // pos time
  230. {
  231. state.time_week_ms = SwapUint32(gsof_msg.data, a);
  232. state.time_week = SwapUint16(gsof_msg.data, a + 4);
  233. state.num_sats = gsof_msg.data[a + 6];
  234. uint8_t posf1 = gsof_msg.data[a + 7];
  235. uint8_t posf2 = gsof_msg.data[a + 8];
  236. //Debug("POSTIME: " + posf1 + " " + posf2);
  237. if ((posf1 & 1)) { // New position
  238. state.status = AP_GPS::GPS_OK_FIX_3D;
  239. if ((posf2 & 1)) { // Differential position
  240. state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
  241. if (posf2 & 2) { // Differential position method
  242. if (posf2 & 4) {// Differential position method
  243. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
  244. } else {
  245. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
  246. }
  247. }
  248. }
  249. } else {
  250. state.status = AP_GPS::NO_FIX;
  251. }
  252. valid++;
  253. }
  254. else if (output_type == 2) // position
  255. {
  256. state.location.lat = (int32_t)(RAD_TO_DEG_DOUBLE * (SwapDouble(gsof_msg.data, a)) * (double)1e7);
  257. state.location.lng = (int32_t)(RAD_TO_DEG_DOUBLE * (SwapDouble(gsof_msg.data, a + 8)) * (double)1e7);
  258. state.location.alt = (int32_t)(SwapDouble(gsof_msg.data, a + 16) * 100);
  259. state.last_gps_time_ms = AP_HAL::millis();
  260. valid++;
  261. }
  262. else if (output_type == 8) // velocity
  263. {
  264. uint8_t vflag = gsof_msg.data[a];
  265. if ((vflag & 1) == 1)
  266. {
  267. state.ground_speed = SwapFloat(gsof_msg.data, a + 1);
  268. state.ground_course = degrees(SwapFloat(gsof_msg.data, a + 5));
  269. fill_3d_velocity();
  270. state.velocity.z = -SwapFloat(gsof_msg.data, a + 9);
  271. state.have_vertical_velocity = true;
  272. }
  273. valid++;
  274. }
  275. else if (output_type == 9) //dop
  276. {
  277. state.hdop = (uint16_t)(SwapFloat(gsof_msg.data, a + 4) * 100);
  278. valid++;
  279. }
  280. else if (output_type == 12) // position sigma
  281. {
  282. state.horizontal_accuracy = (SwapFloat(gsof_msg.data, a + 4) + SwapFloat(gsof_msg.data, a + 8)) / 2;
  283. state.vertical_accuracy = SwapFloat(gsof_msg.data, a + 16);
  284. state.have_horizontal_accuracy = true;
  285. state.have_vertical_accuracy = true;
  286. valid++;
  287. }
  288. a += output_length-1u;
  289. }
  290. if (valid == 5) {
  291. return true;
  292. } else {
  293. state.status = AP_GPS::NO_FIX;
  294. }
  295. }
  296. return false;
  297. }