AP_GPS_GSOF.h 2.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384
  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. #pragma once
  18. #include "AP_GPS.h"
  19. #include "GPS_Backend.h"
  20. class AP_GPS_GSOF : public AP_GPS_Backend
  21. {
  22. public:
  23. AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
  24. AP_GPS::GPS_Status highest_supported_status(void) override {
  25. return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
  26. }
  27. // Methods
  28. bool read() override;
  29. const char *name() const override { return "GSOF"; }
  30. private:
  31. bool parse(uint8_t temp);
  32. bool process_message();
  33. void requestBaud(uint8_t portindex);
  34. void requestGSOF(uint8_t messagetype, uint8_t portindex);
  35. double SwapDouble(uint8_t* src, uint32_t pos);
  36. float SwapFloat(uint8_t* src, uint32_t pos);
  37. uint32_t SwapUint32(uint8_t* src, uint32_t pos);
  38. uint16_t SwapUint16(uint8_t* src, uint32_t pos);
  39. struct gsof_msg_parser_t
  40. {
  41. enum
  42. {
  43. STARTTX = 0,
  44. STATUS,
  45. PACKETTYPE,
  46. LENGTH,
  47. DATA,
  48. CHECKSUM,
  49. ENDTX
  50. } gsof_state;
  51. uint8_t starttx;
  52. uint8_t status;
  53. uint8_t packettype;
  54. uint8_t length;
  55. uint8_t data[256];
  56. uint8_t checksum;
  57. uint8_t endtx;
  58. uint16_t read;
  59. uint8_t checksumcalc;
  60. } gsof_msg;
  61. static const uint8_t GSOF_STX = 0x02;
  62. static const uint8_t GSOF_ETX = 0x03;
  63. uint8_t packetcount = 0;
  64. uint32_t gsofmsg_time = 0;
  65. uint8_t gsofmsgreq_index = 0;
  66. uint8_t gsofmsgreq[5] = {1,2,8,9,12};
  67. };