AP_GPS.h 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581
  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. #pragma once
  14. #include <AP_HAL/AP_HAL.h>
  15. #include <inttypes.h>
  16. #include <AP_Common/AP_Common.h>
  17. #include <AP_Common/Location.h>
  18. #include <AP_Param/AP_Param.h>
  19. #include "GPS_detect_state.h"
  20. #include <AP_SerialManager/AP_SerialManager.h>
  21. /**
  22. maximum number of GPS instances available on this platform. If more
  23. than 1 then redundant sensors may be available
  24. */
  25. #ifndef GPS_MAX_RECEIVERS
  26. #define GPS_MAX_RECEIVERS 2 // maximum number of physical GPS sensors allowed - does not include virtual GPS created by blending receiver data
  27. #endif
  28. #ifndef GPS_MAX_INSTANCES
  29. #define GPS_MAX_INSTANCES (GPS_MAX_RECEIVERS + 1) // maximum number of GPS instances including the 'virtual' GPS created by blending receiver data
  30. #endif
  31. #if GPS_MAX_INSTANCES > GPS_MAX_RECEIVERS
  32. #define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2)
  33. #endif
  34. #define GPS_UNKNOWN_DOP UINT16_MAX // set unknown DOP's to maximum value, which is also correct for MAVLink
  35. // the number of GPS leap seconds
  36. #define GPS_LEAPSECONDS_MILLIS 18000ULL
  37. #define UNIX_OFFSET_MSEC (17000ULL * 86400ULL + 52ULL * 10ULL * AP_MSEC_PER_WEEK - GPS_LEAPSECONDS_MILLIS)
  38. class AP_GPS_Backend;
  39. /// @class AP_GPS
  40. /// GPS driver main class
  41. class AP_GPS
  42. {
  43. friend class AP_GPS_ERB;
  44. friend class AP_GPS_GSOF;
  45. friend class AP_GPS_MAV;
  46. friend class AP_GPS_MTK;
  47. friend class AP_GPS_MTK19;
  48. friend class AP_GPS_NMEA;
  49. friend class AP_GPS_NOVA;
  50. friend class AP_GPS_PX4;
  51. friend class AP_GPS_SBF;
  52. friend class AP_GPS_SBP;
  53. friend class AP_GPS_SBP2;
  54. friend class AP_GPS_SIRF;
  55. friend class AP_GPS_UBLOX;
  56. friend class AP_GPS_Backend;
  57. public:
  58. AP_GPS();
  59. /* Do not allow copies */
  60. AP_GPS(const AP_GPS &other) = delete;
  61. AP_GPS &operator=(const AP_GPS&) = delete;
  62. static AP_GPS *get_singleton() {
  63. return _singleton;
  64. }
  65. // GPS driver types
  66. enum GPS_Type {
  67. GPS_TYPE_NONE = 0,
  68. GPS_TYPE_AUTO = 1,
  69. GPS_TYPE_UBLOX = 2,
  70. GPS_TYPE_MTK = 3,
  71. GPS_TYPE_MTK19 = 4,
  72. GPS_TYPE_NMEA = 5,
  73. GPS_TYPE_SIRF = 6,
  74. GPS_TYPE_HIL = 7,
  75. GPS_TYPE_SBP = 8,
  76. GPS_TYPE_UAVCAN = 9,
  77. GPS_TYPE_SBF = 10,
  78. GPS_TYPE_GSOF = 11,
  79. GPS_TYPE_ERB = 13,
  80. GPS_TYPE_MAV = 14,
  81. GPS_TYPE_NOVA = 15,
  82. GPS_TYPE_HEMI = 16, // hemisphere NMEA
  83. };
  84. /// GPS status codes
  85. enum GPS_Status {
  86. NO_GPS = GPS_FIX_TYPE_NO_GPS, ///< No GPS connected/detected
  87. NO_FIX = GPS_FIX_TYPE_NO_FIX, ///< Receiving valid GPS messages but no lock
  88. GPS_OK_FIX_2D = GPS_FIX_TYPE_2D_FIX, ///< Receiving valid messages and 2D lock
  89. GPS_OK_FIX_3D = GPS_FIX_TYPE_3D_FIX, ///< Receiving valid messages and 3D lock
  90. GPS_OK_FIX_3D_DGPS = GPS_FIX_TYPE_DGPS, ///< Receiving valid messages and 3D lock with differential improvements
  91. GPS_OK_FIX_3D_RTK_FLOAT = GPS_FIX_TYPE_RTK_FLOAT, ///< Receiving valid messages and 3D RTK Float
  92. GPS_OK_FIX_3D_RTK_FIXED = GPS_FIX_TYPE_RTK_FIXED, ///< Receiving valid messages and 3D RTK Fixed
  93. };
  94. // GPS navigation engine settings. Not all GPS receivers support
  95. // this
  96. enum GPS_Engine_Setting {
  97. GPS_ENGINE_NONE = -1,
  98. GPS_ENGINE_PORTABLE = 0,
  99. GPS_ENGINE_STATIONARY = 2,
  100. GPS_ENGINE_PEDESTRIAN = 3,
  101. GPS_ENGINE_AUTOMOTIVE = 4,
  102. GPS_ENGINE_SEA = 5,
  103. GPS_ENGINE_AIRBORNE_1G = 6,
  104. GPS_ENGINE_AIRBORNE_2G = 7,
  105. GPS_ENGINE_AIRBORNE_4G = 8
  106. };
  107. enum GPS_Config {
  108. GPS_ALL_CONFIGURED = 255
  109. };
  110. /*
  111. The GPS_State structure is filled in by the backend driver as it
  112. parses each message from the GPS.
  113. */
  114. struct GPS_State {
  115. uint8_t instance; // the instance number of this GPS
  116. // all the following fields must all be filled by the backend driver
  117. GPS_Status status; ///< driver fix status
  118. uint32_t time_week_ms; ///< GPS time (milliseconds from start of GPS week)
  119. uint16_t time_week; ///< GPS week number
  120. Location location; ///< last fix location
  121. float ground_speed; ///< ground speed in m/sec
  122. float ground_course; ///< ground course in degrees
  123. float gps_yaw; ///< GPS derived yaw information, if available (degrees)
  124. uint16_t hdop; ///< horizontal dilution of precision in cm
  125. uint16_t vdop; ///< vertical dilution of precision in cm
  126. uint8_t num_sats; ///< Number of visible satellites
  127. Vector3f velocity; ///< 3D velocity in m/s, in NED format
  128. float speed_accuracy; ///< 3D velocity RMS accuracy estimate in m/s
  129. float horizontal_accuracy; ///< horizontal RMS accuracy estimate in m
  130. float vertical_accuracy; ///< vertical RMS accuracy estimate in m
  131. bool have_vertical_velocity; ///< does GPS give vertical velocity? Set to true only once available.
  132. bool have_speed_accuracy; ///< does GPS give speed accuracy? Set to true only once available.
  133. bool have_horizontal_accuracy; ///< does GPS give horizontal position accuracy? Set to true only once available.
  134. bool have_vertical_accuracy; ///< does GPS give vertical position accuracy? Set to true only once available.
  135. bool have_gps_yaw; ///< does GPS give yaw? Set to true only once available.
  136. uint32_t last_gps_time_ms; ///< the system time we got the last GPS timestamp, milliseconds
  137. uint32_t uart_timestamp_ms; ///< optional timestamp from set_uart_timestamp()
  138. // all the following fields must only all be filled by RTK capable backend drivers
  139. uint32_t rtk_time_week_ms; ///< GPS Time of Week of last baseline in milliseconds
  140. uint16_t rtk_week_number; ///< GPS Week Number of last baseline
  141. uint32_t rtk_age_ms; ///< GPS age of last baseline correction in milliseconds (0 when no corrections, 0xFFFFFFFF indicates overflow)
  142. uint8_t rtk_num_sats; ///< Current number of satellites used for RTK calculation
  143. uint8_t rtk_baseline_coords_type; ///< Coordinate system of baseline. 0 == ECEF, 1 == NED
  144. int32_t rtk_baseline_x_mm; ///< Current baseline in ECEF x or NED north component in mm
  145. int32_t rtk_baseline_y_mm; ///< Current baseline in ECEF y or NED east component in mm
  146. int32_t rtk_baseline_z_mm; ///< Current baseline in ECEF z or NED down component in mm
  147. uint32_t rtk_accuracy; ///< Current estimate of 3D baseline accuracy (receiver dependent, typical 0 to 9999)
  148. int32_t rtk_iar_num_hypotheses; ///< Current number of integer ambiguity hypotheses
  149. };
  150. /// Startup initialisation.
  151. void init(const AP_SerialManager& serial_manager);
  152. /// Update GPS state based on possible bytes received from the module.
  153. /// This routine must be called periodically (typically at 10Hz or
  154. /// more) to process incoming data.
  155. void update(void);
  156. // Pass mavlink data to message handlers (for MAV type)
  157. void handle_msg(const mavlink_message_t &msg);
  158. // Accessor functions
  159. // return number of active GPS sensors. Note that if the first GPS
  160. // is not present but the 2nd is then we return 2. Note that a blended
  161. // GPS solution is treated as an additional sensor.
  162. uint8_t num_sensors(void) const;
  163. // Return the index of the primary sensor which is the index of the sensor contributing to
  164. // the output. A blended solution is available as an additional instance
  165. uint8_t primary_sensor(void) const {
  166. return primary_instance;
  167. }
  168. /// Query GPS status
  169. GPS_Status status(uint8_t instance) const {
  170. if (_force_disable_gps && state[instance].status > NO_FIX) {
  171. return NO_FIX;
  172. }
  173. return state[instance].status;
  174. }
  175. GPS_Status status(void) const {
  176. return status(primary_instance);
  177. }
  178. // Query the highest status this GPS supports (always reports GPS_OK_FIX_3D for the blended GPS)
  179. GPS_Status highest_supported_status(uint8_t instance) const;
  180. // location of last fix
  181. const Location &location(uint8_t instance) const {
  182. return state[instance].location;
  183. }
  184. const Location &location() const {
  185. return location(primary_instance);
  186. }
  187. // report speed accuracy
  188. bool speed_accuracy(uint8_t instance, float &sacc) const;
  189. bool speed_accuracy(float &sacc) const {
  190. return speed_accuracy(primary_instance, sacc);
  191. }
  192. bool horizontal_accuracy(uint8_t instance, float &hacc) const;
  193. bool horizontal_accuracy(float &hacc) const {
  194. return horizontal_accuracy(primary_instance, hacc);
  195. }
  196. bool vertical_accuracy(uint8_t instance, float &vacc) const;
  197. bool vertical_accuracy(float &vacc) const {
  198. return vertical_accuracy(primary_instance, vacc);
  199. }
  200. // 3D velocity in NED format
  201. const Vector3f &velocity(uint8_t instance) const {
  202. return state[instance].velocity;
  203. }
  204. const Vector3f &velocity() const {
  205. return velocity(primary_instance);
  206. }
  207. // ground speed in m/s
  208. float ground_speed(uint8_t instance) const {
  209. return state[instance].ground_speed;
  210. }
  211. float ground_speed() const {
  212. return ground_speed(primary_instance);
  213. }
  214. // ground speed in cm/s
  215. uint32_t ground_speed_cm(void) {
  216. return ground_speed() * 100;
  217. }
  218. // ground course in degrees
  219. float ground_course(uint8_t instance) const {
  220. return state[instance].ground_course;
  221. }
  222. float ground_course() const {
  223. return ground_course(primary_instance);
  224. }
  225. // ground course in centi-degrees
  226. int32_t ground_course_cd(uint8_t instance) const {
  227. return ground_course(instance) * 100;
  228. }
  229. int32_t ground_course_cd() const {
  230. return ground_course_cd(primary_instance);
  231. }
  232. // yaw in degrees if available
  233. bool gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg) const {
  234. if (!have_gps_yaw(instance)) {
  235. return false;
  236. }
  237. yaw_deg = state[instance].gps_yaw;
  238. // None of the GPS backends can provide this yet, so we hard
  239. // code a fixed value of 10 degrees, which seems like a
  240. // reasonable guess. Once a backend can provide a proper
  241. // estimate we can implement it
  242. accuracy_deg = 10;
  243. return true;
  244. }
  245. bool gps_yaw_deg(float &yaw_deg, float &accuracy_deg) const {
  246. return gps_yaw_deg(primary_instance, yaw_deg, accuracy_deg);
  247. }
  248. // number of locked satellites
  249. uint8_t num_sats(uint8_t instance) const {
  250. return state[instance].num_sats;
  251. }
  252. uint8_t num_sats() const {
  253. return num_sats(primary_instance);
  254. }
  255. // GPS time of week in milliseconds
  256. uint32_t time_week_ms(uint8_t instance) const {
  257. return state[instance].time_week_ms;
  258. }
  259. uint32_t time_week_ms() const {
  260. return time_week_ms(primary_instance);
  261. }
  262. // GPS week
  263. uint16_t time_week(uint8_t instance) const {
  264. return state[instance].time_week;
  265. }
  266. uint16_t time_week() const {
  267. return time_week(primary_instance);
  268. }
  269. // horizontal dilution of precision
  270. uint16_t get_hdop(uint8_t instance) const {
  271. return state[instance].hdop;
  272. }
  273. uint16_t get_hdop() const {
  274. return get_hdop(primary_instance);
  275. }
  276. // vertical dilution of precision
  277. uint16_t get_vdop(uint8_t instance) const {
  278. return state[instance].vdop;
  279. }
  280. uint16_t get_vdop() const {
  281. return get_vdop(primary_instance);
  282. }
  283. // the time we got our last fix in system milliseconds. This is
  284. // used when calculating how far we might have moved since that fix
  285. uint32_t last_fix_time_ms(uint8_t instance) const {
  286. return timing[instance].last_fix_time_ms;
  287. }
  288. uint32_t last_fix_time_ms(void) const {
  289. return last_fix_time_ms(primary_instance);
  290. }
  291. // the time we last processed a message in milliseconds. This is
  292. // used to indicate that we have new GPS data to process
  293. uint32_t last_message_time_ms(uint8_t instance) const {
  294. return timing[instance].last_message_time_ms;
  295. }
  296. uint32_t last_message_time_ms(void) const {
  297. return last_message_time_ms(primary_instance);
  298. }
  299. // system time delta between the last two reported positions
  300. uint16_t last_message_delta_time_ms(uint8_t instance) const {
  301. return timing[instance].delta_time_ms;
  302. }
  303. uint16_t last_message_delta_time_ms(void) const {
  304. return last_message_delta_time_ms(primary_instance);
  305. }
  306. // return true if the GPS supports vertical velocity values
  307. bool have_vertical_velocity(uint8_t instance) const {
  308. return state[instance].have_vertical_velocity;
  309. }
  310. bool have_vertical_velocity(void) const {
  311. return have_vertical_velocity(primary_instance);
  312. }
  313. // return true if the GPS supports yaw
  314. bool have_gps_yaw(uint8_t instance) const {
  315. return state[instance].have_gps_yaw;
  316. }
  317. bool have_gps_yaw(void) const {
  318. return have_gps_yaw(primary_instance);
  319. }
  320. // the expected lag (in seconds) in the position and velocity readings from the gps
  321. // return true if the GPS hardware configuration is known or the lag parameter has been set manually
  322. bool get_lag(uint8_t instance, float &lag_sec) const;
  323. bool get_lag(float &lag_sec) const {
  324. return get_lag(primary_instance, lag_sec);
  325. }
  326. // return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin
  327. const Vector3f &get_antenna_offset(uint8_t instance) const;
  328. // set position for HIL
  329. void setHIL(uint8_t instance, GPS_Status status, uint64_t time_epoch_ms,
  330. const Location &location, const Vector3f &velocity, uint8_t num_sats,
  331. uint16_t hdop);
  332. // set accuracy for HIL
  333. void setHIL_Accuracy(uint8_t instance, float vdop, float hacc, float vacc, float sacc, bool _have_vertical_velocity, uint32_t sample_ms);
  334. // lock out a GPS port, allowing another application to use the port
  335. void lock_port(uint8_t instance, bool locked);
  336. //MAVLink Status Sending
  337. void send_mavlink_gps_raw(mavlink_channel_t chan);
  338. void send_mavlink_gps2_raw(mavlink_channel_t chan);
  339. void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst);
  340. // Returns true if there is an unconfigured GPS, and provides the instance number of the first non configured GPS
  341. bool first_unconfigured_gps(uint8_t &instance) const WARN_IF_UNUSED;
  342. void broadcast_first_configuration_failure_reason(void) const;
  343. // pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned
  344. bool all_consistent(float &distance) const;
  345. // pre-arm check of GPS blending. False if blending is unhealthy, True if healthy or blending is not being used
  346. bool blend_health_check() const;
  347. // handle sending of initialisation strings to the GPS - only used by backends
  348. void send_blob_start(uint8_t instance, const char *_blob, uint16_t size);
  349. void send_blob_update(uint8_t instance);
  350. // return last fix time since the 1/1/1970 in microseconds
  351. uint64_t time_epoch_usec(uint8_t instance) const;
  352. uint64_t time_epoch_usec(void) const {
  353. return time_epoch_usec(primary_instance);
  354. }
  355. // convert GPS week and millis to unix epoch in ms
  356. static uint64_t time_epoch_convert(uint16_t gps_week, uint32_t gps_ms);
  357. static const struct AP_Param::GroupInfo var_info[];
  358. void Write_AP_Logger_Log_Startup_messages();
  359. // indicate which bit in LOG_BITMASK indicates gps logging enabled
  360. void set_log_gps_bit(uint32_t bit) { _log_gps_bit = bit; }
  361. // report if the gps is healthy (this is defined as existing, an update at a rate greater than 4Hz,
  362. // as well as any driver specific behaviour)
  363. bool is_healthy(uint8_t instance) const;
  364. bool is_healthy(void) const { return is_healthy(primary_instance); }
  365. // returns true if all GPS instances have passed all final arming checks/state changes
  366. bool prepare_for_arming(void);
  367. // used to disable GPS for GPS failure testing in flight
  368. void force_disable(bool disable) {
  369. _force_disable_gps = disable;
  370. }
  371. protected:
  372. // configuration parameters
  373. AP_Int8 _type[GPS_MAX_RECEIVERS];
  374. AP_Int8 _navfilter;
  375. AP_Int8 _auto_switch;
  376. AP_Int8 _min_dgps;
  377. AP_Int16 _sbp_logmask;
  378. AP_Int8 _inject_to;
  379. uint32_t _last_instance_swap_ms;
  380. AP_Int8 _sbas_mode;
  381. AP_Int8 _min_elevation;
  382. AP_Int8 _raw_data;
  383. AP_Int8 _gnss_mode[GPS_MAX_RECEIVERS];
  384. AP_Int16 _rate_ms[GPS_MAX_RECEIVERS]; // this parameter should always be accessed using get_rate_ms()
  385. AP_Int8 _save_config;
  386. AP_Int8 _auto_config;
  387. AP_Vector3f _antenna_offset[GPS_MAX_RECEIVERS];
  388. AP_Int16 _delay_ms[GPS_MAX_RECEIVERS];
  389. AP_Int8 _blend_mask;
  390. AP_Float _blend_tc;
  391. uint32_t _log_gps_bit = -1;
  392. private:
  393. static AP_GPS *_singleton;
  394. // returns the desired gps update rate in milliseconds
  395. // this does not provide any guarantee that the GPS is updating at the requested
  396. // rate it is simply a helper for use in the backends for determining what rate
  397. // they should be configuring the GPS to run at
  398. uint16_t get_rate_ms(uint8_t instance) const;
  399. struct GPS_timing {
  400. // the time we got our last fix in system milliseconds
  401. uint32_t last_fix_time_ms;
  402. // the time we got our last message in system milliseconds
  403. uint32_t last_message_time_ms;
  404. // delta time between the last pair of GPS updates in system milliseconds
  405. uint16_t delta_time_ms;
  406. };
  407. // Note allowance for an additional instance to contain blended data
  408. GPS_timing timing[GPS_MAX_INSTANCES];
  409. GPS_State state[GPS_MAX_INSTANCES];
  410. AP_GPS_Backend *drivers[GPS_MAX_RECEIVERS];
  411. AP_HAL::UARTDriver *_port[GPS_MAX_RECEIVERS];
  412. /// primary GPS instance
  413. uint8_t primary_instance;
  414. /// number of GPS instances present
  415. uint8_t num_instances;
  416. // which ports are locked
  417. uint8_t locked_ports;
  418. // state of auto-detection process, per instance
  419. struct detect_state {
  420. uint32_t last_baud_change_ms;
  421. uint8_t current_baud;
  422. bool auto_detected_baud;
  423. struct UBLOX_detect_state ublox_detect_state;
  424. struct MTK_detect_state mtk_detect_state;
  425. struct MTK19_detect_state mtk19_detect_state;
  426. struct SIRF_detect_state sirf_detect_state;
  427. struct NMEA_detect_state nmea_detect_state;
  428. struct SBP_detect_state sbp_detect_state;
  429. struct SBP2_detect_state sbp2_detect_state;
  430. struct ERB_detect_state erb_detect_state;
  431. } detect_state[GPS_MAX_RECEIVERS];
  432. struct {
  433. const char *blob;
  434. uint16_t remaining;
  435. } initblob_state[GPS_MAX_RECEIVERS];
  436. static const uint32_t _baudrates[];
  437. static const char _initialisation_blob[];
  438. static const char _initialisation_raw_blob[];
  439. void detect_instance(uint8_t instance);
  440. void update_instance(uint8_t instance);
  441. /*
  442. buffer for re-assembling RTCM data for GPS injection.
  443. The 8 bit flags field in GPS_RTCM_DATA is interpreted as:
  444. 1 bit for "is fragmented"
  445. 2 bits for fragment number
  446. 5 bits for sequence number
  447. The rtcm_buffer is allocated on first use. Once a block of data
  448. is successfully reassembled it is injected into all active GPS
  449. backends. This assumes we don't want more than 4*180=720 bytes
  450. in a RTCM data block
  451. */
  452. struct rtcm_buffer {
  453. uint8_t fragments_received;
  454. uint8_t sequence;
  455. uint8_t fragment_count;
  456. uint16_t total_length;
  457. uint8_t buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*4];
  458. } *rtcm_buffer;
  459. // re-assemble GPS_RTCM_DATA message
  460. void handle_gps_rtcm_data(const mavlink_message_t &msg);
  461. void handle_gps_inject(const mavlink_message_t &msg);
  462. //Inject a packet of raw binary to a GPS
  463. void inject_data(uint8_t *data, uint16_t len);
  464. void inject_data(uint8_t instance, uint8_t *data, uint16_t len);
  465. // GPS blending and switching
  466. Vector2f _NE_pos_offset_m[GPS_MAX_RECEIVERS]; // Filtered North,East position offset from GPS instance to blended solution in _output_state.location (m)
  467. float _hgt_offset_cm[GPS_MAX_RECEIVERS]; // Filtered height offset from GPS instance relative to blended solution in _output_state.location (cm)
  468. Vector3f _blended_antenna_offset; // blended antenna offset
  469. float _blended_lag_sec; // blended receiver lag in seconds
  470. float _blend_weights[GPS_MAX_RECEIVERS]; // blend weight for each GPS. The blend weights must sum to 1.0 across all instances.
  471. uint32_t _last_time_updated[GPS_MAX_RECEIVERS]; // the last value of state.last_gps_time_ms read for that GPS instance - used to detect new data.
  472. float _omega_lpf; // cutoff frequency in rad/sec of LPF applied to position offsets
  473. bool _output_is_blended; // true when a blended GPS solution being output
  474. uint8_t _blend_health_counter; // 0 = perfectly health, 100 = very unhealthy
  475. // calculate the blend weight. Returns true if blend could be calculated, false if not
  476. bool calc_blend_weights(void);
  477. // calculate the blended state
  478. void calc_blended_state(void);
  479. bool should_log() const;
  480. // Auto configure types
  481. enum GPS_AUTO_CONFIG {
  482. GPS_AUTO_CONFIG_DISABLE = 0,
  483. GPS_AUTO_CONFIG_ENABLE = 1
  484. };
  485. // used for flight testing with GPS loss
  486. bool _force_disable_gps;
  487. };
  488. namespace AP {
  489. AP_GPS &gps();
  490. };