AP_GPS_SIRF.h 2.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  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. // SiRF Binary GPS driver for ArduPilot and ArduPilotMega.
  15. // Code by Michael Smith.
  16. //
  17. #pragma once
  18. #include <AP_Common/AP_Common.h>
  19. #include <AP_HAL/AP_HAL.h>
  20. #include "AP_GPS.h"
  21. #include "GPS_Backend.h"
  22. #define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C\r\n"
  23. class AP_GPS_SIRF : public AP_GPS_Backend {
  24. public:
  25. AP_GPS_SIRF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
  26. bool read() override;
  27. static bool _detect(struct SIRF_detect_state &state, uint8_t data);
  28. const char *name() const override { return "SIRF"; }
  29. private:
  30. struct PACKED sirf_geonav {
  31. uint16_t fix_invalid;
  32. uint16_t fix_type;
  33. uint16_t week;
  34. uint32_t time;
  35. uint16_t year;
  36. uint8_t month;
  37. uint8_t day;
  38. uint8_t hour;
  39. uint8_t minute;
  40. uint16_t second;
  41. uint32_t satellites_used;
  42. int32_t latitude;
  43. int32_t longitude;
  44. int32_t altitude_ellipsoid;
  45. int32_t altitude_msl;
  46. int8_t map_datum;
  47. int16_t ground_speed;
  48. int16_t ground_course;
  49. int16_t res1;
  50. int16_t climb_rate;
  51. uint16_t heading_rate;
  52. uint32_t horizontal_position_error;
  53. uint32_t vertical_position_error;
  54. uint32_t time_error;
  55. int16_t horizontal_velocity_error;
  56. int32_t clock_bias;
  57. uint32_t clock_bias_error;
  58. int32_t clock_drift;
  59. uint32_t clock_drift_error;
  60. uint32_t distance;
  61. uint16_t distance_error;
  62. uint16_t heading_error;
  63. uint8_t satellites;
  64. uint8_t hdop;
  65. uint8_t mode_info;
  66. };
  67. enum sirf_protocol_bytes {
  68. PREAMBLE1 = 0xa0,
  69. PREAMBLE2 = 0xa2,
  70. POSTAMBLE1 = 0xb0,
  71. POSTAMBLE2 = 0xb3,
  72. MSG_GEONAV = 0x29
  73. };
  74. enum sirf_fix_type {
  75. FIX_3D = 0x6,
  76. FIX_MASK = 0x7
  77. };
  78. // State machine state
  79. uint8_t _step;
  80. uint16_t _checksum;
  81. bool _gather;
  82. uint16_t _payload_length;
  83. uint16_t _payload_counter;
  84. uint8_t _msg_id;
  85. // Message buffer
  86. union {
  87. DEFINE_BYTE_ARRAY_METHODS
  88. sirf_geonav nav;
  89. } _buffer;
  90. bool _parse_gps(void);
  91. void _accumulate(uint8_t val);
  92. static const uint8_t _initialisation_blob[];
  93. };