AP_GPS_SBF.h 6.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206
  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. #pragma once
  18. #include "AP_GPS.h"
  19. #include "GPS_Backend.h"
  20. #define SBF_DISK_ACTIVITY (1 << 7)
  21. #define SBF_DISK_FULL (1 << 8)
  22. #define SBF_DISK_MOUNTED (1 << 9)
  23. class AP_GPS_SBF : public AP_GPS_Backend
  24. {
  25. public:
  26. AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
  27. AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
  28. // Methods
  29. bool read() override;
  30. const char *name() const override { return "SBF"; }
  31. bool is_configured (void) override;
  32. void broadcast_configuration_failure_reason(void) const override;
  33. // get the velocity lag, returns true if the driver is confident in the returned value
  34. bool get_lag(float &lag_sec) const override { lag_sec = 0.08f; return true; } ;
  35. bool is_healthy(void) const override;
  36. bool prepare_for_arming(void) override;
  37. private:
  38. bool parse(uint8_t temp);
  39. bool process_message();
  40. static const uint8_t SBF_PREAMBLE1 = '$';
  41. static const uint8_t SBF_PREAMBLE2 = '@';
  42. uint8_t _init_blob_index = 0;
  43. uint32_t _init_blob_time = 0;
  44. const char* _initialisation_blob[5] = {
  45. "sso, Stream1, COM1, PVTGeodetic+DOP+ReceiverStatus+VelCovGeodetic, msec100\n",
  46. "srd, Moderate, UAV\n",
  47. "sem, PVT, 5\n",
  48. "spm, Rover, all\n",
  49. "sso, Stream2, Dsk1, postprocess+event+comment+ReceiverStatus, msec100\n"};
  50. uint32_t _config_last_ack_time;
  51. const char* _port_enable = "\nSSSSSSSSSS\n";
  52. uint32_t crc_error_counter = 0;
  53. uint32_t RxState;
  54. uint32_t RxError;
  55. void mount_disk(void) const;
  56. void unmount_disk(void) const;
  57. bool _has_been_armed;
  58. enum sbf_ids {
  59. DOP = 4001,
  60. PVTGeodetic = 4007,
  61. ReceiverStatus = 4014,
  62. VelCovGeodetic = 5908
  63. };
  64. struct PACKED msg4007 // PVTGeodetic
  65. {
  66. uint32_t TOW;
  67. uint16_t WNc;
  68. uint8_t Mode;
  69. uint8_t Error;
  70. double Latitude;
  71. double Longitude;
  72. double Height;
  73. float Undulation;
  74. float Vn;
  75. float Ve;
  76. float Vu;
  77. float COG;
  78. double RxClkBias;
  79. float RxClkDrift;
  80. uint8_t TimeSystem;
  81. uint8_t Datum;
  82. uint8_t NrSV;
  83. uint8_t WACorrInfo;
  84. uint16_t ReferenceID;
  85. uint16_t MeanCorrAge;
  86. uint32_t SignalInfo;
  87. uint8_t AlertFlag;
  88. // rev1
  89. uint8_t NrBases;
  90. uint16_t PPPInfo;
  91. // rev2
  92. uint16_t Latency;
  93. uint16_t HAccuracy;
  94. uint16_t VAccuracy;
  95. uint8_t Misc;
  96. };
  97. struct PACKED msg4001 // DOP
  98. {
  99. uint32_t TOW;
  100. uint16_t WNc;
  101. uint8_t NrSV;
  102. uint8_t Reserved;
  103. uint16_t PDOP;
  104. uint16_t TDOP;
  105. uint16_t HDOP;
  106. uint16_t VDOP;
  107. float HPL;
  108. float VPL;
  109. };
  110. struct PACKED msg4014 // ReceiverStatus (v2)
  111. {
  112. uint32_t TOW;
  113. uint16_t WNc;
  114. uint8_t CPULoad;
  115. uint8_t ExtError;
  116. uint32_t UpTime;
  117. uint32_t RxState;
  118. uint32_t RxError;
  119. // remaining data is AGCData, which we don't have a use for, don't extract the data
  120. };
  121. struct PACKED msg5908 // VelCovGeodetic
  122. {
  123. uint32_t TOW;
  124. uint16_t WNc;
  125. uint8_t Mode;
  126. uint8_t Error;
  127. float Cov_VnVn;
  128. float Cov_VeVe;
  129. float Cov_VuVu;
  130. float Cov_DtDt;
  131. float Cov_VnVe;
  132. float Cov_VnVu;
  133. float Cov_VnDt;
  134. float Cov_VeVu;
  135. float Cov_VeDt;
  136. float Cov_VuDt;
  137. };
  138. union PACKED msgbuffer {
  139. msg4007 msg4007u;
  140. msg4001 msg4001u;
  141. msg4014 msg4014u;
  142. msg5908 msg5908u;
  143. uint8_t bytes[256];
  144. };
  145. struct sbf_msg_parser_t
  146. {
  147. enum
  148. {
  149. PREAMBLE1 = 0,
  150. PREAMBLE2,
  151. CRC1,
  152. CRC2,
  153. BLOCKID1,
  154. BLOCKID2,
  155. LENGTH1,
  156. LENGTH2,
  157. DATA,
  158. COMMAND_LINE // used to parse command responses
  159. } sbf_state;
  160. uint16_t preamble;
  161. uint16_t crc;
  162. uint16_t blockid;
  163. uint16_t length;
  164. msgbuffer data;
  165. uint16_t read;
  166. } sbf_msg;
  167. enum {
  168. SOFTWARE = (1 << 3), // set upon detection of a software warning or error. This bit is reset by the command lif, error
  169. WATCHDOG = (1 << 4), // set when the watch-dog expired at least once since the last power-on.
  170. CONGESTION = (1 << 6), // set when an output data congestion has been detected on at least one of the communication ports of the receiver during the last second.
  171. MISSEDEVENT = (1 << 8), // set when an external event congestion has been detected during the last second. It indicates that the receiver is receiving too many events on its EVENTx pins.
  172. CPUOVERLOAD = (1 << 9), // set when the CPU load is larger than 90%. If this bit is set, receiver operation may be unreliable and the user must decrease the processing load by following the recommendations in the User Manual.
  173. INVALIDCONFIG = (1 << 10), // set if one or more configuration file (permission or channel configuration) is invalid or absent.
  174. OUTOFGEOFENCE = (1 << 11), // set if the receiver is currently out of its permitted region of operation (geo-fencing).
  175. };
  176. };