AP_GPS_ERB.h 5.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155
  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. // Emlid Reach Binary (ERB) GPS driver for ArduPilot.
  15. // ERB protocol: http://files.emlid.com/ERB.pdf
  16. #pragma once
  17. #include <AP_HAL/AP_HAL.h>
  18. #include "AP_GPS.h"
  19. #include "GPS_Backend.h"
  20. class AP_GPS_ERB : public AP_GPS_Backend
  21. {
  22. public:
  23. using AP_GPS_Backend::AP_GPS_Backend;
  24. // Methods
  25. bool read() override;
  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. static bool _detect(struct ERB_detect_state &state, uint8_t data);
  29. const char *name() const override { return "ERB"; }
  30. private:
  31. struct PACKED erb_header {
  32. uint8_t preamble1;
  33. uint8_t preamble2;
  34. uint8_t msg_id;
  35. uint16_t length;
  36. };
  37. struct PACKED erb_ver {
  38. uint32_t time; ///< GPS time of week of the navigation epoch [ms]
  39. uint8_t ver_high;
  40. uint8_t ver_medium;
  41. uint8_t ver_low;
  42. };
  43. struct PACKED erb_pos {
  44. uint32_t time; ///< GPS time of week of the navigation epoch [ms]
  45. double longitude;
  46. double latitude;
  47. double altitude_ellipsoid; ///< Height above ellipsoid [m]
  48. double altitude_msl; ///< Height above mean sea level [m]
  49. uint32_t horizontal_accuracy; ///< Horizontal accuracy estimate [mm]
  50. uint32_t vertical_accuracy; ///< Vertical accuracy estimate [mm]
  51. };
  52. struct PACKED erb_stat {
  53. uint32_t time; ///< GPS time of week of the navigation epoch [ms]
  54. uint16_t week;
  55. uint8_t fix_type; ///< see erb_fix_type enum
  56. uint8_t fix_status;
  57. uint8_t satellites;
  58. };
  59. struct PACKED erb_dops {
  60. uint32_t time; ///< GPS time of week of the navigation epoch [ms]
  61. uint16_t gDOP; ///< Geometric DOP
  62. uint16_t pDOP; ///< Position DOP
  63. uint16_t vDOP; ///< Vertical DOP
  64. uint16_t hDOP; ///< Horizontal DOP
  65. };
  66. struct PACKED erb_vel {
  67. uint32_t time; ///< GPS time of week of the navigation epoch [ms]
  68. int32_t vel_north; ///< North velocity component [cm/s]
  69. int32_t vel_east; ///< East velocity component [cm/s]
  70. int32_t vel_down; ///< Down velocity component [cm/s]
  71. uint32_t speed_2d; ///< Ground speed (2-D) [cm/s]
  72. int32_t heading_2d; ///< Heading of motion 2-D [1e5 deg]
  73. uint32_t speed_accuracy; ///< Speed accuracy Estimate [cm/s]
  74. };
  75. struct PACKED erb_rtk {
  76. uint8_t base_num_sats; ///< Current number of satellites used for RTK calculation
  77. uint16_t age_cs; ///< Age of the corrections in centiseconds (0 when no corrections, 0xFFFF indicates overflow)
  78. int32_t baseline_N_mm; ///< distance between base and rover along the north axis in millimeters
  79. int32_t baseline_E_mm; ///< distance between base and rover along the east axis in millimeters
  80. int32_t baseline_D_mm; ///< distance between base and rover along the down axis in millimeters
  81. uint16_t ar_ratio; ///< AR ratio multiplied by 10
  82. uint16_t base_week_number; ///< GPS Week Number of last baseline
  83. uint32_t base_time_week_ms; ///< GPS Time of Week of last baseline in milliseconds
  84. };
  85. // Receive buffer
  86. union PACKED {
  87. DEFINE_BYTE_ARRAY_METHODS
  88. erb_ver ver;
  89. erb_pos pos;
  90. erb_stat stat;
  91. erb_dops dops;
  92. erb_vel vel;
  93. erb_rtk rtk;
  94. } _buffer;
  95. enum erb_protocol_bytes {
  96. PREAMBLE1 = 0x45,
  97. PREAMBLE2 = 0x52,
  98. MSG_VER = 0x01,
  99. MSG_POS = 0x02,
  100. MSG_STAT = 0x03,
  101. MSG_DOPS = 0x04,
  102. MSG_VEL = 0x05,
  103. MSG_RTK = 0x07,
  104. };
  105. enum erb_fix_type {
  106. FIX_NONE = 0x00,
  107. FIX_SINGLE = 0x01,
  108. FIX_FLOAT = 0x02,
  109. FIX_FIX = 0x03,
  110. };
  111. // Packet checksum accumulators
  112. uint8_t _ck_a;
  113. uint8_t _ck_b;
  114. // State machine state
  115. uint8_t _step;
  116. uint8_t _msg_id;
  117. uint16_t _payload_length;
  118. uint16_t _payload_counter;
  119. // 8 bit count of fix messages processed, used for periodic processing
  120. uint8_t _fix_count;
  121. uint32_t _last_pos_time;
  122. uint32_t _last_vel_time;
  123. // do we have new position information?
  124. bool _new_position:1;
  125. // do we have new speed information?
  126. bool _new_speed:1;
  127. // Buffer parse & GPS state update
  128. bool _parse_gps();
  129. // used to update fix between status and position packets
  130. AP_GPS::GPS_Status next_fix = AP_GPS::NO_FIX;
  131. };