GPS_Backend.h 3.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110
  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. GPS driver backend class
  15. */
  16. #pragma once
  17. #include <GCS_MAVLink/GCS_MAVLink.h>
  18. #include <AP_RTC/JitterCorrection.h>
  19. #include "AP_GPS.h"
  20. class AP_GPS_Backend
  21. {
  22. public:
  23. AP_GPS_Backend(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
  24. // we declare a virtual destructor so that GPS drivers can
  25. // override with a custom destructor if need be.
  26. virtual ~AP_GPS_Backend(void) {}
  27. // The read() method is the only one needed in each driver. It
  28. // should return true when the backend has successfully received a
  29. // valid packet from the GPS.
  30. virtual bool read() = 0;
  31. // Highest status supported by this GPS.
  32. // Allows external system to identify type of receiver connected.
  33. virtual AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D; }
  34. virtual bool is_configured(void) { return true; }
  35. virtual void inject_data(const uint8_t *data, uint16_t len);
  36. //MAVLink methods
  37. virtual bool supports_mavlink_gps_rtk_message() { return false; }
  38. virtual void send_mavlink_gps_rtk(mavlink_channel_t chan);
  39. virtual void broadcast_configuration_failure_reason(void) const { return ; }
  40. virtual void handle_msg(const mavlink_message_t &msg) { return ; }
  41. // driver specific lag, returns true if the driver is confident in the provided lag
  42. virtual bool get_lag(float &lag) const { lag = 0.2f; return true; }
  43. // driver specific health, returns true if the driver is healthy
  44. virtual bool is_healthy(void) const { return true; }
  45. virtual const char *name() const = 0;
  46. void broadcast_gps_type() const;
  47. virtual void Write_AP_Logger_Log_Startup_messages() const;
  48. virtual bool prepare_for_arming(void) { return true; }
  49. protected:
  50. AP_HAL::UARTDriver *port; ///< UART we are attached to
  51. AP_GPS &gps; ///< access to frontend (for parameters)
  52. AP_GPS::GPS_State &state; ///< public state for this instance
  53. // common utility functions
  54. int32_t swap_int32(int32_t v) const;
  55. int16_t swap_int16(int16_t v) const;
  56. /*
  57. fill in 3D velocity from 2D components
  58. */
  59. void fill_3d_velocity(void);
  60. /*
  61. fill in time_week_ms and time_week from BCD date and time components
  62. assumes MTK19 millisecond form of bcd_time
  63. */
  64. void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds);
  65. void _detection_message(char *buffer, uint8_t buflen) const;
  66. bool should_log() const;
  67. /*
  68. set a timestamp based on arrival time on uart at current byte,
  69. assuming the message started nbytes ago
  70. */
  71. void set_uart_timestamp(uint16_t nbytes);
  72. void check_new_itow(uint32_t itow, uint32_t msg_length);
  73. private:
  74. // itow from previous message
  75. uint32_t _last_itow;
  76. uint64_t _pseudo_itow;
  77. uint32_t _last_ms;
  78. uint32_t _rate_ms;
  79. uint32_t _last_rate_ms;
  80. uint16_t _rate_counter;
  81. JitterCorrection jitter_correction;
  82. };