AP_GPS_SBP2.h 8.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204
  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. // Swift Navigation SBP GPS driver for ArduPilot.
  15. // Code by Niels Joubert
  16. //
  17. // Swift Binary Protocol format: http://docs.swift-nav.com/
  18. //
  19. #pragma once
  20. #include "AP_GPS.h"
  21. #include "GPS_Backend.h"
  22. class AP_GPS_SBP2 : public AP_GPS_Backend
  23. {
  24. public:
  25. AP_GPS_SBP2(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
  26. AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
  27. // Methods
  28. bool read() override;
  29. void inject_data(const uint8_t *data, uint16_t len) override;
  30. static bool _detect(struct SBP2_detect_state &state, uint8_t data);
  31. const char *name() const override { return "SBP2"; }
  32. private:
  33. // ************************************************************************
  34. // Swift Navigation SBP protocol types and definitions
  35. // ************************************************************************
  36. struct sbp_parser_state_t {
  37. enum {
  38. WAITING = 0,
  39. GET_TYPE = 1,
  40. GET_SENDER = 2,
  41. GET_LEN = 3,
  42. GET_MSG = 4,
  43. GET_CRC = 5
  44. } state:8;
  45. uint16_t msg_type;
  46. uint16_t sender_id;
  47. uint16_t crc;
  48. uint8_t msg_len;
  49. uint8_t n_read;
  50. uint8_t msg_buff[256];
  51. } parser_state;
  52. static const uint8_t SBP_PREAMBLE = 0x55;
  53. // Message types supported by this driver
  54. static const uint16_t SBP_STARTUP_MSGTYPE = 0xFF00;
  55. static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF;
  56. static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0102;
  57. static const uint16_t SBP_DOPS_MSGTYPE = 0x0208;
  58. static const uint16_t SBP_POS_ECEF_MSGTYPE = 0x0209;
  59. static const uint16_t SBP_POS_LLH_MSGTYPE = 0x020A;
  60. static const uint16_t SBP_BASELINE_ECEF_MSGTYPE = 0x020B;
  61. static const uint16_t SBP_BASELINE_NED_MSGTYPE = 0x020C;
  62. static const uint16_t SBP_VEL_ECEF_MSGTYPE = 0x020D;
  63. static const uint16_t SBP_VEL_NED_MSGTYPE = 0x020E;
  64. static const uint16_t SBP_TRACKING_STATE_MSGTYPE = 0x0013;
  65. static const uint16_t SBP_IAR_STATE_MSGTYPE = 0x0019;
  66. static const uint16_t SBP_EXT_EVENT_MSGTYPE = 0x0101;
  67. // Heartbeat
  68. struct PACKED sbp_heartbeat_t {
  69. bool sys_error : 1;
  70. bool io_error : 1;
  71. bool nap_error : 1;
  72. uint8_t res : 5;
  73. uint8_t protocol_minor : 8;
  74. uint8_t protocol_major : 8;
  75. uint8_t res2 : 6;
  76. bool ext_antenna_short : 1;
  77. bool ext_antenna : 1;
  78. }; // 4 bytes
  79. // GPS Time
  80. struct PACKED sbp_gps_time_t {
  81. uint16_t wn; //< GPS week number (unit: weeks)
  82. uint32_t tow; //< GPS Time of Week rounded to the nearest ms (unit: ms)
  83. int32_t ns; //< Nanosecond remainder of rounded tow (unit: ns)
  84. struct PACKED flags {
  85. uint8_t time_src:3; //< Fix mode (0: invalid, 1: GNSS Solution, 2: Propagated
  86. uint8_t res:5; //< Reserved
  87. } flags;
  88. }; // 11 bytes
  89. // Dilution of Precision
  90. struct PACKED sbp_dops_t {
  91. uint32_t tow; //< GPS Time of Week (unit: ms)
  92. uint16_t gdop; //< Geometric Dilution of Precision (unit: 0.01)
  93. uint16_t pdop; //< Position Dilution of Precision (unit: 0.01)
  94. uint16_t tdop; //< Time Dilution of Precision (unit: 0.01)
  95. uint16_t hdop; //< Horizontal Dilution of Precision (unit: 0.01)
  96. uint16_t vdop; //< Vertical Dilution of Precision (unit: 0.01)
  97. struct PACKED flags {
  98. uint8_t fix_mode:3; //< Fix mode (0: invalid, 1: SPP, 2: DGNSS, 3: Float RTX, 4: Fixed RTX, 5: Undefined, 6: SBAS Position
  99. uint8_t res:4; //< Reserved
  100. bool raim_repair:1; //< Solution from RAIM?
  101. } flags;
  102. }; // 15 bytes
  103. // Geodetic position solution.
  104. struct PACKED sbp_pos_llh_t {
  105. uint32_t tow; //< GPS Time of Week (unit: ms)
  106. double lat; //< Latitude (unit: degrees)
  107. double lon; //< Longitude (unit: degrees)
  108. double height; //< Height (unit: meters)
  109. uint16_t h_accuracy; //< Horizontal position accuracy estimate (unit: mm)
  110. uint16_t v_accuracy; //< Vertical position accuracy estimate (unit: mm)
  111. uint8_t n_sats; //< Number of satellites used in solution
  112. struct PACKED flags {
  113. uint8_t fix_mode:3; //< Fix mode (0: invalid, 1: SPP, 2: DGNSS, 3: Float RTX, 4: Fixed RTX, 5: Dead Reckoning, 6: SBAS Position
  114. uint8_t ins_mode:2; //< Inertial navigation mode (0: none, 1: INS used)
  115. uint8_t res:3; //< Reserved
  116. } flags;
  117. }; // 34 bytes
  118. // Velocity in NED Velocity in local North East Down (NED) coordinates.
  119. struct PACKED sbp_vel_ned_t {
  120. uint32_t tow; //< GPS Time of Week (unit: ms)
  121. int32_t n; //< Velocity North coordinate (unit: mm/s)
  122. int32_t e; //< Velocity East coordinate (unit: mm/s)
  123. int32_t d; //< Velocity Down coordinate (unit: mm/s)
  124. uint16_t h_accuracy; //< Horizontal velocity accuracy estimate (unit: mm/s)
  125. uint16_t v_accuracy; //< Vertical velocity accuracy estimate (unit: mm/s)
  126. uint8_t n_sats; //< Number of satellites used in solution
  127. struct PACKED flags {
  128. uint8_t vel_mode:3; //< Velocity mode (0: Invalid, 1: Measured Doppler derived, 2: Computed Doppler derived, 3: Dead reckoning)
  129. uint8_t ins_mode:2; //< Inertial navigation mode (0: none, 1: INS used)
  130. uint8_t res:3; //< Reserved
  131. } flags;
  132. }; // 22 bytes
  133. // Messages reporting accurately-timestamped external events, e.g. camera shutter time.
  134. struct PACKED sbp_ext_event_t {
  135. uint16_t wn; //< GPS week number (unit: weeks)
  136. uint32_t tow; //< GPS Time of Week (unit: ms)
  137. int32_t ns_residual; //< Nanosecond residual of millisecond-rounded TOW (ranges from -500000 to 500000)
  138. struct PACKED flags {
  139. uint8_t level:1; //< New level of pin values (0: Low (falling edge), 1: High (rising edge))
  140. uint8_t quality:1; //< Time quality values (0: Unknown - don't have nav solution, 1: Good (< 1 microsecond))
  141. uint8_t res:6; //< Reserved
  142. } flags;
  143. uint8_t pin; //< Pin number (0-9)
  144. }; // 12 bytes
  145. void _sbp_process();
  146. void _sbp_process_message();
  147. bool _attempt_state_update();
  148. // ************************************************************************
  149. // Internal Received Messages State
  150. // ************************************************************************
  151. uint32_t last_heartbeat_received_ms;
  152. uint32_t last_injected_data_ms;
  153. struct sbp_heartbeat_t last_heartbeat;
  154. struct sbp_gps_time_t last_gps_time;
  155. struct sbp_dops_t last_dops;
  156. struct sbp_pos_llh_t last_pos_llh;
  157. struct sbp_vel_ned_t last_vel_ned;
  158. struct sbp_ext_event_t last_event;
  159. uint32_t last_full_update_tow;
  160. uint16_t last_full_update_wn;
  161. // ************************************************************************
  162. // Monitoring and Performance Counting
  163. // ************************************************************************
  164. uint32_t crc_error_counter;
  165. // ************************************************************************
  166. // Logging to AP_Logger
  167. // ************************************************************************
  168. void logging_log_full_update();
  169. void logging_ext_event();
  170. void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff);
  171. int32_t distMod(int32_t tow1_ms, int32_t tow2_ms, int32_t mod);
  172. };