AP_GPS.cpp 62 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635
  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. #include "AP_GPS.h"
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_HAL/AP_HAL.h>
  16. #include <AP_Math/AP_Math.h>
  17. #include <AP_Notify/AP_Notify.h>
  18. #include <GCS_MAVLink/GCS.h>
  19. #include <AP_BoardConfig/AP_BoardConfig.h>
  20. #include <AP_RTC/AP_RTC.h>
  21. #include <climits>
  22. #include "AP_GPS_NOVA.h"
  23. #include "AP_GPS_ERB.h"
  24. #include "AP_GPS_GSOF.h"
  25. #include "AP_GPS_MTK.h"
  26. #include "AP_GPS_MTK19.h"
  27. #include "AP_GPS_NMEA.h"
  28. #include "AP_GPS_SBF.h"
  29. #include "AP_GPS_SBP.h"
  30. #include "AP_GPS_SBP2.h"
  31. #include "AP_GPS_SIRF.h"
  32. #include "AP_GPS_UBLOX.h"
  33. #include "AP_GPS_MAV.h"
  34. #include "GPS_Backend.h"
  35. #if HAL_WITH_UAVCAN
  36. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  37. #include <AP_UAVCAN/AP_UAVCAN.h>
  38. #include "AP_GPS_UAVCAN.h"
  39. #endif
  40. #include <AP_AHRS/AP_AHRS.h>
  41. #include <AP_Logger/AP_Logger.h>
  42. #define GPS_RTK_INJECT_TO_ALL 127
  43. #define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms
  44. #define GPS_BAUD_TIME_MS 1200
  45. #define GPS_TIMEOUT_MS 4000u
  46. // defines used to specify the mask position for use of different accuracy metrics in the blending algorithm
  47. #define BLEND_MASK_USE_HPOS_ACC 1
  48. #define BLEND_MASK_USE_VPOS_ACC 2
  49. #define BLEND_MASK_USE_SPD_ACC 4
  50. #define BLEND_COUNTER_FAILURE_INCREMENT 10
  51. extern const AP_HAL::HAL &hal;
  52. // baudrates to try to detect GPSes with
  53. const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U};
  54. // initialisation blobs to send to the GPS to try to get it into the
  55. // right mode
  56. const char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY;
  57. AP_GPS *AP_GPS::_singleton;
  58. // table of user settable parameters
  59. const AP_Param::GroupInfo AP_GPS::var_info[] = {
  60. // @Param: TYPE
  61. // @DisplayName: GPS type
  62. // @Description: GPS type
  63. // @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA
  64. // @RebootRequired: True
  65. // @User: Advanced
  66. AP_GROUPINFO("TYPE", 0, AP_GPS, _type[0], HAL_GPS_TYPE_DEFAULT),
  67. #if GPS_MAX_RECEIVERS > 1
  68. // @Param: TYPE2
  69. // @DisplayName: 2nd GPS type
  70. // @Description: GPS type of 2nd GPS
  71. // @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA
  72. // @RebootRequired: True
  73. // @User: Advanced
  74. AP_GROUPINFO("TYPE2", 1, AP_GPS, _type[1], 0),
  75. #endif
  76. // @Param: NAVFILTER
  77. // @DisplayName: Navigation filter setting
  78. // @Description: Navigation filter engine setting
  79. // @Values: 0:Portable,2:Stationary,3:Pedestrian,4:Automotive,5:Sea,6:Airborne1G,7:Airborne2G,8:Airborne4G
  80. // @User: Advanced
  81. AP_GROUPINFO("NAVFILTER", 2, AP_GPS, _navfilter, GPS_ENGINE_AIRBORNE_4G),
  82. #if GPS_MAX_RECEIVERS > 1
  83. // @Param: AUTO_SWITCH
  84. // @DisplayName: Automatic Switchover Setting
  85. // @Description: Automatic switchover to GPS reporting best lock
  86. // @Values: 0:Disabled,1:UseBest,2:Blend,3:UseSecond
  87. // @User: Advanced
  88. AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, 1),
  89. #endif
  90. // @Param: MIN_DGPS
  91. // @DisplayName: Minimum Lock Type Accepted for DGPS
  92. // @Description: Sets the minimum type of differential GPS corrections required before allowing to switch into DGPS mode.
  93. // @Values: 0:Any,50:FloatRTK,100:IntegerRTK
  94. // @User: Advanced
  95. // @RebootRequired: True
  96. AP_GROUPINFO("MIN_DGPS", 4, AP_GPS, _min_dgps, 100),
  97. // @Param: SBAS_MODE
  98. // @DisplayName: SBAS Mode
  99. // @Description: This sets the SBAS (satellite based augmentation system) mode if available on this GPS. If set to 2 then the SBAS mode is not changed in the GPS. Otherwise the GPS will be reconfigured to enable/disable SBAS. Disabling SBAS may be worthwhile in some parts of the world where an SBAS signal is available but the baseline is too long to be useful.
  100. // @Values: 0:Disabled,1:Enabled,2:NoChange
  101. // @User: Advanced
  102. AP_GROUPINFO("SBAS_MODE", 5, AP_GPS, _sbas_mode, 2),
  103. // @Param: MIN_ELEV
  104. // @DisplayName: Minimum elevation
  105. // @Description: This sets the minimum elevation of satellites above the horizon for them to be used for navigation. Setting this to -100 leaves the minimum elevation set to the GPS modules default.
  106. // @Range: -100 90
  107. // @Units: deg
  108. // @User: Advanced
  109. AP_GROUPINFO("MIN_ELEV", 6, AP_GPS, _min_elevation, -100),
  110. // @Param: INJECT_TO
  111. // @DisplayName: Destination for GPS_INJECT_DATA MAVLink packets
  112. // @Description: The GGS can send raw serial packets to inject data to multiple GPSes.
  113. // @Values: 0:send to first GPS,1:send to 2nd GPS,127:send to all
  114. // @User: Advanced
  115. AP_GROUPINFO("INJECT_TO", 7, AP_GPS, _inject_to, GPS_RTK_INJECT_TO_ALL),
  116. // @Param: SBP_LOGMASK
  117. // @DisplayName: Swift Binary Protocol Logging Mask
  118. // @Description: Masked with the SBP msg_type field to determine whether SBR1/SBR2 data is logged
  119. // @Values: 0:None (0x0000),-1:All (0xFFFF),-256:External only (0xFF00)
  120. // @User: Advanced
  121. AP_GROUPINFO("SBP_LOGMASK", 8, AP_GPS, _sbp_logmask, -256),
  122. // @Param: RAW_DATA
  123. // @DisplayName: Raw data logging
  124. // @Description: Handles logging raw data; on uBlox chips that support raw data this will log RXM messages into logger; on Septentrio this will log on the equipment's SD card and when set to 2, the autopilot will try to stop logging after disarming and restart after arming
  125. // @Values: 0:Ignore,1:Always log,2:Stop logging when disarmed (SBF only),5:Only log every five samples (uBlox only)
  126. // @RebootRequired: True
  127. // @User: Advanced
  128. AP_GROUPINFO("RAW_DATA", 9, AP_GPS, _raw_data, 0),
  129. // @Param: GNSS_MODE
  130. // @DisplayName: GNSS system configuration
  131. // @Description: Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured)
  132. // @Values: 0:Leave as currently configured, 1:GPS-NoSBAS, 3:GPS+SBAS, 4:Galileo-NoSBAS, 6:Galileo+SBAS, 8:Beidou, 51:GPS+IMES+QZSS+SBAS (Japan Only), 64:GLONASS, 66:GLONASS+SBAS, 67:GPS+GLONASS+SBAS
  133. // @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS
  134. // @User: Advanced
  135. AP_GROUPINFO("GNSS_MODE", 10, AP_GPS, _gnss_mode[0], 0),
  136. // @Param: SAVE_CFG
  137. // @DisplayName: Save GPS configuration
  138. // @Description: Determines whether the configuration for this GPS should be written to non-volatile memory on the GPS. Currently working for UBlox 6 series and above.
  139. // @Values: 0:Do not save config,1:Save config,2:Save only when needed
  140. // @User: Advanced
  141. AP_GROUPINFO("SAVE_CFG", 11, AP_GPS, _save_config, 2),
  142. #if GPS_MAX_RECEIVERS > 1
  143. // @Param: GNSS_MODE2
  144. // @DisplayName: GNSS system configuration
  145. // @Description: Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured)
  146. // @Values: 0:Leave as currently configured, 1:GPS-NoSBAS, 3:GPS+SBAS, 4:Galileo-NoSBAS, 6:Galileo+SBAS, 8:Beidou, 51:GPS+IMES+QZSS+SBAS (Japan Only), 64:GLONASS, 66:GLONASS+SBAS, 67:GPS+GLONASS+SBAS
  147. // @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS
  148. // @User: Advanced
  149. AP_GROUPINFO("GNSS_MODE2", 12, AP_GPS, _gnss_mode[1], 0),
  150. #endif
  151. // @Param: AUTO_CONFIG
  152. // @DisplayName: Automatic GPS configuration
  153. // @Description: Controls if the autopilot should automatically configure the GPS based on the parameters and default settings
  154. // @Values: 0:Disables automatic configuration,1:Enable automatic configuration
  155. // @User: Advanced
  156. AP_GROUPINFO("AUTO_CONFIG", 13, AP_GPS, _auto_config, 1),
  157. // @Param: RATE_MS
  158. // @DisplayName: GPS update rate in milliseconds
  159. // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz is not allowed
  160. // @Units: ms
  161. // @Values: 100:10Hz,125:8Hz,200:5Hz
  162. // @Range: 50 200
  163. // @User: Advanced
  164. AP_GROUPINFO("RATE_MS", 14, AP_GPS, _rate_ms[0], 200),
  165. #if GPS_MAX_RECEIVERS > 1
  166. // @Param: RATE_MS2
  167. // @DisplayName: GPS 2 update rate in milliseconds
  168. // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz is not allowed
  169. // @Units: ms
  170. // @Values: 100:10Hz,125:8Hz,200:5Hz
  171. // @Range: 50 200
  172. // @User: Advanced
  173. AP_GROUPINFO("RATE_MS2", 15, AP_GPS, _rate_ms[1], 200),
  174. #endif
  175. // @Param: POS1_X
  176. // @DisplayName: Antenna X position offset
  177. // @Description: X position of the first GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
  178. // @Units: m
  179. // @Range: -10 10
  180. // @User: Advanced
  181. // @Param: POS1_Y
  182. // @DisplayName: Antenna Y position offset
  183. // @Description: Y position of the first GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
  184. // @Units: m
  185. // @Range: -10 10
  186. // @User: Advanced
  187. // @Param: POS1_Z
  188. // @DisplayName: Antenna Z position offset
  189. // @Description: Z position of the first GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
  190. // @Units: m
  191. // @Range: -10 10
  192. // @User: Advanced
  193. AP_GROUPINFO("POS1", 16, AP_GPS, _antenna_offset[0], 0.0f),
  194. // @Param: POS2_X
  195. // @DisplayName: Antenna X position offset
  196. // @Description: X position of the second GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
  197. // @Units: m
  198. // @Range: -10 10
  199. // @User: Advanced
  200. // @Param: POS2_Y
  201. // @DisplayName: Antenna Y position offset
  202. // @Description: Y position of the second GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
  203. // @Units: m
  204. // @Range: -10 10
  205. // @User: Advanced
  206. #if GPS_MAX_RECEIVERS > 1
  207. // @Param: POS2_Z
  208. // @DisplayName: Antenna Z position offset
  209. // @Description: Z position of the second GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
  210. // @Units: m
  211. // @Range: -10 10
  212. // @User: Advanced
  213. AP_GROUPINFO("POS2", 17, AP_GPS, _antenna_offset[1], 0.0f),
  214. #endif
  215. // @Param: DELAY_MS
  216. // @DisplayName: GPS delay in milliseconds
  217. // @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.
  218. // @Units: ms
  219. // @Range: 0 250
  220. // @User: Advanced
  221. // @RebootRequired: True
  222. AP_GROUPINFO("DELAY_MS", 18, AP_GPS, _delay_ms[0], 0),
  223. #if GPS_MAX_RECEIVERS > 1
  224. // @Param: DELAY_MS2
  225. // @DisplayName: GPS 2 delay in milliseconds
  226. // @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.
  227. // @Units: ms
  228. // @Range: 0 250
  229. // @User: Advanced
  230. // @RebootRequired: True
  231. AP_GROUPINFO("DELAY_MS2", 19, AP_GPS, _delay_ms[1], 0),
  232. #endif
  233. #if defined(GPS_BLENDED_INSTANCE)
  234. // @Param: BLEND_MASK
  235. // @DisplayName: Multi GPS Blending Mask
  236. // @Description: Determines which of the accuracy measures Horizontal position, Vertical Position and Speed are used to calculate the weighting on each GPS receiver when soft switching has been selected by setting GPS_AUTO_SWITCH to 2
  237. // @Bitmask: 0:Horiz Pos,1:Vert Pos,2:Speed
  238. // @User: Advanced
  239. AP_GROUPINFO("BLEND_MASK", 20, AP_GPS, _blend_mask, 5),
  240. // @Param: BLEND_TC
  241. // @DisplayName: Blending time constant
  242. // @Description: Controls the slowest time constant applied to the calculation of GPS position and height offsets used to adjust different GPS receivers for steady state position differences.
  243. // @Units: s
  244. // @Range: 5.0 30.0
  245. // @User: Advanced
  246. AP_GROUPINFO("BLEND_TC", 21, AP_GPS, _blend_tc, 10.0f),
  247. #endif
  248. AP_GROUPEND
  249. };
  250. // constructor
  251. AP_GPS::AP_GPS()
  252. {
  253. static_assert((sizeof(_initialisation_blob) * (CHAR_BIT + 2)) < (4800 * GPS_BAUD_TIME_MS * 1e-3),
  254. "GPS initilisation blob is too large to be completely sent before the baud rate changes");
  255. AP_Param::setup_object_defaults(this, var_info);
  256. if (_singleton != nullptr) {
  257. AP_HAL::panic("AP_GPS must be singleton");
  258. }
  259. _singleton = this;
  260. }
  261. /// Startup initialisation.
  262. void AP_GPS::init(const AP_SerialManager& serial_manager)
  263. {
  264. primary_instance = 0;
  265. // search for serial ports with gps protocol
  266. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  267. _port[i] = serial_manager.find_serial(AP_SerialManager::SerialProtocol_GPS, i);
  268. }
  269. _last_instance_swap_ms = 0;
  270. // Initialise class variables used to do GPS blending
  271. _omega_lpf = 1.0f / constrain_float(_blend_tc, 5.0f, 30.0f);
  272. // prep the state instance fields
  273. for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) {
  274. state[i].instance = i;
  275. }
  276. // sanity check update rate
  277. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  278. if (_rate_ms[i] <= 0 || _rate_ms[i] > GPS_MAX_RATE_MS) {
  279. _rate_ms[i] = GPS_MAX_RATE_MS;
  280. }
  281. }
  282. }
  283. // return number of active GPS sensors. Note that if the first GPS
  284. // is not present but the 2nd is then we return 2. Note that a blended
  285. // GPS solution is treated as an additional sensor.
  286. uint8_t AP_GPS::num_sensors(void) const
  287. {
  288. if (!_output_is_blended) {
  289. return num_instances;
  290. } else {
  291. return num_instances+1;
  292. }
  293. }
  294. bool AP_GPS::speed_accuracy(uint8_t instance, float &sacc) const
  295. {
  296. if (state[instance].have_speed_accuracy) {
  297. sacc = state[instance].speed_accuracy;
  298. return true;
  299. }
  300. return false;
  301. }
  302. bool AP_GPS::horizontal_accuracy(uint8_t instance, float &hacc) const
  303. {
  304. if (state[instance].have_horizontal_accuracy) {
  305. hacc = state[instance].horizontal_accuracy;
  306. return true;
  307. }
  308. return false;
  309. }
  310. bool AP_GPS::vertical_accuracy(uint8_t instance, float &vacc) const
  311. {
  312. if (state[instance].have_vertical_accuracy) {
  313. vacc = state[instance].vertical_accuracy;
  314. return true;
  315. }
  316. return false;
  317. }
  318. /**
  319. convert GPS week and milliseconds to unix epoch in milliseconds
  320. */
  321. uint64_t AP_GPS::time_epoch_convert(uint16_t gps_week, uint32_t gps_ms)
  322. {
  323. uint64_t fix_time_ms = UNIX_OFFSET_MSEC + gps_week * AP_MSEC_PER_WEEK + gps_ms;
  324. return fix_time_ms;
  325. }
  326. /**
  327. calculate current time since the unix epoch in microseconds
  328. */
  329. uint64_t AP_GPS::time_epoch_usec(uint8_t instance) const
  330. {
  331. const GPS_State &istate = state[instance];
  332. if (istate.last_gps_time_ms == 0 || istate.time_week == 0) {
  333. return 0;
  334. }
  335. uint64_t fix_time_ms = time_epoch_convert(istate.time_week, istate.time_week_ms);
  336. // add in the milliseconds since the last fix
  337. return (fix_time_ms + (AP_HAL::millis() - istate.last_gps_time_ms)) * 1000ULL;
  338. }
  339. /*
  340. send some more initialisation string bytes if there is room in the
  341. UART transmit buffer
  342. */
  343. void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
  344. {
  345. initblob_state[instance].blob = _blob;
  346. initblob_state[instance].remaining = size;
  347. }
  348. /*
  349. send some more initialisation string bytes if there is room in the
  350. UART transmit buffer
  351. */
  352. void AP_GPS::send_blob_update(uint8_t instance)
  353. {
  354. // exit immediately if no uart for this instance
  355. if (_port[instance] == nullptr) {
  356. return;
  357. }
  358. // see if we can write some more of the initialisation blob
  359. if (initblob_state[instance].remaining > 0) {
  360. int16_t space = _port[instance]->txspace();
  361. if (space > (int16_t)initblob_state[instance].remaining) {
  362. space = initblob_state[instance].remaining;
  363. }
  364. while (space > 0) {
  365. _port[instance]->write(*initblob_state[instance].blob);
  366. initblob_state[instance].blob++;
  367. space--;
  368. initblob_state[instance].remaining--;
  369. }
  370. }
  371. }
  372. /*
  373. run detection step for one GPS instance. If this finds a GPS then it
  374. will fill in drivers[instance] and change state[instance].status
  375. from NO_GPS to NO_FIX.
  376. */
  377. void AP_GPS::detect_instance(uint8_t instance)
  378. {
  379. AP_GPS_Backend *new_gps = nullptr;
  380. struct detect_state *dstate = &detect_state[instance];
  381. const uint32_t now = AP_HAL::millis();
  382. state[instance].status = NO_GPS;
  383. state[instance].hdop = GPS_UNKNOWN_DOP;
  384. state[instance].vdop = GPS_UNKNOWN_DOP;
  385. switch (_type[instance]) {
  386. // user has to explicitly set the MAV type, do not use AUTO
  387. // do not try to detect the MAV type, assume it's there
  388. case GPS_TYPE_MAV:
  389. #ifndef HAL_BUILD_AP_PERIPH
  390. dstate->auto_detected_baud = false; // specified, not detected
  391. new_gps = new AP_GPS_MAV(*this, state[instance], nullptr);
  392. goto found_gps;
  393. #endif
  394. break;
  395. // user has to explicitly set the UAVCAN type, do not use AUTO
  396. case GPS_TYPE_UAVCAN:
  397. #if HAL_WITH_UAVCAN
  398. dstate->auto_detected_baud = false; // specified, not detected
  399. new_gps = AP_GPS_UAVCAN::probe(*this, state[instance]);
  400. goto found_gps;
  401. #endif
  402. return; // We don't do anything here if UAVCAN is not supported
  403. default:
  404. break;
  405. }
  406. if (_port[instance] == nullptr) {
  407. // UART not available
  408. return;
  409. }
  410. // all remaining drivers automatically cycle through baud rates to detect
  411. // the correct baud rate, and should have the selected baud broadcast
  412. dstate->auto_detected_baud = true;
  413. #ifndef HAL_BUILD_AP_PERIPH
  414. switch (_type[instance]) {
  415. // by default the sbf/trimble gps outputs no data on its port, until configured.
  416. case GPS_TYPE_SBF:
  417. new_gps = new AP_GPS_SBF(*this, state[instance], _port[instance]);
  418. break;
  419. case GPS_TYPE_GSOF:
  420. new_gps = new AP_GPS_GSOF(*this, state[instance], _port[instance]);
  421. break;
  422. case GPS_TYPE_NOVA:
  423. new_gps = new AP_GPS_NOVA(*this, state[instance], _port[instance]);
  424. break;
  425. default:
  426. break;
  427. }
  428. #endif // HAL_BUILD_AP_PERIPH
  429. if (now - dstate->last_baud_change_ms > GPS_BAUD_TIME_MS) {
  430. // try the next baud rate
  431. // incrementing like this will skip the first element in array of bauds
  432. // this is okay, and relied upon
  433. dstate->current_baud++;
  434. if (dstate->current_baud == ARRAY_SIZE(_baudrates)) {
  435. dstate->current_baud = 0;
  436. }
  437. uint32_t baudrate = _baudrates[dstate->current_baud];
  438. _port[instance]->begin(baudrate);
  439. _port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
  440. dstate->last_baud_change_ms = now;
  441. if (_auto_config == GPS_AUTO_CONFIG_ENABLE && new_gps == nullptr) {
  442. if (_type[instance] == GPS_TYPE_HEMI) {
  443. send_blob_start(instance, AP_GPS_NMEA_HEMISPHERE_INIT_STRING, strlen(AP_GPS_NMEA_HEMISPHERE_INIT_STRING));
  444. } else {
  445. send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
  446. }
  447. }
  448. }
  449. if (_auto_config == GPS_AUTO_CONFIG_ENABLE && new_gps == nullptr) {
  450. send_blob_update(instance);
  451. }
  452. while (initblob_state[instance].remaining == 0 && _port[instance]->available() > 0
  453. && new_gps == nullptr) {
  454. uint8_t data = _port[instance]->read();
  455. /*
  456. running a uBlox at less than 38400 will lead to packet
  457. corruption, as we can't receive the packets in the 200ms
  458. window for 5Hz fixes. The NMEA startup message should force
  459. the uBlox into 115200 no matter what rate it is configured
  460. for.
  461. */
  462. if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_UBLOX) &&
  463. ((!_auto_config && _baudrates[dstate->current_baud] >= 38400) ||
  464. _baudrates[dstate->current_baud] == 115200) &&
  465. AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
  466. new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance]);
  467. }
  468. #ifndef HAL_BUILD_AP_PERIPH
  469. #if !HAL_MINIMIZE_FEATURES
  470. // we drop the MTK drivers when building a small build as they are so rarely used
  471. // and are surprisingly large
  472. else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK19) &&
  473. AP_GPS_MTK19::_detect(dstate->mtk19_detect_state, data)) {
  474. new_gps = new AP_GPS_MTK19(*this, state[instance], _port[instance]);
  475. } else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK) &&
  476. AP_GPS_MTK::_detect(dstate->mtk_detect_state, data)) {
  477. new_gps = new AP_GPS_MTK(*this, state[instance], _port[instance]);
  478. }
  479. #endif
  480. else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
  481. AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) {
  482. new_gps = new AP_GPS_SBP2(*this, state[instance], _port[instance]);
  483. }
  484. else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
  485. AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
  486. new_gps = new AP_GPS_SBP(*this, state[instance], _port[instance]);
  487. }
  488. #if !HAL_MINIMIZE_FEATURES
  489. else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) &&
  490. AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) {
  491. new_gps = new AP_GPS_SIRF(*this, state[instance], _port[instance]);
  492. }
  493. #endif
  494. else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_ERB) &&
  495. AP_GPS_ERB::_detect(dstate->erb_detect_state, data)) {
  496. new_gps = new AP_GPS_ERB(*this, state[instance], _port[instance]);
  497. } else if ((_type[instance] == GPS_TYPE_NMEA ||
  498. _type[instance] == GPS_TYPE_HEMI) &&
  499. AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) {
  500. new_gps = new AP_GPS_NMEA(*this, state[instance], _port[instance]);
  501. }
  502. #endif // HAL_BUILD_AP_PERIPH
  503. if (new_gps) {
  504. goto found_gps;
  505. }
  506. }
  507. found_gps:
  508. if (new_gps != nullptr) {
  509. state[instance].status = NO_FIX;
  510. drivers[instance] = new_gps;
  511. timing[instance].last_message_time_ms = now;
  512. timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
  513. new_gps->broadcast_gps_type();
  514. }
  515. }
  516. AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const
  517. {
  518. if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {
  519. return drivers[instance]->highest_supported_status();
  520. }
  521. return AP_GPS::GPS_OK_FIX_3D;
  522. }
  523. bool AP_GPS::should_log() const
  524. {
  525. #ifndef HAL_BUILD_AP_PERIPH
  526. AP_Logger *logger = AP_Logger::get_singleton();
  527. if (logger == nullptr) {
  528. return false;
  529. }
  530. if (_log_gps_bit == (uint32_t)-1) {
  531. return false;
  532. }
  533. if (!logger->should_log(_log_gps_bit)) {
  534. return false;
  535. }
  536. return true;
  537. #else
  538. return false;
  539. #endif
  540. }
  541. /*
  542. update one GPS instance. This should be called at 10Hz or greater
  543. */
  544. void AP_GPS::update_instance(uint8_t instance)
  545. {
  546. if (_type[instance] == GPS_TYPE_HIL) {
  547. // in HIL, leave info alone
  548. return;
  549. }
  550. if (_type[instance] == GPS_TYPE_NONE) {
  551. // not enabled
  552. state[instance].status = NO_GPS;
  553. state[instance].hdop = GPS_UNKNOWN_DOP;
  554. state[instance].vdop = GPS_UNKNOWN_DOP;
  555. return;
  556. }
  557. if (locked_ports & (1U<<instance)) {
  558. // the port is locked by another driver
  559. return;
  560. }
  561. if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
  562. // we don't yet know the GPS type of this one, or it has timed
  563. // out and needs to be re-initialised
  564. detect_instance(instance);
  565. return;
  566. }
  567. if (_auto_config == GPS_AUTO_CONFIG_ENABLE) {
  568. send_blob_update(instance);
  569. }
  570. // we have an active driver for this instance
  571. bool result = drivers[instance]->read();
  572. uint32_t tnow = AP_HAL::millis();
  573. // if we did not get a message, and the idle timer of 2 seconds
  574. // has expired, re-initialise the GPS. This will cause GPS
  575. // detection to run again
  576. bool data_should_be_logged = false;
  577. if (!result) {
  578. if (tnow - timing[instance].last_message_time_ms > GPS_TIMEOUT_MS) {
  579. memset((void *)&state[instance], 0, sizeof(state[instance]));
  580. state[instance].instance = instance;
  581. state[instance].hdop = GPS_UNKNOWN_DOP;
  582. state[instance].vdop = GPS_UNKNOWN_DOP;
  583. timing[instance].last_message_time_ms = tnow;
  584. timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
  585. // do not try to detect again if type is MAV
  586. if (_type[instance] == GPS_TYPE_MAV) {
  587. state[instance].status = NO_FIX;
  588. } else {
  589. // free the driver before we run the next detection, so we
  590. // don't end up with two allocated at any time
  591. delete drivers[instance];
  592. drivers[instance] = nullptr;
  593. state[instance].status = NO_GPS;
  594. }
  595. // log this data as a "flag" that the GPS is no longer
  596. // valid (see PR#8144)
  597. data_should_be_logged = true;
  598. }
  599. } else {
  600. if (state[instance].uart_timestamp_ms != 0) {
  601. // set the timestamp for this messages based on
  602. // set_uart_timestamp() in backend, if available
  603. tnow = state[instance].uart_timestamp_ms;
  604. state[instance].uart_timestamp_ms = 0;
  605. }
  606. // delta will only be correct after parsing two messages
  607. timing[instance].delta_time_ms = tnow - timing[instance].last_message_time_ms;
  608. timing[instance].last_message_time_ms = tnow;
  609. if (state[instance].status >= GPS_OK_FIX_2D) {
  610. timing[instance].last_fix_time_ms = tnow;
  611. }
  612. data_should_be_logged = true;
  613. }
  614. #ifndef HAL_BUILD_AP_PERIPH
  615. if (data_should_be_logged &&
  616. (should_log() || AP::ahrs().have_ekf_logging())) {
  617. AP::logger().Write_GPS(instance);
  618. }
  619. if (state[instance].status >= GPS_OK_FIX_3D) {
  620. const uint64_t now = time_epoch_usec(instance);
  621. if (now != 0) {
  622. AP::rtc().set_utc_usec(now, AP_RTC::SOURCE_GPS);
  623. }
  624. }
  625. #else
  626. (void)data_should_be_logged;
  627. #endif
  628. }
  629. /*
  630. update all GPS instances
  631. */
  632. void AP_GPS::update(void)
  633. {
  634. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  635. update_instance(i);
  636. }
  637. // calculate number of instances
  638. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  639. if (state[i].status != NO_GPS) {
  640. num_instances = i+1;
  641. }
  642. }
  643. #if defined(GPS_BLENDED_INSTANCE)
  644. // if blending is requested, attempt to calculate weighting for each GPS
  645. if (_auto_switch == 2) {
  646. _output_is_blended = calc_blend_weights();
  647. // adjust blend health counter
  648. if (!_output_is_blended) {
  649. _blend_health_counter = MIN(_blend_health_counter+BLEND_COUNTER_FAILURE_INCREMENT, 100);
  650. } else if (_blend_health_counter > 0) {
  651. _blend_health_counter--;
  652. }
  653. // stop blending if unhealthy
  654. if (_blend_health_counter >= 50) {
  655. _output_is_blended = false;
  656. }
  657. } else {
  658. _output_is_blended = false;
  659. _blend_health_counter = 0;
  660. }
  661. if (_output_is_blended) {
  662. // Use the weighting to calculate blended GPS states
  663. calc_blended_state();
  664. // set primary to the virtual instance
  665. primary_instance = GPS_BLENDED_INSTANCE;
  666. } else {
  667. // use switch logic to find best GPS
  668. uint32_t now = AP_HAL::millis();
  669. if (_auto_switch == 3) {
  670. // select the second GPS instance
  671. primary_instance = 1;
  672. } else if (_auto_switch >= 1) {
  673. // handling switching away from blended GPS
  674. if (primary_instance == GPS_BLENDED_INSTANCE) {
  675. primary_instance = 0;
  676. for (uint8_t i=1; i<GPS_MAX_RECEIVERS; i++) {
  677. // choose GPS with highest state or higher number of satellites
  678. if ((state[i].status > state[primary_instance].status) ||
  679. ((state[i].status == state[primary_instance].status) && (state[i].num_sats > state[primary_instance].num_sats))) {
  680. primary_instance = i;
  681. _last_instance_swap_ms = now;
  682. }
  683. }
  684. } else {
  685. // handle switch between real GPSs
  686. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  687. if (i == primary_instance) {
  688. continue;
  689. }
  690. if (state[i].status > state[primary_instance].status) {
  691. // we have a higher status lock, or primary is set to the blended GPS, change GPS
  692. primary_instance = i;
  693. _last_instance_swap_ms = now;
  694. continue;
  695. }
  696. bool another_gps_has_1_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 1);
  697. if (state[i].status == state[primary_instance].status && another_gps_has_1_or_more_sats) {
  698. bool another_gps_has_2_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 2);
  699. if ((another_gps_has_1_or_more_sats && (now - _last_instance_swap_ms) >= 20000) ||
  700. (another_gps_has_2_or_more_sats && (now - _last_instance_swap_ms) >= 5000)) {
  701. // this GPS has more satellites than the
  702. // current primary, switch primary. Once we switch we will
  703. // then tend to stick to the new GPS as primary. We don't
  704. // want to switch too often as it will look like a
  705. // position shift to the controllers.
  706. primary_instance = i;
  707. _last_instance_swap_ms = now;
  708. }
  709. }
  710. }
  711. }
  712. } else {
  713. // AUTO_SWITCH is 0 so no switching of GPSs
  714. primary_instance = 0;
  715. }
  716. // copy the primary instance to the blended instance in case it is enabled later
  717. state[GPS_BLENDED_INSTANCE] = state[primary_instance];
  718. _blended_antenna_offset = _antenna_offset[primary_instance];
  719. }
  720. #endif // GPS_BLENDED_INSTANCE
  721. #ifndef HAL_BUILD_AP_PERIPH
  722. // update notify with gps status. We always base this on the primary_instance
  723. AP_Notify::flags.gps_status = state[primary_instance].status;
  724. AP_Notify::flags.gps_num_sats = state[primary_instance].num_sats;
  725. #endif
  726. }
  727. void AP_GPS::handle_gps_inject(const mavlink_message_t &msg)
  728. {
  729. mavlink_gps_inject_data_t packet;
  730. mavlink_msg_gps_inject_data_decode(&msg, &packet);
  731. //TODO: check target
  732. inject_data(packet.data, packet.len);
  733. }
  734. /*
  735. pass along a mavlink message (for MAV type)
  736. */
  737. void AP_GPS::handle_msg(const mavlink_message_t &msg)
  738. {
  739. switch (msg.msgid) {
  740. case MAVLINK_MSG_ID_GPS_RTCM_DATA:
  741. // pass data to de-fragmenter
  742. handle_gps_rtcm_data(msg);
  743. break;
  744. case MAVLINK_MSG_ID_GPS_INJECT_DATA:
  745. handle_gps_inject(msg);
  746. break;
  747. default: {
  748. uint8_t i;
  749. for (i=0; i<num_instances; i++) {
  750. if ((drivers[i] != nullptr) && (_type[i] != GPS_TYPE_NONE)) {
  751. drivers[i]->handle_msg(msg);
  752. }
  753. }
  754. break;
  755. }
  756. }
  757. }
  758. /*
  759. set HIL (hardware in the loop) status for a GPS instance
  760. */
  761. void AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms,
  762. const Location &_location, const Vector3f &_velocity, uint8_t _num_sats,
  763. uint16_t hdop)
  764. {
  765. if (instance >= GPS_MAX_RECEIVERS) {
  766. return;
  767. }
  768. const uint32_t tnow = AP_HAL::millis();
  769. GPS_State &istate = state[instance];
  770. istate.status = _status;
  771. istate.location = _location;
  772. istate.velocity = _velocity;
  773. istate.ground_speed = norm(istate.velocity.x, istate.velocity.y);
  774. istate.ground_course = wrap_360(degrees(atan2f(istate.velocity.y, istate.velocity.x)));
  775. istate.hdop = hdop;
  776. istate.num_sats = _num_sats;
  777. istate.last_gps_time_ms = tnow;
  778. uint64_t gps_time_ms = time_epoch_ms - UNIX_OFFSET_MSEC;
  779. istate.time_week = gps_time_ms / AP_MSEC_PER_WEEK;
  780. istate.time_week_ms = gps_time_ms - istate.time_week * AP_MSEC_PER_WEEK;
  781. timing[instance].last_message_time_ms = tnow;
  782. timing[instance].last_fix_time_ms = tnow;
  783. _type[instance].set(GPS_TYPE_HIL);
  784. }
  785. // set accuracy for HIL
  786. void AP_GPS::setHIL_Accuracy(uint8_t instance, float vdop, float hacc, float vacc, float sacc, bool _have_vertical_velocity, uint32_t sample_ms)
  787. {
  788. if (instance >= GPS_MAX_RECEIVERS) {
  789. return;
  790. }
  791. GPS_State &istate = state[instance];
  792. istate.vdop = vdop * 100;
  793. istate.horizontal_accuracy = hacc;
  794. istate.vertical_accuracy = vacc;
  795. istate.speed_accuracy = sacc;
  796. istate.have_horizontal_accuracy = true;
  797. istate.have_vertical_accuracy = true;
  798. istate.have_speed_accuracy = true;
  799. istate.have_vertical_velocity |= _have_vertical_velocity;
  800. if (sample_ms != 0) {
  801. timing[instance].last_message_time_ms = sample_ms;
  802. timing[instance].last_fix_time_ms = sample_ms;
  803. }
  804. }
  805. /**
  806. Lock a GPS port, preventing the GPS driver from using it. This can
  807. be used to allow a user to control a GPS port via the
  808. SERIAL_CONTROL protocol
  809. */
  810. void AP_GPS::lock_port(uint8_t instance, bool lock)
  811. {
  812. if (instance >= GPS_MAX_RECEIVERS) {
  813. return;
  814. }
  815. if (lock) {
  816. locked_ports |= (1U<<instance);
  817. } else {
  818. locked_ports &= ~(1U<<instance);
  819. }
  820. }
  821. // Inject a packet of raw binary to a GPS
  822. void AP_GPS::inject_data(uint8_t *data, uint16_t len)
  823. {
  824. //Support broadcasting to all GPSes.
  825. if (_inject_to == GPS_RTK_INJECT_TO_ALL) {
  826. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  827. inject_data(i, data, len);
  828. }
  829. } else {
  830. inject_data(_inject_to, data, len);
  831. }
  832. }
  833. void AP_GPS::inject_data(uint8_t instance, uint8_t *data, uint16_t len)
  834. {
  835. if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {
  836. drivers[instance]->inject_data(data, len);
  837. }
  838. }
  839. void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
  840. {
  841. static uint32_t last_send_time_ms[MAVLINK_COMM_NUM_BUFFERS];
  842. if (status(0) > AP_GPS::NO_GPS) {
  843. // when we have a GPS then only send new data
  844. if (last_send_time_ms[chan] == last_message_time_ms(0)) {
  845. return;
  846. }
  847. last_send_time_ms[chan] = last_message_time_ms(0);
  848. } else {
  849. // when we don't have a GPS then send at 1Hz
  850. uint32_t now = AP_HAL::millis();
  851. if (now - last_send_time_ms[chan] < 1000) {
  852. return;
  853. }
  854. last_send_time_ms[chan] = now;
  855. }
  856. const Location &loc = location(0);
  857. float hacc = 0.0f;
  858. float vacc = 0.0f;
  859. float sacc = 0.0f;
  860. horizontal_accuracy(0, hacc);
  861. vertical_accuracy(0, vacc);
  862. speed_accuracy(0, sacc);
  863. mavlink_msg_gps_raw_int_send(
  864. chan,
  865. last_fix_time_ms(0)*(uint64_t)1000,
  866. status(0),
  867. loc.lat, // in 1E7 degrees
  868. loc.lng, // in 1E7 degrees
  869. loc.alt * 10UL, // in mm
  870. get_hdop(0),
  871. get_vdop(0),
  872. ground_speed(0)*100, // cm/s
  873. ground_course(0)*100, // 1/100 degrees,
  874. num_sats(0),
  875. 0, // TODO: Elipsoid height in mm
  876. hacc * 1000, // one-sigma standard deviation in mm
  877. vacc * 1000, // one-sigma standard deviation in mm
  878. sacc * 1000, // one-sigma standard deviation in mm/s
  879. 0); // TODO one-sigma heading accuracy standard deviation
  880. }
  881. #if GPS_MAX_RECEIVERS > 1
  882. void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
  883. {
  884. static uint32_t last_send_time_ms[MAVLINK_COMM_NUM_BUFFERS];
  885. if (num_instances < 2 || status(1) <= AP_GPS::NO_GPS) {
  886. return;
  887. }
  888. // when we have a GPS then only send new data
  889. if (last_send_time_ms[chan] == last_message_time_ms(1)) {
  890. return;
  891. }
  892. last_send_time_ms[chan] = last_message_time_ms(1);
  893. const Location &loc = location(1);
  894. mavlink_msg_gps2_raw_send(
  895. chan,
  896. last_fix_time_ms(1)*(uint64_t)1000,
  897. status(1),
  898. loc.lat,
  899. loc.lng,
  900. loc.alt * 10UL,
  901. get_hdop(1),
  902. get_vdop(1),
  903. ground_speed(1)*100, // cm/s
  904. ground_course(1)*100, // 1/100 degrees,
  905. num_sats(1),
  906. state[1].rtk_num_sats,
  907. state[1].rtk_age_ms);
  908. }
  909. #endif // GPS_MAX_RECEIVERS
  910. void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
  911. {
  912. if (inst >= GPS_MAX_RECEIVERS) {
  913. return;
  914. }
  915. if (drivers[inst] != nullptr && drivers[inst]->supports_mavlink_gps_rtk_message()) {
  916. drivers[inst]->send_mavlink_gps_rtk(chan);
  917. }
  918. }
  919. bool AP_GPS::first_unconfigured_gps(uint8_t &instance) const
  920. {
  921. for (int i = 0; i < GPS_MAX_RECEIVERS; i++) {
  922. if (_type[i] != GPS_TYPE_NONE && (drivers[i] == nullptr || !drivers[i]->is_configured())) {
  923. instance = i;
  924. return true;
  925. }
  926. }
  927. return false;
  928. }
  929. void AP_GPS::broadcast_first_configuration_failure_reason(void) const
  930. {
  931. uint8_t unconfigured;
  932. if (first_unconfigured_gps(unconfigured)) {
  933. if (drivers[unconfigured] == nullptr) {
  934. gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: was not found", unconfigured + 1);
  935. } else {
  936. drivers[unconfigured]->broadcast_configuration_failure_reason();
  937. }
  938. }
  939. }
  940. // pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned
  941. bool AP_GPS::all_consistent(float &distance) const
  942. {
  943. // return true immediately if only one valid receiver
  944. if (num_instances <= 1 ||
  945. drivers[0] == nullptr || _type[0] == GPS_TYPE_NONE) {
  946. distance = 0;
  947. return true;
  948. }
  949. // calculate distance
  950. distance = state[0].location.get_distance_NED(state[1].location).length();
  951. // success if distance is within 50m
  952. return (distance < 50);
  953. }
  954. // pre-arm check of GPS blending. True means healthy or that blending is not being used
  955. bool AP_GPS::blend_health_check() const
  956. {
  957. return (_blend_health_counter < 50);
  958. }
  959. /*
  960. re-assemble GPS_RTCM_DATA message
  961. */
  962. void AP_GPS::handle_gps_rtcm_data(const mavlink_message_t &msg)
  963. {
  964. mavlink_gps_rtcm_data_t packet;
  965. mavlink_msg_gps_rtcm_data_decode(&msg, &packet);
  966. if (packet.len > MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {
  967. // invalid packet
  968. return;
  969. }
  970. if ((packet.flags & 1) == 0) {
  971. // it is not fragmented, pass direct
  972. inject_data(packet.data, packet.len);
  973. return;
  974. }
  975. // see if we need to allocate re-assembly buffer
  976. if (rtcm_buffer == nullptr) {
  977. rtcm_buffer = (struct rtcm_buffer *)calloc(1, sizeof(*rtcm_buffer));
  978. if (rtcm_buffer == nullptr) {
  979. // nothing to do but discard the data
  980. return;
  981. }
  982. }
  983. uint8_t fragment = (packet.flags >> 1U) & 0x03;
  984. uint8_t sequence = (packet.flags >> 3U) & 0x1F;
  985. // see if this fragment is consistent with existing fragments
  986. if (rtcm_buffer->fragments_received &&
  987. (rtcm_buffer->sequence != sequence ||
  988. (rtcm_buffer->fragments_received & (1U<<fragment)))) {
  989. // we have one or more partial fragments already received
  990. // which conflict with the new fragment, discard previous fragments
  991. memset(rtcm_buffer, 0, sizeof(*rtcm_buffer));
  992. }
  993. // add this fragment
  994. rtcm_buffer->sequence = sequence;
  995. rtcm_buffer->fragments_received |= (1U << fragment);
  996. // copy the data
  997. memcpy(&rtcm_buffer->buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*(uint16_t)fragment], packet.data, packet.len);
  998. // when we get a fragment of less than max size then we know the
  999. // number of fragments. Note that this means if you want to send a
  1000. // block of RTCM data of an exact multiple of the buffer size you
  1001. // need to send a final packet of zero length
  1002. if (packet.len < MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {
  1003. rtcm_buffer->fragment_count = fragment+1;
  1004. rtcm_buffer->total_length = (MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*fragment) + packet.len;
  1005. } else if (rtcm_buffer->fragments_received == 0x0F) {
  1006. // special case of 4 full fragments
  1007. rtcm_buffer->fragment_count = 4;
  1008. rtcm_buffer->total_length = MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*4;
  1009. }
  1010. // see if we have all fragments
  1011. if (rtcm_buffer->fragment_count != 0 &&
  1012. rtcm_buffer->fragments_received == (1U << rtcm_buffer->fragment_count) - 1) {
  1013. // we have them all, inject
  1014. inject_data(rtcm_buffer->buffer, rtcm_buffer->total_length);
  1015. memset(rtcm_buffer, 0, sizeof(*rtcm_buffer));
  1016. }
  1017. }
  1018. void AP_GPS::Write_AP_Logger_Log_Startup_messages()
  1019. {
  1020. for (uint8_t instance=0; instance<num_instances; instance++) {
  1021. if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
  1022. continue;
  1023. }
  1024. drivers[instance]->Write_AP_Logger_Log_Startup_messages();
  1025. }
  1026. }
  1027. /*
  1028. return the expected lag (in seconds) in the position and velocity readings from the gps
  1029. return true if the GPS hardware configuration is known or the delay parameter has been set
  1030. */
  1031. bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const
  1032. {
  1033. // always enusre a lag is provided
  1034. lag_sec = 0.22f;
  1035. if (instance >= GPS_MAX_INSTANCES) {
  1036. return false;
  1037. }
  1038. #if defined(GPS_BLENDED_INSTANCE)
  1039. // return lag of blended GPS
  1040. if (instance == GPS_BLENDED_INSTANCE) {
  1041. lag_sec = _blended_lag_sec;
  1042. // auto switching uses all GPS receivers, so all must be configured
  1043. uint8_t inst; // we don't actually care what the number is, but must pass it
  1044. return first_unconfigured_gps(inst);
  1045. }
  1046. #endif
  1047. if (_delay_ms[instance] > 0) {
  1048. // if the user has specified a non zero time delay, always return that value
  1049. lag_sec = 0.001f * (float)_delay_ms[instance];
  1050. // the user is always right !!
  1051. return true;
  1052. } else if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
  1053. // no GPS was detected in this instance so return the worst possible lag term
  1054. if (_type[instance] == GPS_TYPE_NONE) {
  1055. lag_sec = 0.0f;
  1056. return true;
  1057. }
  1058. return _type[instance] == GPS_TYPE_AUTO;
  1059. } else {
  1060. // the user has not specified a delay so we determine it from the GPS type
  1061. return drivers[instance]->get_lag(lag_sec);
  1062. }
  1063. }
  1064. // return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin
  1065. const Vector3f &AP_GPS::get_antenna_offset(uint8_t instance) const
  1066. {
  1067. if (instance >= GPS_MAX_INSTANCES) {
  1068. // we have to return a reference so use instance 0
  1069. return _antenna_offset[0];
  1070. }
  1071. #if defined(GPS_BLENDED_INSTANCE)
  1072. if (instance == GPS_BLENDED_INSTANCE) {
  1073. // return an offset for the blended GPS solution
  1074. return _blended_antenna_offset;
  1075. }
  1076. #endif
  1077. return _antenna_offset[instance];
  1078. }
  1079. /*
  1080. returns the desired gps update rate in milliseconds
  1081. this does not provide any guarantee that the GPS is updating at the requested
  1082. rate it is simply a helper for use in the backends for determining what rate
  1083. they should be configuring the GPS to run at
  1084. */
  1085. uint16_t AP_GPS::get_rate_ms(uint8_t instance) const
  1086. {
  1087. // sanity check
  1088. if (instance >= num_instances || _rate_ms[instance] <= 0) {
  1089. return GPS_MAX_RATE_MS;
  1090. }
  1091. return MIN(_rate_ms[instance], GPS_MAX_RATE_MS);
  1092. }
  1093. #if defined(GPS_BLENDED_INSTANCE)
  1094. /*
  1095. calculate the weightings used to blend GPSs location and velocity data
  1096. */
  1097. bool AP_GPS::calc_blend_weights(void)
  1098. {
  1099. // zero the blend weights
  1100. memset(&_blend_weights, 0, sizeof(_blend_weights));
  1101. // exit immediately if not enough receivers to do blending
  1102. if (state[0].status <= NO_FIX || state[1].status <= NO_FIX) {
  1103. return false;
  1104. }
  1105. // Use the oldest non-zero time, but if time difference is excessive, use newest to prevent a disconnected receiver from blocking updates
  1106. uint32_t max_ms = 0; // newest non-zero system time of arrival of a GPS message
  1107. uint32_t min_ms = -1; // oldest non-zero system time of arrival of a GPS message
  1108. int16_t max_rate_ms = 0; // largest update interval of a GPS receiver
  1109. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1110. // Find largest and smallest times
  1111. if (state[i].last_gps_time_ms > max_ms) {
  1112. max_ms = state[i].last_gps_time_ms;
  1113. }
  1114. if ((state[i].last_gps_time_ms < min_ms) && (state[i].last_gps_time_ms > 0)) {
  1115. min_ms = state[i].last_gps_time_ms;
  1116. }
  1117. if (get_rate_ms(i) > max_rate_ms) {
  1118. max_rate_ms = get_rate_ms(i);
  1119. }
  1120. }
  1121. if ((int32_t)(max_ms - min_ms) < (int32_t)(2 * max_rate_ms)) {
  1122. // data is not too delayed so use the oldest time_stamp to give a chance for data from that receiver to be updated
  1123. state[GPS_BLENDED_INSTANCE].last_gps_time_ms = min_ms;
  1124. } else {
  1125. // receiver data has timed out so fail out of blending
  1126. return false;
  1127. }
  1128. // calculate the sum squared speed accuracy across all GPS sensors
  1129. float speed_accuracy_sum_sq = 0.0f;
  1130. if (_blend_mask & BLEND_MASK_USE_SPD_ACC) {
  1131. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1132. if (state[i].status >= GPS_OK_FIX_3D) {
  1133. if (state[i].have_speed_accuracy && state[i].speed_accuracy > 0.0f) {
  1134. speed_accuracy_sum_sq += state[i].speed_accuracy * state[i].speed_accuracy;
  1135. } else {
  1136. // not all receivers support this metric so set it to zero and don't use it
  1137. speed_accuracy_sum_sq = 0.0f;
  1138. break;
  1139. }
  1140. }
  1141. }
  1142. }
  1143. // calculate the sum squared horizontal position accuracy across all GPS sensors
  1144. float horizontal_accuracy_sum_sq = 0.0f;
  1145. if (_blend_mask & BLEND_MASK_USE_HPOS_ACC) {
  1146. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1147. if (state[i].status >= GPS_OK_FIX_2D) {
  1148. if (state[i].have_horizontal_accuracy && state[i].horizontal_accuracy > 0.0f) {
  1149. horizontal_accuracy_sum_sq += state[i].horizontal_accuracy * state[i].horizontal_accuracy;
  1150. } else {
  1151. // not all receivers support this metric so set it to zero and don't use it
  1152. horizontal_accuracy_sum_sq = 0.0f;
  1153. break;
  1154. }
  1155. }
  1156. }
  1157. }
  1158. // calculate the sum squared vertical position accuracy across all GPS sensors
  1159. float vertical_accuracy_sum_sq = 0.0f;
  1160. if (_blend_mask & BLEND_MASK_USE_VPOS_ACC) {
  1161. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1162. if (state[i].status >= GPS_OK_FIX_3D) {
  1163. if (state[i].have_vertical_accuracy && state[i].vertical_accuracy > 0.0f) {
  1164. vertical_accuracy_sum_sq += state[i].vertical_accuracy * state[i].vertical_accuracy;
  1165. } else {
  1166. // not all receivers support this metric so set it to zero and don't use it
  1167. vertical_accuracy_sum_sq = 0.0f;
  1168. break;
  1169. }
  1170. }
  1171. }
  1172. }
  1173. // Check if we can do blending using reported accuracy
  1174. bool can_do_blending = (horizontal_accuracy_sum_sq > 0.0f || vertical_accuracy_sum_sq > 0.0f || speed_accuracy_sum_sq > 0.0f);
  1175. // if we can't do blending using reported accuracy, return false and hard switch logic will be used instead
  1176. if (!can_do_blending) {
  1177. return false;
  1178. }
  1179. float sum_of_all_weights = 0.0f;
  1180. // calculate a weighting using the reported horizontal position
  1181. float hpos_blend_weights[GPS_MAX_RECEIVERS] = {};
  1182. if (horizontal_accuracy_sum_sq > 0.0f && (_blend_mask & BLEND_MASK_USE_HPOS_ACC)) {
  1183. // calculate the weights using the inverse of the variances
  1184. float sum_of_hpos_weights = 0.0f;
  1185. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1186. if (state[i].status >= GPS_OK_FIX_2D && state[i].horizontal_accuracy >= 0.001f) {
  1187. hpos_blend_weights[i] = horizontal_accuracy_sum_sq / (state[i].horizontal_accuracy * state[i].horizontal_accuracy);
  1188. sum_of_hpos_weights += hpos_blend_weights[i];
  1189. }
  1190. }
  1191. // normalise the weights
  1192. if (sum_of_hpos_weights > 0.0f) {
  1193. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1194. hpos_blend_weights[i] = hpos_blend_weights[i] / sum_of_hpos_weights;
  1195. }
  1196. sum_of_all_weights += 1.0f;
  1197. }
  1198. }
  1199. // calculate a weighting using the reported vertical position accuracy
  1200. float vpos_blend_weights[GPS_MAX_RECEIVERS] = {};
  1201. if (vertical_accuracy_sum_sq > 0.0f && (_blend_mask & BLEND_MASK_USE_VPOS_ACC)) {
  1202. // calculate the weights using the inverse of the variances
  1203. float sum_of_vpos_weights = 0.0f;
  1204. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1205. if (state[i].status >= GPS_OK_FIX_3D && state[i].vertical_accuracy >= 0.001f) {
  1206. vpos_blend_weights[i] = vertical_accuracy_sum_sq / (state[i].vertical_accuracy * state[i].vertical_accuracy);
  1207. sum_of_vpos_weights += vpos_blend_weights[i];
  1208. }
  1209. }
  1210. // normalise the weights
  1211. if (sum_of_vpos_weights > 0.0f) {
  1212. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1213. vpos_blend_weights[i] = vpos_blend_weights[i] / sum_of_vpos_weights;
  1214. }
  1215. sum_of_all_weights += 1.0f;
  1216. };
  1217. }
  1218. // calculate a weighting using the reported speed accuracy
  1219. float spd_blend_weights[GPS_MAX_RECEIVERS] = {};
  1220. if (speed_accuracy_sum_sq > 0.0f && (_blend_mask & BLEND_MASK_USE_SPD_ACC)) {
  1221. // calculate the weights using the inverse of the variances
  1222. float sum_of_spd_weights = 0.0f;
  1223. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1224. if (state[i].status >= GPS_OK_FIX_3D && state[i].speed_accuracy >= 0.001f) {
  1225. spd_blend_weights[i] = speed_accuracy_sum_sq / (state[i].speed_accuracy * state[i].speed_accuracy);
  1226. sum_of_spd_weights += spd_blend_weights[i];
  1227. }
  1228. }
  1229. // normalise the weights
  1230. if (sum_of_spd_weights > 0.0f) {
  1231. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1232. spd_blend_weights[i] = spd_blend_weights[i] / sum_of_spd_weights;
  1233. }
  1234. sum_of_all_weights += 1.0f;
  1235. }
  1236. }
  1237. // calculate an overall weight
  1238. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1239. _blend_weights[i] = (hpos_blend_weights[i] + vpos_blend_weights[i] + spd_blend_weights[i]) / sum_of_all_weights;
  1240. }
  1241. return true;
  1242. }
  1243. /*
  1244. calculate a blended GPS state
  1245. */
  1246. void AP_GPS::calc_blended_state(void)
  1247. {
  1248. // initialise the blended states so we can accumulate the results using the weightings for each GPS receiver
  1249. state[GPS_BLENDED_INSTANCE].instance = GPS_BLENDED_INSTANCE;
  1250. state[GPS_BLENDED_INSTANCE].status = NO_FIX;
  1251. state[GPS_BLENDED_INSTANCE].time_week_ms = 0;
  1252. state[GPS_BLENDED_INSTANCE].time_week = 0;
  1253. state[GPS_BLENDED_INSTANCE].ground_speed = 0.0f;
  1254. state[GPS_BLENDED_INSTANCE].ground_course = 0.0f;
  1255. state[GPS_BLENDED_INSTANCE].hdop = GPS_UNKNOWN_DOP;
  1256. state[GPS_BLENDED_INSTANCE].vdop = GPS_UNKNOWN_DOP;
  1257. state[GPS_BLENDED_INSTANCE].num_sats = 0;
  1258. state[GPS_BLENDED_INSTANCE].velocity.zero();
  1259. state[GPS_BLENDED_INSTANCE].speed_accuracy = 1e6f;
  1260. state[GPS_BLENDED_INSTANCE].horizontal_accuracy = 1e6f;
  1261. state[GPS_BLENDED_INSTANCE].vertical_accuracy = 1e6f;
  1262. state[GPS_BLENDED_INSTANCE].have_vertical_velocity = false;
  1263. state[GPS_BLENDED_INSTANCE].have_speed_accuracy = false;
  1264. state[GPS_BLENDED_INSTANCE].have_horizontal_accuracy = false;
  1265. state[GPS_BLENDED_INSTANCE].have_vertical_accuracy = false;
  1266. state[GPS_BLENDED_INSTANCE].location = {};
  1267. _blended_antenna_offset.zero();
  1268. _blended_lag_sec = 0;
  1269. timing[GPS_BLENDED_INSTANCE].last_fix_time_ms = 0;
  1270. timing[GPS_BLENDED_INSTANCE].last_message_time_ms = 0;
  1271. // combine the states into a blended solution
  1272. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1273. // use the highest status
  1274. if (state[i].status > state[GPS_BLENDED_INSTANCE].status) {
  1275. state[GPS_BLENDED_INSTANCE].status = state[i].status;
  1276. }
  1277. // calculate a blended average velocity
  1278. state[GPS_BLENDED_INSTANCE].velocity += state[i].velocity * _blend_weights[i];
  1279. // report the best valid accuracies and DOP metrics
  1280. if (state[i].have_horizontal_accuracy && state[i].horizontal_accuracy > 0.0f && state[i].horizontal_accuracy < state[GPS_BLENDED_INSTANCE].horizontal_accuracy) {
  1281. state[GPS_BLENDED_INSTANCE].have_horizontal_accuracy = true;
  1282. state[GPS_BLENDED_INSTANCE].horizontal_accuracy = state[i].horizontal_accuracy;
  1283. }
  1284. if (state[i].have_vertical_accuracy && state[i].vertical_accuracy > 0.0f && state[i].vertical_accuracy < state[GPS_BLENDED_INSTANCE].vertical_accuracy) {
  1285. state[GPS_BLENDED_INSTANCE].have_vertical_accuracy = true;
  1286. state[GPS_BLENDED_INSTANCE].vertical_accuracy = state[i].vertical_accuracy;
  1287. }
  1288. if (state[i].have_vertical_velocity) {
  1289. state[GPS_BLENDED_INSTANCE].have_vertical_velocity = true;
  1290. }
  1291. if (state[i].have_speed_accuracy && state[i].speed_accuracy > 0.0f && state[i].speed_accuracy < state[GPS_BLENDED_INSTANCE].speed_accuracy) {
  1292. state[GPS_BLENDED_INSTANCE].have_speed_accuracy = true;
  1293. state[GPS_BLENDED_INSTANCE].speed_accuracy = state[i].speed_accuracy;
  1294. }
  1295. if (state[i].hdop > 0 && state[i].hdop < state[GPS_BLENDED_INSTANCE].hdop) {
  1296. state[GPS_BLENDED_INSTANCE].hdop = state[i].hdop;
  1297. }
  1298. if (state[i].vdop > 0 && state[i].vdop < state[GPS_BLENDED_INSTANCE].vdop) {
  1299. state[GPS_BLENDED_INSTANCE].vdop = state[i].vdop;
  1300. }
  1301. if (state[i].num_sats > 0 && state[i].num_sats > state[GPS_BLENDED_INSTANCE].num_sats) {
  1302. state[GPS_BLENDED_INSTANCE].num_sats = state[i].num_sats;
  1303. }
  1304. // report a blended average GPS antenna position
  1305. Vector3f temp_antenna_offset = _antenna_offset[i];
  1306. temp_antenna_offset *= _blend_weights[i];
  1307. _blended_antenna_offset += temp_antenna_offset;
  1308. // blend the timing data
  1309. if (timing[i].last_fix_time_ms > timing[GPS_BLENDED_INSTANCE].last_fix_time_ms) {
  1310. timing[GPS_BLENDED_INSTANCE].last_fix_time_ms = timing[i].last_fix_time_ms;
  1311. }
  1312. if (timing[i].last_message_time_ms > timing[GPS_BLENDED_INSTANCE].last_message_time_ms) {
  1313. timing[GPS_BLENDED_INSTANCE].last_message_time_ms = timing[i].last_message_time_ms;
  1314. }
  1315. }
  1316. /*
  1317. * Calculate an instantaneous weighted/blended average location from the available GPS instances and store in the _output_state.
  1318. * This will be statistically the most likely location, but will be not stable enough for direct use by the autopilot.
  1319. */
  1320. // Use the GPS with the highest weighting as the reference position
  1321. float best_weight = 0.0f;
  1322. uint8_t best_index = 0;
  1323. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1324. if (_blend_weights[i] > best_weight) {
  1325. best_weight = _blend_weights[i];
  1326. best_index = i;
  1327. state[GPS_BLENDED_INSTANCE].location = state[i].location;
  1328. }
  1329. }
  1330. // Calculate the weighted sum of horizontal and vertical position offsets relative to the reference position
  1331. Vector2f blended_NE_offset_m;
  1332. float blended_alt_offset_cm = 0.0f;
  1333. blended_NE_offset_m.zero();
  1334. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1335. if (_blend_weights[i] > 0.0f && i != best_index) {
  1336. blended_NE_offset_m += state[GPS_BLENDED_INSTANCE].location.get_distance_NE(state[i].location) * _blend_weights[i];
  1337. blended_alt_offset_cm += (float)(state[i].location.alt - state[GPS_BLENDED_INSTANCE].location.alt) * _blend_weights[i];
  1338. }
  1339. }
  1340. // Add the sum of weighted offsets to the reference location to obtain the blended location
  1341. state[GPS_BLENDED_INSTANCE].location.offset(blended_NE_offset_m.x, blended_NE_offset_m.y);
  1342. state[GPS_BLENDED_INSTANCE].location.alt += (int)blended_alt_offset_cm;
  1343. // Calculate ground speed and course from blended velocity vector
  1344. state[GPS_BLENDED_INSTANCE].ground_speed = norm(state[GPS_BLENDED_INSTANCE].velocity.x, state[GPS_BLENDED_INSTANCE].velocity.y);
  1345. state[GPS_BLENDED_INSTANCE].ground_course = wrap_360(degrees(atan2f(state[GPS_BLENDED_INSTANCE].velocity.y, state[GPS_BLENDED_INSTANCE].velocity.x)));
  1346. /*
  1347. * The blended location in _output_state.location is not stable enough to be used by the autopilot
  1348. * as it will move around as the relative accuracy changes. To mitigate this effect a low-pass filtered
  1349. * offset from each GPS location to the blended location is calculated and the filtered offset is applied
  1350. * to each receiver.
  1351. */
  1352. // Calculate filter coefficients to be applied to the offsets for each GPS position and height offset
  1353. // A weighting of 1 will make the offset adjust the slowest, a weighting of 0 will make it adjust with zero filtering
  1354. float alpha[GPS_MAX_RECEIVERS] = {};
  1355. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1356. if (state[i].last_gps_time_ms - _last_time_updated[i] > 0) {
  1357. float min_alpha = constrain_float(_omega_lpf * 0.001f * (float)(state[i].last_gps_time_ms - _last_time_updated[i]), 0.0f, 1.0f);
  1358. if (_blend_weights[i] > min_alpha) {
  1359. alpha[i] = min_alpha / _blend_weights[i];
  1360. } else {
  1361. alpha[i] = 1.0f;
  1362. }
  1363. _last_time_updated[i] = state[i].last_gps_time_ms;
  1364. }
  1365. }
  1366. // Calculate the offset from each GPS solution to the blended solution
  1367. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1368. _NE_pos_offset_m[i] = state[i].location.get_distance_NE(state[GPS_BLENDED_INSTANCE].location) * alpha[i] + _NE_pos_offset_m[i] * (1.0f - alpha[i]);
  1369. _hgt_offset_cm[i] = (float)(state[GPS_BLENDED_INSTANCE].location.alt - state[i].location.alt) * alpha[i] + _hgt_offset_cm[i] * (1.0f - alpha[i]);
  1370. }
  1371. // Calculate a corrected location for each GPS
  1372. Location corrected_location[GPS_MAX_RECEIVERS];
  1373. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1374. corrected_location[i] = state[i].location;
  1375. corrected_location[i].offset(_NE_pos_offset_m[i].x, _NE_pos_offset_m[i].y);
  1376. corrected_location[i].alt += (int)(_hgt_offset_cm[i]);
  1377. }
  1378. // If the GPS week is the same then use a blended time_week_ms
  1379. // If week is different, then use time stamp from GPS with largest weighting
  1380. // detect inconsistent week data
  1381. uint8_t last_week_instance = 0;
  1382. bool weeks_consistent = true;
  1383. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1384. if (last_week_instance == 0 && _blend_weights[i] > 0) {
  1385. // this is our first valid sensor week data
  1386. last_week_instance = state[i].time_week;
  1387. } else if (last_week_instance != 0 && _blend_weights[i] > 0 && last_week_instance != state[i].time_week) {
  1388. // there is valid sensor week data that is inconsistent
  1389. weeks_consistent = false;
  1390. }
  1391. }
  1392. // calculate output
  1393. if (!weeks_consistent) {
  1394. // use data from highest weighted sensor
  1395. state[GPS_BLENDED_INSTANCE].time_week = state[best_index].time_week;
  1396. state[GPS_BLENDED_INSTANCE].time_week_ms = state[best_index].time_week_ms;
  1397. } else {
  1398. // use week number from highest weighting GPS (they should all have the same week number)
  1399. state[GPS_BLENDED_INSTANCE].time_week = state[best_index].time_week;
  1400. // calculate a blended value for the number of ms lapsed in the week
  1401. double temp_time_0 = 0.0;
  1402. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1403. if (_blend_weights[i] > 0.0f) {
  1404. temp_time_0 += (double)state[i].time_week_ms * (double)_blend_weights[i];
  1405. }
  1406. }
  1407. state[GPS_BLENDED_INSTANCE].time_week_ms = (uint32_t)temp_time_0;
  1408. }
  1409. // calculate a blended value for the timing data and lag
  1410. double temp_time_1 = 0.0;
  1411. double temp_time_2 = 0.0;
  1412. for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
  1413. if (_blend_weights[i] > 0.0f) {
  1414. temp_time_1 += (double)timing[i].last_fix_time_ms * (double) _blend_weights[i];
  1415. temp_time_2 += (double)timing[i].last_message_time_ms * (double)_blend_weights[i];
  1416. float gps_lag_sec = 0;
  1417. get_lag(i, gps_lag_sec);
  1418. _blended_lag_sec += gps_lag_sec * _blend_weights[i];
  1419. }
  1420. }
  1421. timing[GPS_BLENDED_INSTANCE].last_fix_time_ms = (uint32_t)temp_time_1;
  1422. timing[GPS_BLENDED_INSTANCE].last_message_time_ms = (uint32_t)temp_time_2;
  1423. }
  1424. #endif // GPS_BLENDED_INSTANCE
  1425. bool AP_GPS::is_healthy(uint8_t instance) const
  1426. {
  1427. if (instance >= GPS_MAX_INSTANCES) {
  1428. return false;
  1429. }
  1430. const uint16_t gps_max_delta_ms = 245; // 200 ms (5Hz) + 45 ms buffer
  1431. bool last_msg_valid = last_message_delta_time_ms(instance) < gps_max_delta_ms;
  1432. #if defined(GPS_BLENDED_INSTANCE)
  1433. if (instance == GPS_BLENDED_INSTANCE) {
  1434. return last_msg_valid && blend_health_check();
  1435. }
  1436. #endif
  1437. return last_msg_valid &&
  1438. drivers[instance] != nullptr &&
  1439. drivers[instance]->is_healthy();
  1440. }
  1441. bool AP_GPS::prepare_for_arming(void) {
  1442. bool all_passed = true;
  1443. for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
  1444. if (drivers[i] != nullptr) {
  1445. all_passed &= drivers[i]->prepare_for_arming();
  1446. }
  1447. }
  1448. return all_passed;
  1449. }
  1450. namespace AP {
  1451. AP_GPS &gps()
  1452. {
  1453. return *AP_GPS::get_singleton();
  1454. }
  1455. };