AP_GPS_SBP.h 7.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187
  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_SBP : public AP_GPS_Backend
  23. {
  24. public:
  25. AP_GPS_SBP(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. bool supports_mavlink_gps_rtk_message() override { return true; }
  28. // Methods
  29. bool read() override;
  30. void inject_data(const uint8_t *data, uint16_t len) override;
  31. static bool _detect(struct SBP_detect_state &state, uint8_t data);
  32. const char *name() const override { return "SBP"; }
  33. private:
  34. // ************************************************************************
  35. // Swift Navigation SBP protocol types and definitions
  36. // ************************************************************************
  37. struct sbp_parser_state_t {
  38. enum {
  39. WAITING = 0,
  40. GET_TYPE = 1,
  41. GET_SENDER = 2,
  42. GET_LEN = 3,
  43. GET_MSG = 4,
  44. GET_CRC = 5
  45. } state:8;
  46. uint16_t msg_type;
  47. uint16_t sender_id;
  48. uint16_t crc;
  49. uint8_t msg_len;
  50. uint8_t n_read;
  51. uint8_t msg_buff[256];
  52. } parser_state;
  53. static const uint8_t SBP_PREAMBLE = 0x55;
  54. //Message types supported by this driver
  55. static const uint16_t SBP_STARTUP_MSGTYPE = 0xFF00;
  56. static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF;
  57. static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0100;
  58. static const uint16_t SBP_DOPS_MSGTYPE = 0x0206;
  59. static const uint16_t SBP_POS_ECEF_MSGTYPE = 0x0200;
  60. static const uint16_t SBP_POS_LLH_MSGTYPE = 0x0201;
  61. static const uint16_t SBP_BASELINE_ECEF_MSGTYPE = 0x0202;
  62. static const uint16_t SBP_BASELINE_NED_MSGTYPE = 0x0203;
  63. static const uint16_t SBP_VEL_ECEF_MSGTYPE = 0x0204;
  64. static const uint16_t SBP_VEL_NED_MSGTYPE = 0x0205;
  65. static const uint16_t SBP_TRACKING_STATE_MSGTYPE = 0x0016;
  66. static const uint16_t SBP_IAR_STATE_MSGTYPE = 0x0019;
  67. // Heartbeat
  68. // struct sbp_heartbeat_t {
  69. // uint32_t flags; //< Status flags (reserved)
  70. // }; // 4 bytes
  71. struct PACKED sbp_heartbeat_t {
  72. bool sys_error : 1;
  73. bool io_error : 1;
  74. bool nap_error : 1;
  75. uint8_t res : 5;
  76. uint8_t protocol_minor : 8;
  77. uint8_t protocol_major : 8;
  78. uint8_t res2 : 7;
  79. bool ext_antenna : 1;
  80. }; // 4 bytes
  81. // GPS Time
  82. struct PACKED sbp_gps_time_t {
  83. uint16_t wn; //< GPS week number (unit: weeks)
  84. uint32_t tow; //< GPS Time of Week rounded to the nearest ms (unit: ms)
  85. int32_t ns; //< Nanosecond remainder of rounded tow (unit: ns)
  86. uint8_t flags; //< Status flags (reserved)
  87. }; // 11 bytes
  88. // Dilution of Precision
  89. struct PACKED sbp_dops_t {
  90. uint32_t tow; //< GPS Time of Week (unit: ms)
  91. uint16_t gdop; //< Geometric Dilution of Precision (unit: 0.01)
  92. uint16_t pdop; //< Position Dilution of Precision (unit: 0.01)
  93. uint16_t tdop; //< Time Dilution of Precision (unit: 0.01)
  94. uint16_t hdop; //< Horizontal Dilution of Precision (unit: 0.01)
  95. uint16_t vdop; //< Vertical Dilution of Precision (unit: 0.01)
  96. }; // 14 bytes
  97. // Geodetic position solution.
  98. struct PACKED sbp_pos_llh_t {
  99. uint32_t tow; //< GPS Time of Week (unit: ms)
  100. double lat; //< Latitude (unit: degrees)
  101. double lon; //< Longitude (unit: degrees)
  102. double height; //< Height (unit: meters)
  103. uint16_t h_accuracy; //< Horizontal position accuracy estimate (unit: mm)
  104. uint16_t v_accuracy; //< Vertical position accuracy estimate (unit: mm)
  105. uint8_t n_sats; //< Number of satellites used in solution
  106. uint8_t flags; //< Status flags
  107. }; // 34 bytes
  108. // Velocity in NED Velocity in local North East Down (NED) coordinates.
  109. struct PACKED sbp_vel_ned_t {
  110. uint32_t tow; //< GPS Time of Week (unit: ms)
  111. int32_t n; //< Velocity North coordinate (unit: mm/s)
  112. int32_t e; //< Velocity East coordinate (unit: mm/s)
  113. int32_t d; //< Velocity Down coordinate (unit: mm/s)
  114. uint16_t h_accuracy; //< Horizontal velocity accuracy estimate (unit: mm/s)
  115. uint16_t v_accuracy; //< Vertical velocity accuracy estimate (unit: mm/s)
  116. uint8_t n_sats; //< Number of satellites used in solution
  117. uint8_t flags; //< Status flags (reserved)
  118. }; // 22 bytes
  119. // Activity and Signal-to-Noise data of a tracking channel on the GPS.
  120. struct PACKED sbp_tracking_state_t {
  121. uint8_t state; //< 0 if disabled, 1 if running
  122. uint8_t prn; //< PRN identifier of tracked satellite
  123. float cn0; //< carrier to noise power ratio.
  124. };
  125. // Integer Ambiguity Resolution state - how is the RTK resolution doing?
  126. struct PACKED sbp_iar_state_t {
  127. uint32_t num_hypotheses;
  128. };
  129. void _sbp_process();
  130. void _sbp_process_message();
  131. bool _attempt_state_update();
  132. // ************************************************************************
  133. // Internal Received Messages State
  134. // ************************************************************************
  135. uint32_t last_heatbeat_received_ms;
  136. uint32_t last_injected_data_ms;
  137. struct sbp_gps_time_t last_gps_time;
  138. struct sbp_dops_t last_dops;
  139. struct sbp_pos_llh_t last_pos_llh_spp;
  140. struct sbp_pos_llh_t last_pos_llh_rtk;
  141. struct sbp_vel_ned_t last_vel_ned;
  142. uint32_t last_iar_num_hypotheses;
  143. uint32_t last_full_update_tow;
  144. uint32_t last_full_update_cpu_ms;
  145. // ************************************************************************
  146. // Monitoring and Performance Counting
  147. // ************************************************************************
  148. uint32_t crc_error_counter;
  149. // ************************************************************************
  150. // Logging to AP_Logger
  151. // ************************************************************************
  152. void logging_log_full_update();
  153. void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff);
  154. };