Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_GPS/AP_GPS.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14#include "AP_GPS_config.h"1516#if AP_GPS_ENABLED1718#include "AP_GPS.h"1920#include <AP_Common/AP_Common.h>21#include <AP_HAL/AP_HAL.h>22#include <AP_Math/AP_Math.h>23#include <AP_Notify/AP_Notify.h>24#include <GCS_MAVLink/GCS.h>25#include <AP_BoardConfig/AP_BoardConfig.h>26#include <AP_RTC/AP_RTC.h>27#include <climits>28#include <AP_SerialManager/AP_SerialManager.h>2930#include "AP_GPS_NOVA.h"31#include "AP_GPS_Blended.h"32#include "AP_GPS_ERB.h"33#include "AP_GPS_GSOF.h"34#include "AP_GPS_NMEA.h"35#include "AP_GPS_SBF.h"36#include "AP_GPS_SBP.h"37#include "AP_GPS_SBP2.h"38#include "AP_GPS_SIRF.h"39#include "AP_GPS_UBLOX.h"40#include "AP_GPS_MAV.h"41#include "AP_GPS_MSP.h"42#include "AP_GPS_ExternalAHRS.h"43#include "GPS_Backend.h"44#if HAL_SIM_GPS_ENABLED45#include "AP_GPS_SITL.h"46#endif4748#if HAL_ENABLE_DRONECAN_DRIVERS49#include <AP_CANManager/AP_CANManager.h>50#include <AP_DroneCAN/AP_DroneCAN.h>51#include "AP_GPS_DroneCAN.h"52#endif5354#include <AP_AHRS/AP_AHRS.h>55#include <AP_Logger/AP_Logger.h>56#include "AP_GPS_FixType.h"5758#if AP_GPS_RTCM_DECODE_ENABLED59#include "RTCM3_Parser.h"60#endif6162#if !AP_GPS_BLENDED_ENABLED63#if defined(GPS_BLENDED_INSTANCE)64#error GPS_BLENDED_INSTANCE should not be defined when AP_GPS_BLENDED_ENABLED is false65#endif66#endif6768#define GPS_RTK_INJECT_TO_ALL 12769#ifndef GPS_MAX_RATE_MS70#define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms71#endif72#define GPS_BAUD_TIME_MS 120073#define GPS_TIMEOUT_MS 4000u7475extern const AP_HAL::HAL &hal;7677// baudrates to try to detect GPSes with78const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U, 460800U};7980// initialisation blobs to send to the GPS to try to get it into the81// right mode.82const char AP_GPS::_initialisation_blob[] =83#if AP_GPS_UBLOX_ENABLED84UBLOX_SET_BINARY_23040085#endif86#if AP_GPS_SIRF_ENABLED87SIRF_SET_BINARY88#endif89#if AP_GPS_NMEA_UNICORE_ENABLED90NMEA_UNICORE_SETUP91#endif92"" // to compile we need *some_initialiser if all backends compiled out93;9495#if HAL_GCS_ENABLED96// ensure that our GPS_Status enumeration is 1:1 with the mavlink97// numbers of the same fix type. This allows us to do a simple cast98// from one to the other when sending GPS mavlink messages, rather99// than having some sort of mapping function from our internal100// enumeration into the mavlink enumeration. Doing things this way101// has two advantages - in the future we could add that mapping102// function and change our enumeration, and the other is that it103// allows us to build the GPS library without having the mavlink104// headers built (for example, in AP_Periph we shouldn't need mavlink105// headers).106static_assert((uint32_t)AP_GPS::GPS_Status::NO_GPS == (uint32_t)GPS_FIX_TYPE_NO_GPS, "NO_GPS incorrect");107static_assert((uint32_t)AP_GPS::GPS_Status::NO_FIX == (uint32_t)GPS_FIX_TYPE_NO_FIX, "NO_FIX incorrect");108static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_2D == (uint32_t)GPS_FIX_TYPE_2D_FIX, "FIX_2D incorrect");109static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D == (uint32_t)GPS_FIX_TYPE_3D_FIX, "FIX_3D incorrect");110static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS == (uint32_t)GPS_FIX_TYPE_DGPS, "FIX_DGPS incorrect");111static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == (uint32_t)GPS_FIX_TYPE_RTK_FLOAT, "FIX_RTK_FLOAT incorrect");112static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == (uint32_t)GPS_FIX_TYPE_RTK_FIXED, "FIX_RTK_FIXED incorrect");113#endif114115// ensure that our own enum-class status is equivalent to the116// ArduPilot-scoped AP_GPS_FixType enumeration:117static_assert((uint32_t)AP_GPS::GPS_Status::NO_GPS == (uint8_t)AP_GPS_FixType::NO_GPS, "NO_GPS incorrect");118static_assert((uint32_t)AP_GPS::GPS_Status::NO_FIX == (uint8_t)AP_GPS_FixType::NONE, "NO_FIX incorrect");119static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_2D == (uint8_t)AP_GPS_FixType::FIX_2D, "FIX_2D incorrect");120static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D == (uint8_t)AP_GPS_FixType::FIX_3D, "FIX_3D incorrect");121static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS == (uint8_t)AP_GPS_FixType::DGPS, "FIX_DGPS incorrect");122static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == (uint8_t)AP_GPS_FixType::RTK_FLOAT, "FIX_RTK_FLOAT incorrect");123static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == (uint8_t)AP_GPS_FixType::RTK_FIXED, "FIX_RTK_FIXED incorrect");124125AP_GPS *AP_GPS::_singleton;126127// table of user settable parameters128const AP_Param::GroupInfo AP_GPS::var_info[] = {129130// 0 was GPS_TYPE131132// 1 was GPS_TYPE2133134// @Param: _NAVFILTER135// @DisplayName: Navigation filter setting136// @Description: Navigation filter engine setting137// @Values: 0:Portable,2:Stationary,3:Pedestrian,4:Automotive,5:Sea,6:Airborne1G,7:Airborne2G,8:Airborne4G138// @User: Advanced139AP_GROUPINFO("_NAVFILTER", 2, AP_GPS, _navfilter, GPS_ENGINE_AIRBORNE_4G),140141#if GPS_MAX_RECEIVERS > 1142// @Param: _AUTO_SWITCH143// @DisplayName: Automatic Switchover Setting144// @Description: Automatic switchover to GPS reporting best lock, 1:UseBest selects the GPS with highest status, if both are equal the GPS with highest satellite count is used 4:Use primary if 3D fix or better, will revert to 'UseBest' behaviour if 3D fix is lost on primary145// @Values: 0:Use primary, 1:UseBest, 2:Blend, 4:Use primary if 3D fix or better146// @User: Advanced147AP_GROUPINFO("_AUTO_SWITCH", 3, AP_GPS, _auto_switch, (int8_t)GPSAutoSwitch::USE_BEST),148#endif149150// 4 was _MIN_GPS, removed Feb 2024151152// @Param: _SBAS_MODE153// @DisplayName: SBAS Mode154// @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.155// @Values: 0:Disabled,1:Enabled,2:NoChange156// @User: Advanced157AP_GROUPINFO("_SBAS_MODE", 5, AP_GPS, _sbas_mode, 2),158159// @Param: _MIN_ELEV160// @DisplayName: Minimum elevation161// @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.162// @Range: -100 90163// @Units: deg164// @User: Advanced165AP_GROUPINFO("_MIN_ELEV", 6, AP_GPS, _min_elevation, -100),166167// @Param: _INJECT_TO168// @DisplayName: Destination for GPS_INJECT_DATA MAVLink packets169// @Description: The GGS can send raw serial packets to inject data to multiple GPSes.170// @Values: 0:send to first GPS,1:send to 2nd GPS,127:send to all171// @User: Advanced172AP_GROUPINFO("_INJECT_TO", 7, AP_GPS, _inject_to, GPS_RTK_INJECT_TO_ALL),173174#if AP_GPS_SBP2_ENABLED || AP_GPS_SBP_ENABLED175// @Param: _SBP_LOGMASK176// @DisplayName: Swift Binary Protocol Logging Mask177// @Description: Masked with the SBP msg_type field to determine whether SBR1/SBR2 data is logged178// @Values: 0:None (0x0000),-1:All (0xFFFF),-256:External only (0xFF00)179// @User: Advanced180AP_GROUPINFO("_SBP_LOGMASK", 8, AP_GPS, _sbp_logmask, -256),181#endif //AP_GPS_SBP2_ENABLED || AP_GPS_SBP_ENABLED182183// @Param: _RAW_DATA184// @DisplayName: Raw data logging185// @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 arming186// @Values: 0:Ignore,1:Always log,2:Stop logging when disarmed (SBF only),5:Only log every five samples (uBlox only)187// @RebootRequired: True188// @User: Advanced189AP_GROUPINFO("_RAW_DATA", 9, AP_GPS, _raw_data, 0),190191// 10 was GPS_GNSS_MODE192193// @Param: _SAVE_CFG194// @DisplayName: Save GPS configuration195// @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.196// @Values: 0:Do not save config,1:Save config,2:Save only when needed197// @User: Advanced198AP_GROUPINFO("_SAVE_CFG", 11, AP_GPS, _save_config, 2),199200// 12 was GPS_GNSS_MODE2201202// @Param: _AUTO_CONFIG203// @DisplayName: Automatic GPS configuration204// @Description: Controls if the autopilot should automatically configure the GPS based on the parameters and default settings205// @Values: 0:Disables automatic configuration,1:Enable automatic configuration for Serial GPSes only,2:Enable automatic configuration for DroneCAN as well206// @User: Advanced207AP_GROUPINFO("_AUTO_CONFIG", 13, AP_GPS, _auto_config, 1),208209// 14 was GPS_RATE_MS210211// 15 was GPS_RATE_MS2212213// 16 was GPS_POS1214215// 17 was GPS_POS2216217// 18 was GPS_DELAY_MS218219// 19 was GPS_DELAY_MS2220221#if AP_GPS_BLENDED_ENABLED222// @Param: _BLEND_MASK223// @DisplayName: Multi GPS Blending Mask224// @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(Blend)225// @Bitmask: 0:Horiz Pos,1:Vert Pos,2:Speed226// @User: Advanced227AP_GROUPINFO("_BLEND_MASK", 20, AP_GPS, _blend_mask, 5),228229// @Param: _BLEND_TC230// @DisplayName: Blending time constant231// @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.232// @Units: s233// @Range: 5.0 30.0234// @User: Advanced235// Had key 21, no longer used236#endif237238// @Param: _DRV_OPTIONS239// @DisplayName: driver options240// @Description: Additional backend specific options241// @Bitmask: 0:Use UART2 for moving baseline on ublox,1:Use base station for GPS yaw on SBF,2:Use baudrate 115200,3:Use dedicated CAN port b/w GPSes for moving baseline,4:Use ellipsoid height instead of AMSL, 5:Override GPS satellite health of L5 band from L1 health, 6:Enable RTCM full parse even for a single channel, 7:Disable automatic full RTCM parsing when RTCM seen on more than one channel242// @User: Advanced243AP_GROUPINFO("_DRV_OPTIONS", 22, AP_GPS, _driver_options, 0),244245// 23 was GPS_COM_PORT246247// 24 was GPS_COM_PORT2248249// 25 was GPS_MB1_*250251// 26 was GPS_MB2_*252253#if GPS_MAX_RECEIVERS > 1254// @Param: _PRIMARY255// @DisplayName: Primary GPS256// @Description: This GPS will be used when GPS_AUTO_SWITCH is 0 and used preferentially with GPS_AUTO_SWITCH = 4.257// @Increment: 1258// @Values: 0:FirstGPS, 1:SecondGPS259// @User: Advanced260AP_GROUPINFO("_PRIMARY", 27, AP_GPS, _primary, 0),261#endif262263// 28 was GPS_CAN_NODEID1264265// 29 was GPS_CAN_NODEID2266267// 30 was GPS1_CAN_OVRIDE268269// 31 was GPS2_CAN_OVRIDE270271// @Group: 1_272// @Path: AP_GPS_Params.cpp273AP_SUBGROUPINFO(params[0], "1_", 32, AP_GPS, AP_GPS::Params),274275#if GPS_MAX_RECEIVERS > 1276// @Group: 2_277// @Path: AP_GPS_Params.cpp278AP_SUBGROUPINFO(params[1], "2_", 33, AP_GPS, AP_GPS::Params),279#endif280281AP_GROUPEND282};283284// constructor285AP_GPS::AP_GPS()286{287static_assert((sizeof(_initialisation_blob) * (CHAR_BIT + 2)) < (4800 * GPS_BAUD_TIME_MS * 1e-3),288"GPS initilisation blob is too large to be completely sent before the baud rate changes");289290AP_Param::setup_object_defaults(this, var_info);291292if (_singleton != nullptr) {293AP_HAL::panic("AP_GPS must be singleton");294}295_singleton = this;296}297298// return true if a specific type of GPS uses a UART299bool AP_GPS::needs_uart(GPS_Type type) const300{301switch (type) {302case GPS_TYPE_NONE:303case GPS_TYPE_HIL:304case GPS_TYPE_UAVCAN:305case GPS_TYPE_UAVCAN_RTK_BASE:306case GPS_TYPE_UAVCAN_RTK_ROVER:307case GPS_TYPE_MAV:308case GPS_TYPE_MSP:309case GPS_TYPE_EXTERNAL_AHRS:310return false;311default:312break;313}314return true;315}316317/// Startup initialisation.318void AP_GPS::init()319{320// set the default for the first GPS according to define:321params[0].type.set_default(HAL_GPS1_TYPE_DEFAULT);322323convert_parameters();324325// Set new primary param based on old auto_switch use second option326if ((_auto_switch.get() == 3) && !_primary.configured()) {327_primary.set_and_save(1);328_auto_switch.set_and_save(0);329}330331// search for serial ports with gps protocol332const auto &serial_manager = AP::serialmanager();333uint8_t uart_idx = 0;334for (uint8_t i=0; i<ARRAY_SIZE(params); i++) {335if (needs_uart(params[i].type)) {336_port[i] = serial_manager.find_serial(AP_SerialManager::SerialProtocol_GPS, uart_idx);337uart_idx++;338}339}340_last_instance_swap_ms = 0;341342// prep the state instance fields343for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) {344state[i].instance = i;345}346347// sanity check update rate348for (uint8_t i=0; i<ARRAY_SIZE(params); i++) {349auto &rate_ms = params[i].rate_ms;350if (rate_ms <= 0 || rate_ms > GPS_MAX_RATE_MS) {351rate_ms.set(GPS_MAX_RATE_MS);352}353}354355// create the blended instance if appropriate:356#if AP_GPS_BLENDED_ENABLED357drivers[GPS_BLENDED_INSTANCE] = NEW_NOTHROW AP_GPS_Blended(*this, params[GPS_BLENDED_INSTANCE], state[GPS_BLENDED_INSTANCE], timing[GPS_BLENDED_INSTANCE]);358#endif359}360361void AP_GPS::convert_parameters()362{363// find GPS's top level key364uint16_t k_param_gps_key;365if (!AP_Param::find_top_level_key_by_pointer(this, k_param_gps_key)) {366return;367}368369// table parameters to convert without scaling370static const AP_Param::ConversionInfo conversion_info[] {371// PARAMETER_CONVERSION - Added: Mar-2024 for 4.6372{ k_param_gps_key, 0, AP_PARAM_INT8, "GPS1_TYPE" },373{ k_param_gps_key, 1, AP_PARAM_INT8, "GPS2_TYPE" },374{ k_param_gps_key, 10, AP_PARAM_INT8, "GPS1_GNSS_MODE" },375{ k_param_gps_key, 12, AP_PARAM_INT8, "GPS2_GNSS_MODE" },376{ k_param_gps_key, 14, AP_PARAM_INT16, "GPS1_RATE_MS" },377{ k_param_gps_key, 15, AP_PARAM_INT16, "GPS2_RATE_MS" },378{ k_param_gps_key, 16, AP_PARAM_VECTOR3F, "GPS1_POS" },379{ k_param_gps_key, 17, AP_PARAM_VECTOR3F, "GPS2_POS" },380{ k_param_gps_key, 18, AP_PARAM_INT16, "GPS1_DELAY_MS" },381{ k_param_gps_key, 19, AP_PARAM_INT16, "GPS2_DELAY_MS" },382#if AP_GPS_SBF_ENABLED383{ k_param_gps_key, 23, AP_PARAM_INT8, "GPS1_COM_PORT" },384{ k_param_gps_key, 24, AP_PARAM_INT8, "GPS2_COM_PORT" },385#endif386387#if HAL_ENABLE_DRONECAN_DRIVERS388{ k_param_gps_key, 28, AP_PARAM_INT32, "GPS1_CAN_NODEID" },389{ k_param_gps_key, 29, AP_PARAM_INT32, "GPS2_CAN_NODEID" },390{ k_param_gps_key, 30, AP_PARAM_INT32, "GPS1_CAN_OVRIDE" },391{ k_param_gps_key, 31, AP_PARAM_INT32, "GPS2_CAN_OVRIDE" },392#endif393};394AP_Param::convert_old_parameters(conversion_info, ARRAY_SIZE(conversion_info));395396#if GPS_MOVING_BASELINE397// convert old MovingBaseline parameters398// PARAMETER_CONVERSION - Added: Mar-2024 for 4.6399for (uint8_t i=0; i<MIN(2, GPS_MAX_RECEIVERS); i++) {400// the old _MB parameters were 25 and 26:401const uint8_t old_index = 25 + i;402AP_Param::convert_class(k_param_gps_key, ¶ms[i].mb_params, params[i].mb_params.var_info, old_index, false);403}404#endif // GPS_MOVING_BASELINE405}406407// return number of active GPS sensors. Note that if the first GPS408// is not present but the 2nd is then we return 2. Note that a blended409// GPS solution is treated as an additional sensor.410uint8_t AP_GPS::num_sensors(void) const411{412#if AP_GPS_BLENDED_ENABLED413if (_output_is_blended) {414return num_instances+1;415}416#endif417return num_instances;418}419420bool AP_GPS::speed_accuracy(uint8_t instance, float &sacc) const421{422if (state[instance].have_speed_accuracy) {423sacc = state[instance].speed_accuracy;424return true;425}426return false;427}428429bool AP_GPS::horizontal_accuracy(uint8_t instance, float &hacc) const430{431if (state[instance].have_horizontal_accuracy) {432hacc = state[instance].horizontal_accuracy;433return true;434}435return false;436}437438bool AP_GPS::vertical_accuracy(uint8_t instance, float &vacc) const439{440if (state[instance].have_vertical_accuracy) {441vacc = state[instance].vertical_accuracy;442return true;443}444return false;445}446447AP_GPS::CovarianceType AP_GPS::position_covariance(const uint8_t instance, Matrix3f& cov) const448{449AP_GPS::CovarianceType cov_type = AP_GPS::CovarianceType::UNKNOWN;450cov.zero();451float hacc, vacc;452if (horizontal_accuracy(instance, hacc) && vertical_accuracy(instance, vacc))453{454cov_type = AP_GPS::CovarianceType::DIAGONAL_KNOWN;455const auto hacc_variance = hacc * hacc;456cov[0][0] = hacc_variance;457cov[1][1] = hacc_variance;458cov[2][2] = vacc * vacc;459}460// There may be a receiver that implements hdop+vdop but not accuracy461// If so, there could be a condition here to attempt to calculate it462463return cov_type;464}465466467/**468convert GPS week and milliseconds to unix epoch in milliseconds469*/470uint64_t AP_GPS::istate_time_to_epoch_ms(uint16_t gps_week, uint32_t gps_ms)471{472uint64_t fix_time_ms = UNIX_OFFSET_MSEC + gps_week * AP_MSEC_PER_WEEK + gps_ms;473return fix_time_ms;474}475476/**477calculate current time since the unix epoch in microseconds478*/479uint64_t AP_GPS::time_epoch_usec(uint8_t instance) const480{481const GPS_State &istate = state[instance];482if ((istate.last_gps_time_ms == 0 && istate.last_corrected_gps_time_us == 0) || istate.time_week == 0) {483return 0;484}485uint64_t fix_time_ms;486// add in the time since the last fix message487if (istate.last_corrected_gps_time_us != 0) {488fix_time_ms = istate_time_to_epoch_ms(istate.time_week, drivers[instance]->get_last_itow_ms());489return (fix_time_ms*1000ULL) + (AP_HAL::micros64() - istate.last_corrected_gps_time_us);490} else {491fix_time_ms = istate_time_to_epoch_ms(istate.time_week, istate.time_week_ms);492return (fix_time_ms + (AP_HAL::millis() - istate.last_gps_time_ms)) * 1000ULL;493}494}495496/**497calculate last message time since the unix epoch in microseconds498*/499uint64_t AP_GPS::last_message_epoch_usec(uint8_t instance) const500{501const GPS_State &istate = state[instance];502if (istate.time_week == 0) {503return 0;504}505return istate_time_to_epoch_ms(istate.time_week, drivers[instance]->get_last_itow_ms()) * 1000ULL;506}507508/*509send some more initialisation string bytes if there is room in the510UART transmit buffer511*/512void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size)513{514initblob_state[instance].blob = _blob;515initblob_state[instance].remaining = size;516}517518/*519initialise state for sending binary blob initialisation strings. We520may choose different blobs not just based on type but also based on521parameters.522*/523void AP_GPS::send_blob_start(uint8_t instance)524{525const auto type = params[instance].type;526527#if AP_GPS_UBLOX_ENABLED528if (type == GPS_TYPE_UBLOX && option_set(DriverOptions::UBX_Use115200)) {529static const char blob[] = UBLOX_SET_BINARY_115200;530send_blob_start(instance, blob, sizeof(blob));531return;532}533#endif // AP_GPS_UBLOX_ENABLED534535#if GPS_MOVING_BASELINE && AP_GPS_UBLOX_ENABLED536if ((type == GPS_TYPE_UBLOX_RTK_BASE ||537type == GPS_TYPE_UBLOX_RTK_ROVER) &&538!option_set(DriverOptions::UBX_MBUseUart2)) {539// we use 460800 when doing moving baseline as we need540// more bandwidth. We don't do this if using UART2, as541// in that case the RTCMv3 data doesn't go over the542// link to the flight controller543static const char blob[] = UBLOX_SET_BINARY_460800;544send_blob_start(instance, blob, sizeof(blob));545return;546}547#endif548549// the following devices don't have init blobs:550const char *blob = nullptr;551uint32_t blob_size = 0;552switch (GPS_Type(type)) {553#if AP_GPS_SBF_ENABLED554case GPS_TYPE_SBF:555case GPS_TYPE_SBF_DUAL_ANTENNA:556#endif //AP_GPS_SBF_ENABLED557#if AP_GPS_GSOF_ENABLED558case GPS_TYPE_GSOF:559#endif //AP_GPS_GSOF_ENABLED560#if AP_GPS_NOVA_ENABLED561case GPS_TYPE_NOVA:562#endif //AP_GPS_NOVA_ENABLED563#if HAL_SIM_GPS_ENABLED564case GPS_TYPE_SITL:565#endif // HAL_SIM_GPS_ENABLED566// none of these GPSs have initialisation blobs567break;568default:569// send combined initialisation blob, on the assumption that the570// GPS units will parse what they need and ignore the data they571// don't understand:572blob = _initialisation_blob;573blob_size = sizeof(_initialisation_blob);574break;575}576577send_blob_start(instance, blob, blob_size);578}579580/*581send some more initialisation string bytes if there is room in the582UART transmit buffer583*/584void AP_GPS::send_blob_update(uint8_t instance)585{586// exit immediately if no uart for this instance587if (_port[instance] == nullptr) {588return;589}590591if (initblob_state[instance].remaining == 0) {592return;593}594595// see if we can write some more of the initialisation blob596const uint16_t n = MIN(_port[instance]->txspace(),597initblob_state[instance].remaining);598const size_t written = _port[instance]->write((const uint8_t*)initblob_state[instance].blob, n);599initblob_state[instance].blob += written;600initblob_state[instance].remaining -= written;601}602603/*604run detection step for one GPS instance. If this finds a GPS then it605will fill in drivers[instance] and change state[instance].status606from NO_GPS to NO_FIX.607*/608void AP_GPS::detect_instance(uint8_t instance)609{610const uint32_t now = AP_HAL::millis();611612state[instance].status = NO_GPS;613state[instance].hdop = GPS_UNKNOWN_DOP;614state[instance].vdop = GPS_UNKNOWN_DOP;615616AP_GPS_Backend *new_gps = _detect_instance(instance);617if (new_gps == nullptr) {618return;619}620621state[instance].status = NO_FIX;622drivers[instance] = new_gps;623timing[instance].last_message_time_ms = now;624timing[instance].delta_time_ms = GPS_TIMEOUT_MS;625626new_gps->broadcast_gps_type();627}628629/*630run detection step for one GPS instance. If this finds a GPS then it631will return it - otherwise nullptr632*/633AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)634{635struct detect_state *dstate = &detect_state[instance];636637const auto type = params[instance].type;638639switch (GPS_Type(type)) {640// user has to explicitly set the MAV type, do not use AUTO641// do not try to detect the MAV type, assume it's there642case GPS_TYPE_MAV:643#if AP_GPS_MAV_ENABLED644dstate->auto_detected_baud = false; // specified, not detected645return NEW_NOTHROW AP_GPS_MAV(*this, params[instance], state[instance], nullptr);646#endif //AP_GPS_MAV_ENABLED647648// user has to explicitly set the UAVCAN type, do not use AUTO649case GPS_TYPE_UAVCAN:650case GPS_TYPE_UAVCAN_RTK_BASE:651case GPS_TYPE_UAVCAN_RTK_ROVER:652#if AP_GPS_DRONECAN_ENABLED653dstate->auto_detected_baud = false; // specified, not detected654return AP_GPS_DroneCAN::probe(*this, state[instance]);655#endif656return nullptr; // We don't do anything here if UAVCAN is not supported657#if HAL_MSP_GPS_ENABLED658case GPS_TYPE_MSP:659dstate->auto_detected_baud = false; // specified, not detected660return NEW_NOTHROW AP_GPS_MSP(*this, params[instance], state[instance], nullptr);661#endif662#if HAL_EXTERNAL_AHRS_ENABLED663case GPS_TYPE_EXTERNAL_AHRS:664if (AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::GPS) >= 0) {665dstate->auto_detected_baud = false; // specified, not detected666return NEW_NOTHROW AP_GPS_ExternalAHRS(*this, params[instance], state[instance], nullptr);667}668break;669#endif670#if AP_GPS_GSOF_ENABLED671case GPS_TYPE_GSOF:672dstate->auto_detected_baud = false; // specified, not detected673return NEW_NOTHROW AP_GPS_GSOF(*this, params[instance], state[instance], _port[instance]);674#endif //AP_GPS_GSOF_ENABLED675default:676break;677}678679if (_port[instance] == nullptr) {680// UART not available681return nullptr;682}683684// all remaining drivers automatically cycle through baud rates to detect685// the correct baud rate, and should have the selected baud broadcast686dstate->auto_detected_baud = true;687const uint32_t now = AP_HAL::millis();688689if (now - dstate->last_baud_change_ms > GPS_BAUD_TIME_MS) {690// try the next baud rate691// incrementing like this will skip the first element in array of bauds692// this is okay, and relied upon693if (dstate->probe_baud == 0) {694dstate->probe_baud = _port[instance]->get_baud_rate();695} else {696dstate->current_baud++;697if (dstate->current_baud == ARRAY_SIZE(_baudrates)) {698dstate->current_baud = 0;699}700dstate->probe_baud = _baudrates[dstate->current_baud];701}702uint16_t rx_size=0, tx_size=0;703if (type == GPS_TYPE_UBLOX_RTK_ROVER) {704tx_size = 2048;705}706if (type == GPS_TYPE_UBLOX_RTK_BASE) {707rx_size = 2048;708}709_port[instance]->begin(dstate->probe_baud, rx_size, tx_size);710_port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);711dstate->last_baud_change_ms = now;712713if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) {714send_blob_start(instance);715}716}717718if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) {719send_blob_update(instance);720}721722switch (GPS_Type(type)) {723#if AP_GPS_SBF_ENABLED724// by default the sbf/trimble gps outputs no data on its port, until configured.725case GPS_TYPE_SBF:726case GPS_TYPE_SBF_DUAL_ANTENNA:727return NEW_NOTHROW AP_GPS_SBF(*this, params[instance], state[instance], _port[instance]);728#endif //AP_GPS_SBF_ENABLED729#if AP_GPS_NOVA_ENABLED730case GPS_TYPE_NOVA:731return NEW_NOTHROW AP_GPS_NOVA(*this, params[instance], state[instance], _port[instance]);732#endif //AP_GPS_NOVA_ENABLED733734#if HAL_SIM_GPS_ENABLED735case GPS_TYPE_SITL:736return NEW_NOTHROW AP_GPS_SITL(*this, params[instance], state[instance], _port[instance]);737#endif // HAL_SIM_GPS_ENABLED738739default:740break;741}742743if (initblob_state[instance].remaining != 0) {744// don't run detection engines if we haven't sent out the initblobs745return nullptr;746}747748uint16_t bytecount = MIN(8192U, _port[instance]->available());749750while (bytecount-- > 0) {751const uint8_t data = _port[instance]->read();752(void)data; // if all backends are compiled out then "data" is unused753754#if AP_GPS_UBLOX_ENABLED755if ((type == GPS_TYPE_AUTO ||756type == GPS_TYPE_UBLOX) &&757((!_auto_config && _baudrates[dstate->current_baud] >= 38400) ||758(_baudrates[dstate->current_baud] >= 115200 && option_set(DriverOptions::UBX_Use115200)) ||759_baudrates[dstate->current_baud] == 230400) &&760AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {761return NEW_NOTHROW AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], GPS_ROLE_NORMAL);762}763764const uint32_t ublox_mb_required_baud = option_set(DriverOptions::UBX_MBUseUart2)?230400:460800;765if ((type == GPS_TYPE_UBLOX_RTK_BASE ||766type == GPS_TYPE_UBLOX_RTK_ROVER) &&767_baudrates[dstate->current_baud] == ublox_mb_required_baud &&768AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {769GPS_Role role;770if (type == GPS_TYPE_UBLOX_RTK_BASE) {771role = GPS_ROLE_MB_BASE;772} else {773role = GPS_ROLE_MB_ROVER;774}775return NEW_NOTHROW AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], role);776}777#endif // AP_GPS_UBLOX_ENABLED778#if AP_GPS_SBP2_ENABLED779if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SBP) &&780AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) {781return NEW_NOTHROW AP_GPS_SBP2(*this, params[instance], state[instance], _port[instance]);782}783#endif //AP_GPS_SBP2_ENABLED784#if AP_GPS_SBP_ENABLED785if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SBP) &&786AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {787return NEW_NOTHROW AP_GPS_SBP(*this, params[instance], state[instance], _port[instance]);788}789#endif //AP_GPS_SBP_ENABLED790#if AP_GPS_SIRF_ENABLED791if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SIRF) &&792AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) {793return NEW_NOTHROW AP_GPS_SIRF(*this, params[instance], state[instance], _port[instance]);794}795#endif796#if AP_GPS_ERB_ENABLED797if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_ERB) &&798AP_GPS_ERB::_detect(dstate->erb_detect_state, data)) {799return NEW_NOTHROW AP_GPS_ERB(*this, params[instance], state[instance], _port[instance]);800}801#endif // AP_GPS_ERB_ENABLED802#if AP_GPS_NMEA_ENABLED803if ((type == GPS_TYPE_NMEA ||804type == GPS_TYPE_HEMI ||805#if AP_GPS_NMEA_UNICORE_ENABLED806type == GPS_TYPE_UNICORE_NMEA ||807type == GPS_TYPE_UNICORE_MOVINGBASE_NMEA ||808#endif809type == GPS_TYPE_ALLYSTAR) &&810AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) {811return NEW_NOTHROW AP_GPS_NMEA(*this, params[instance], state[instance], _port[instance]);812}813#endif //AP_GPS_NMEA_ENABLED814}815816return nullptr;817}818819AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const820{821if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {822return drivers[instance]->highest_supported_status();823}824return AP_GPS::GPS_OK_FIX_3D;825}826827#if HAL_LOGGING_ENABLED828bool AP_GPS::should_log() const829{830AP_Logger *logger = AP_Logger::get_singleton();831if (logger == nullptr) {832return false;833}834if (_log_gps_bit == (uint32_t)-1) {835return false;836}837if (!logger->should_log(_log_gps_bit)) {838return false;839}840return true;841}842#endif843844845/*846update one GPS instance. This should be called at 10Hz or greater847*/848void AP_GPS::update_instance(uint8_t instance)849{850const auto type = params[instance].type;851if (type == GPS_TYPE_HIL) {852// in HIL, leave info alone853return;854}855if (type == GPS_TYPE_NONE) {856// not enabled857state[instance].status = NO_GPS;858state[instance].hdop = GPS_UNKNOWN_DOP;859state[instance].vdop = GPS_UNKNOWN_DOP;860return;861}862if (locked_ports & (1U<<instance)) {863// the port is locked by another driver864return;865}866867if (drivers[instance] == nullptr) {868// we don't yet know the GPS type of this one, or it has timed869// out and needs to be re-initialised870detect_instance(instance);871return;872}873874if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) {875send_blob_update(instance);876}877878// we have an active driver for this instance879bool result = drivers[instance]->read();880uint32_t tnow = AP_HAL::millis();881882// if we did not get a message, and the idle timer of 2 seconds883// has expired, re-initialise the GPS. This will cause GPS884// detection to run again885bool data_should_be_logged = false;886if (!result) {887if (tnow - timing[instance].last_message_time_ms > GPS_TIMEOUT_MS) {888memset((void *)&state[instance], 0, sizeof(state[instance]));889state[instance].instance = instance;890state[instance].hdop = GPS_UNKNOWN_DOP;891state[instance].vdop = GPS_UNKNOWN_DOP;892timing[instance].last_message_time_ms = tnow;893timing[instance].delta_time_ms = GPS_TIMEOUT_MS;894// do not try to detect again if type is MAV or UAVCAN895if (type == GPS_TYPE_MAV ||896type == GPS_TYPE_UAVCAN ||897type == GPS_TYPE_UAVCAN_RTK_BASE ||898type == GPS_TYPE_UAVCAN_RTK_ROVER) {899state[instance].status = NO_FIX;900} else {901// free the driver before we run the next detection, so we902// don't end up with two allocated at any time903delete drivers[instance];904drivers[instance] = nullptr;905state[instance].status = NO_GPS;906}907// log this data as a "flag" that the GPS is no longer908// valid (see PR#8144)909data_should_be_logged = true;910}911} else {912if (state[instance].corrected_timestamp_updated) {913// set the timestamp for this messages based on914// set_uart_timestamp() or per specific transport in backend915// , if available916tnow = state[instance].last_corrected_gps_time_us/1000U;917state[instance].corrected_timestamp_updated = false;918}919920// announce the GPS type once921if (!state[instance].announced_detection) {922state[instance].announced_detection = true;923GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: detected %s", instance + 1, drivers[instance]->name());924}925926// delta will only be correct after parsing two messages927timing[instance].delta_time_ms = tnow - timing[instance].last_message_time_ms;928timing[instance].last_message_time_ms = tnow;929// if GPS disabled for flight testing then don't update fix timing value930if (state[instance].status >= GPS_OK_FIX_2D && !_force_disable_gps) {931timing[instance].last_fix_time_ms = tnow;932}933934data_should_be_logged = true;935}936937#if GPS_MAX_RECEIVERS > 1938if (drivers[instance] && type == GPS_TYPE_UBLOX_RTK_BASE) {939// see if a moving baseline base has some RTCMv3 data940// which we need to pass along to the rover941const uint8_t *rtcm_data;942uint16_t rtcm_len;943if (drivers[instance]->get_RTCMV3(rtcm_data, rtcm_len)) {944for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {945if (i != instance && params[i].type == GPS_TYPE_UBLOX_RTK_ROVER) {946// pass the data to the rover947inject_data(i, rtcm_data, rtcm_len);948drivers[instance]->clear_RTCMV3();949break;950}951}952}953}954#endif955956if (data_should_be_logged) {957// keep count of delayed frames and average frame delay for health reporting958const uint16_t gps_max_delta_ms = 245; // 200 ms (5Hz) + 45 ms buffer959GPS_timing &t = timing[instance];960961if (t.delta_time_ms > gps_max_delta_ms) {962t.delayed_count++;963} else {964t.delayed_count = 0;965}966if (t.delta_time_ms < 2000) {967if (t.average_delta_ms <= 0) {968t.average_delta_ms = t.delta_time_ms;969} else {970t.average_delta_ms = 0.98f * t.average_delta_ms + 0.02f * t.delta_time_ms;971}972}973}974975#if HAL_LOGGING_ENABLED976if (data_should_be_logged && should_log()) {977Write_GPS(instance);978}979#else980(void)data_should_be_logged;981#endif982983#if AP_RTC_ENABLED984if (state[instance].status >= GPS_OK_FIX_3D) {985const uint64_t now = time_epoch_usec(instance);986if (now != 0) {987AP::rtc().set_utc_usec(now, AP_RTC::SOURCE_GPS);988}989}990#endif991}992993994#if GPS_MOVING_BASELINE995bool AP_GPS::get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading)996{997for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {998if (drivers[i] &&999state[i].relposheading_ts != 0 &&1000AP_HAL::millis() - state[i].relposheading_ts < 500) {1001relPosHeading = state[i].relPosHeading;1002relPosLength = state[i].relPosLength;1003relPosD = state[i].relPosD;1004accHeading = state[i].accHeading;1005timestamp = state[i].relposheading_ts;1006return true;1007}1008}1009return false;1010}10111012bool AP_GPS::get_RTCMV3(const uint8_t *&bytes, uint16_t &len)1013{1014for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {1015if (drivers[i] && params[i].type == GPS_TYPE_UBLOX_RTK_BASE) {1016return drivers[i]->get_RTCMV3(bytes, len);1017}1018}1019return false;1020}10211022void AP_GPS::clear_RTCMV3()1023{1024for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {1025if (drivers[i] && params[i].type == GPS_TYPE_UBLOX_RTK_BASE) {1026drivers[i]->clear_RTCMV3();1027}1028}1029}10301031/*1032inject Moving Baseline Data messages.1033*/1034void AP_GPS::inject_MBL_data(uint8_t* data, uint16_t length)1035{1036for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {1037if (params[i].type == GPS_TYPE_UBLOX_RTK_ROVER) {1038// pass the data to the rover1039inject_data(i, data, length);1040break;1041}1042}1043}1044#endif //#if GPS_MOVING_BASELINE10451046/*1047update all GPS instances1048*/1049void AP_GPS::update(void)1050{1051WITH_SEMAPHORE(rsem);10521053for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {1054update_instance(i);1055}10561057// calculate number of instances1058for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {1059if (drivers[i] != nullptr) {1060num_instances = i+1;1061}1062}10631064#if GPS_MAX_RECEIVERS > 11065#if HAL_LOGGING_ENABLED1066const uint8_t old_primary = primary_instance;1067#endif1068update_primary();1069#if HAL_LOGGING_ENABLED1070if (primary_instance != old_primary) {1071AP::logger().Write_Event(LogEvent::GPS_PRIMARY_CHANGED);1072}1073#endif // HAL_LOGING_ENABLED1074#endif // GPS_MAX_RECEIVERS > 110751076#ifndef HAL_BUILD_AP_PERIPH1077// update notify with gps status. We always base this on the primary_instance1078AP_Notify::flags.gps_status = state[primary_instance].status;1079AP_Notify::flags.gps_num_sats = state[primary_instance].num_sats;1080#endif1081}10821083/*1084update primary GPS instance1085*/1086#if GPS_MAX_RECEIVERS > 11087void AP_GPS::update_primary(void)1088{1089#if AP_GPS_BLENDED_ENABLED1090/*1091if blending is requested, attempt to calculate weighting for1092each GPS1093we do not do blending if using moving baseline yaw as the rover is1094significant lagged and gives no more information on position or1095velocity1096*/1097const bool using_moving_base = is_rtk_base(0) || is_rtk_base(1);1098if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::BLEND && !using_moving_base) {1099_output_is_blended = ((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->calc_weights();1100} else {1101_output_is_blended = false;1102((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->zero_health_counter();1103}11041105if (_output_is_blended) {1106// Use the weighting to calculate blended GPS states1107((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->calc_state();1108// set primary to the virtual instance1109primary_instance = GPS_BLENDED_INSTANCE;1110return;1111}1112#endif // AP_GPS_BLENDED_ENABLED11131114// check the primary param is set to possible GPS1115int8_t primary_param = _primary.get();1116if ((primary_param < 0) || (primary_param>=GPS_MAX_RECEIVERS)) {1117primary_param = 0;1118}1119// if primary is not enabled try first instance1120if (get_type(primary_param) == GPS_TYPE_NONE) {1121primary_param = 0;1122}11231124if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::NONE) {1125// No switching of GPSs, always use the primary instance1126primary_instance = primary_param;1127return;1128}11291130uint32_t now = AP_HAL::millis();11311132// special handling of RTK moving baseline pair. Always use the1133// base as the rover position is derived from the base, which1134// means the rover always has worse position and velocity than the1135// base. This overrides the normal logic which would select the1136// rover as it typically is in fix type 6 (RTK) whereas base is1137// usually fix type 31138for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {1139if (is_rtk_base(i) &&1140is_rtk_rover(i^1) &&1141((state[i].status >= GPS_OK_FIX_3D) || (state[i].status >= state[i^1].status))) {1142if (primary_instance != i) {1143_last_instance_swap_ms = now;1144primary_instance = i;1145}1146// don't do any more switching logic. We don't want the1147// RTK status of the rover to cause a switch1148return;1149}1150}11511152#if AP_GPS_BLENDED_ENABLED1153// handling switching away from blended GPS1154if (primary_instance == GPS_BLENDED_INSTANCE) {1155primary_instance = 0;1156for (uint8_t i=1; i<GPS_MAX_RECEIVERS; i++) {1157// choose GPS with highest state or higher number of1158// satellites. Reject a GPS with an old update time, as it1159// may be the old timestamp that triggered the loss of1160// blending1161const uint32_t delay_threshold = 400;1162const bool higher_status = state[i].status > state[primary_instance].status;1163const bool old_data_primary = (now - state[primary_instance].last_gps_time_ms) > delay_threshold;1164const bool old_data = (now - state[i].last_gps_time_ms) > delay_threshold;1165const bool equal_status = state[i].status == state[primary_instance].status;1166const bool more_sats = state[i].num_sats > state[primary_instance].num_sats;1167if (old_data && !old_data_primary) {1168// don't switch to a GPS that has not updated in 400ms1169continue;1170}1171if (state[i].status < GPS_OK_FIX_3D) {1172// don't use a GPS without 3D fix1173continue;1174}1175// select the new GPS if the primary has old data, or new1176// GPS either has higher status, or has the same status1177// and more satellites1178if ((old_data_primary && !old_data) ||1179higher_status ||1180(equal_status && more_sats)) {1181primary_instance = i;1182}1183}1184_last_instance_swap_ms = now;1185return;1186}1187#endif // AP_GPS_BLENDED_ENABLED11881189// Use primary if 3D fix or better1190if (((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::USE_PRIMARY_IF_3D_FIX) && (state[primary_param].status >= GPS_OK_FIX_3D)) {1191// Primary GPS has a least a 3D fix, switch to it if necessary1192if (primary_instance != primary_param) {1193primary_instance = primary_param;1194_last_instance_swap_ms = now;1195}1196return;1197}11981199// handle switch between real GPSs1200for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {1201if (i == primary_instance) {1202continue;1203}1204if (state[i].status > state[primary_instance].status) {1205// we have a higher status lock, or primary is set to the blended GPS, change GPS1206primary_instance = i;1207_last_instance_swap_ms = now;1208continue;1209}12101211bool another_gps_has_1_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 1);12121213if (state[i].status == state[primary_instance].status && another_gps_has_1_or_more_sats) {12141215bool another_gps_has_2_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 2);12161217if ((another_gps_has_1_or_more_sats && (now - _last_instance_swap_ms) >= 20000) ||1218(another_gps_has_2_or_more_sats && (now - _last_instance_swap_ms) >= 5000)) {1219// this GPS has more satellites than the1220// current primary, switch primary. Once we switch we will1221// then tend to stick to the new GPS as primary. We don't1222// want to switch too often as it will look like a1223// position shift to the controllers.1224primary_instance = i;1225_last_instance_swap_ms = now;1226}1227}1228}1229}1230#endif // GPS_MAX_RECEIVERS > 112311232#if HAL_GCS_ENABLED1233void AP_GPS::handle_gps_inject(const mavlink_message_t &msg)1234{1235mavlink_gps_inject_data_t packet;1236mavlink_msg_gps_inject_data_decode(&msg, &packet);12371238if (packet.len > sizeof(packet.data)) {1239// invalid packet1240return;1241}12421243handle_gps_rtcm_fragment(0, packet.data, packet.len);1244}12451246/*1247pass along a mavlink message (for MAV type)1248*/1249void AP_GPS::handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg)1250{1251switch (msg.msgid) {1252case MAVLINK_MSG_ID_GPS_RTCM_DATA:1253// pass data to de-fragmenter1254handle_gps_rtcm_data(chan, msg);1255break;1256case MAVLINK_MSG_ID_GPS_INJECT_DATA:1257handle_gps_inject(msg);1258break;1259default: {1260uint8_t i;1261for (i=0; i<num_instances; i++) {1262if ((drivers[i] != nullptr) && (params[i].type != GPS_TYPE_NONE)) {1263drivers[i]->handle_msg(msg);1264}1265}1266break;1267}1268}1269}1270#endif12711272#if HAL_MSP_GPS_ENABLED1273void AP_GPS::handle_msp(const MSP::msp_gps_data_message_t &pkt)1274{1275for (uint8_t i=0; i<num_instances; i++) {1276if (drivers[i] != nullptr && params[i].type == GPS_TYPE_MSP) {1277drivers[i]->handle_msp(pkt);1278}1279}1280}1281#endif // HAL_MSP_GPS_ENABLED12821283#if HAL_EXTERNAL_AHRS_ENABLED12841285bool AP_GPS::get_first_external_instance(uint8_t& instance) const1286{1287for (uint8_t i=0; i<num_instances; i++) {1288if (drivers[i] != nullptr && params[i].type == GPS_TYPE_EXTERNAL_AHRS) {1289instance = i;1290return true;1291}1292}1293return false;1294}12951296void AP_GPS::handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt, const uint8_t instance)1297{1298if (get_type(instance) == GPS_TYPE_EXTERNAL_AHRS && drivers[instance] != nullptr) {1299drivers[instance]->handle_external(pkt);1300}1301}1302#endif // HAL_EXTERNAL_AHRS_ENABLED13031304/**1305Lock a GPS port, preventing the GPS driver from using it. This can1306be used to allow a user to control a GPS port via the1307SERIAL_CONTROL protocol1308*/1309void AP_GPS::lock_port(uint8_t instance, bool lock)1310{13111312if (instance >= GPS_MAX_RECEIVERS) {1313return;1314}1315if (lock) {1316locked_ports |= (1U<<instance);1317} else {1318locked_ports &= ~(1U<<instance);1319}1320}13211322// Inject a packet of raw binary to a GPS1323void AP_GPS::inject_data(const uint8_t *data, uint16_t len)1324{1325//Support broadcasting to all GPSes.1326if (_inject_to == GPS_RTK_INJECT_TO_ALL) {1327for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {1328if (is_rtk_rover(i)) {1329// we don't externally inject to moving baseline rover1330continue;1331}1332inject_data(i, data, len);1333}1334} else {1335inject_data(_inject_to, data, len);1336}1337}13381339void AP_GPS::inject_data(uint8_t instance, const uint8_t *data, uint16_t len)1340{1341if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {1342drivers[instance]->inject_data(data, len);1343}1344}13451346/*1347get GPS yaw following mavlink GPS_RAW_INT and GPS2_RAW1348convention. We return 0 if the GPS is not configured to provide1349yaw. We return 65535 for a GPS configured to provide yaw that can't1350currently provide it. We return from 1 to 36000 for yaw otherwise1351*/1352uint16_t AP_GPS::gps_yaw_cdeg(uint8_t instance) const1353{1354if (!have_gps_yaw_configured(instance)) {1355return 0;1356}1357float yaw_deg, accuracy_deg;1358uint32_t time_ms;1359if (!gps_yaw_deg(instance, yaw_deg, accuracy_deg, time_ms)) {1360return 65535;1361}1362int yaw_cd = wrap_360_cd(yaw_deg * 100);1363if (yaw_cd == 0) {1364return 36000;1365}1366return yaw_cd;1367}13681369#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED1370void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)1371{1372const Location &loc = location(0);1373float hacc = 0.0f;1374float vacc = 0.0f;1375float sacc = 0.0f;1376float undulation = 0.0;1377int32_t height_elipsoid_mm = 0;1378if (get_undulation(0, undulation)) {1379height_elipsoid_mm = loc.alt*10 - undulation*1000;1380}1381horizontal_accuracy(0, hacc);1382vertical_accuracy(0, vacc);1383speed_accuracy(0, sacc);1384mavlink_msg_gps_raw_int_send(1385chan,1386last_fix_time_ms(0)*(uint64_t)1000,1387status(0),1388loc.lat, // in 1E7 degrees1389loc.lng, // in 1E7 degrees1390loc.alt * 10UL, // in mm1391get_hdop(0),1392get_vdop(0),1393ground_speed(0)*100, // cm/s1394ground_course(0)*100, // 1/100 degrees,1395num_sats(0),1396height_elipsoid_mm, // Ellipsoid height in mm1397hacc * 1000, // one-sigma standard deviation in mm1398vacc * 1000, // one-sigma standard deviation in mm1399sacc * 1000, // one-sigma standard deviation in mm/s14000, // TODO one-sigma heading accuracy standard deviation1401gps_yaw_cdeg(0));1402}1403#endif // AP_GPS_GPS_RAW_INT_SENDING_ENABLED14041405#if AP_GPS_GPS2_RAW_SENDING_ENABLED1406void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)1407{1408// always send the message if 2nd GPS is configured1409if (params[1].type == GPS_TYPE_NONE) {1410return;1411}14121413const Location &loc = location(1);1414float hacc = 0.0f;1415float vacc = 0.0f;1416float sacc = 0.0f;1417float undulation = 0.0;1418float height_elipsoid_mm = 0;1419if (get_undulation(1, undulation)) {1420height_elipsoid_mm = loc.alt*10 - undulation*1000;1421}1422horizontal_accuracy(1, hacc);1423vertical_accuracy(1, vacc);1424speed_accuracy(1, sacc);1425mavlink_msg_gps2_raw_send(1426chan,1427last_fix_time_ms(1)*(uint64_t)1000,1428status(1),1429loc.lat,1430loc.lng,1431loc.alt * 10UL,1432get_hdop(1),1433get_vdop(1),1434ground_speed(1)*100, // cm/s1435ground_course(1)*100, // 1/100 degrees,1436num_sats(1),1437state[1].rtk_num_sats,1438state[1].rtk_age_ms,1439gps_yaw_cdeg(1),1440height_elipsoid_mm, // Ellipsoid height in mm1441hacc * 1000, // one-sigma standard deviation in mm1442vacc * 1000, // one-sigma standard deviation in mm1443sacc * 1000, // one-sigma standard deviation in mm/s14440); // TODO one-sigma heading accuracy standard deviation1445}1446#endif // AP_GPS_GPS2_RAW_SENDING_ENABLED14471448#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED1449void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)1450{1451if (inst >= GPS_MAX_RECEIVERS) {1452return;1453}1454if (drivers[inst] != nullptr && drivers[inst]->supports_mavlink_gps_rtk_message()) {1455drivers[inst]->send_mavlink_gps_rtk(chan);1456}1457}1458#endif14591460bool AP_GPS::first_unconfigured_gps(uint8_t &instance) const1461{1462for (int i = 0; i < GPS_MAX_RECEIVERS; i++) {1463if (params[i].type != GPS_TYPE_NONE && (drivers[i] == nullptr || !drivers[i]->is_configured())) {1464instance = i;1465return true;1466}1467}1468return false;1469}14701471void AP_GPS::broadcast_first_configuration_failure_reason(void) const1472{1473uint8_t unconfigured;1474if (first_unconfigured_gps(unconfigured)) {1475if (drivers[unconfigured] == nullptr) {1476GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: was not found", unconfigured + 1);1477} else {1478drivers[unconfigured]->broadcast_configuration_failure_reason();1479}1480}1481}14821483// pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned1484bool AP_GPS::all_consistent(float &distance) const1485{1486// return true immediately if only one valid receiver1487if (num_instances <= 1 ||1488drivers[0] == nullptr || params[0].type == GPS_TYPE_NONE) {1489distance = 0;1490return true;1491}14921493// calculate distance1494distance = state[0].location.get_distance_NED(state[1].location).length();1495// success if distance is within 50m1496return (distance < 50);1497}14981499/*1500re-assemble fragmented RTCM data1501*/1502void AP_GPS::handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_t len)1503{1504if ((flags & 1) == 0) {1505// it is not fragmented, pass direct1506inject_data(data, len);1507return;1508}15091510// see if we need to allocate re-assembly buffer1511if (rtcm_buffer == nullptr) {1512rtcm_buffer = (struct rtcm_buffer *)calloc(1, sizeof(*rtcm_buffer));1513if (rtcm_buffer == nullptr) {1514// nothing to do but discard the data1515return;1516}1517}15181519const uint8_t fragment = (flags >> 1U) & 0x03;1520const uint8_t sequence = (flags >> 3U) & 0x1F;1521uint8_t* start_of_fragment_in_buffer = &rtcm_buffer->buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN * (uint16_t)fragment];1522bool should_clear_previous_fragments = false;15231524if (rtcm_buffer->fragments_received) {1525const bool sequence_nr_changed = rtcm_buffer->sequence != sequence;1526const bool seen_this_fragment_index = rtcm_buffer->fragments_received & (1U << fragment);15271528// check whether this is a duplicate fragment. If it is, we can1529// return early.1530if (!sequence_nr_changed && seen_this_fragment_index && !memcmp(start_of_fragment_in_buffer, data, len)) {1531return;1532}15331534// not a duplicate1535should_clear_previous_fragments = sequence_nr_changed || seen_this_fragment_index;1536}15371538if (should_clear_previous_fragments) {1539// we have one or more partial fragments already received1540// which conflict with the new fragment, discard previous fragments1541rtcm_buffer->fragment_count = 0;1542rtcm_stats.fragments_discarded += __builtin_popcount(rtcm_buffer->fragments_received);1543rtcm_buffer->fragments_received = 0;1544}15451546// add this fragment1547rtcm_buffer->sequence = sequence;1548rtcm_buffer->fragments_received |= (1U << fragment);15491550// copy the data1551memcpy(start_of_fragment_in_buffer, data, len);15521553// when we get a fragment of less than max size then we know the1554// number of fragments. Note that this means if you want to send a1555// block of RTCM data of an exact multiple of the buffer size you1556// need to send a final packet of zero length1557if (len < MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {1558rtcm_buffer->fragment_count = fragment+1;1559rtcm_buffer->total_length = (MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*fragment) + len;1560} else if (rtcm_buffer->fragments_received == 0x0F) {1561// special case of 4 full fragments1562rtcm_buffer->fragment_count = 4;1563rtcm_buffer->total_length = MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*4;1564}156515661567// see if we have all fragments1568if (rtcm_buffer->fragment_count != 0 &&1569rtcm_buffer->fragments_received == (1U << rtcm_buffer->fragment_count) - 1) {1570// we have them all, inject1571rtcm_stats.fragments_used += __builtin_popcount(rtcm_buffer->fragments_received);1572inject_data(rtcm_buffer->buffer, rtcm_buffer->total_length);1573rtcm_buffer->fragment_count = 0;1574rtcm_buffer->fragments_received = 0;1575}1576}15771578/*1579re-assemble GPS_RTCM_DATA message1580*/1581void AP_GPS::handle_gps_rtcm_data(mavlink_channel_t chan, const mavlink_message_t &msg)1582{1583mavlink_gps_rtcm_data_t packet;1584mavlink_msg_gps_rtcm_data_decode(&msg, &packet);15851586if (packet.len > sizeof(packet.data)) {1587// invalid packet1588return;1589}15901591#if AP_GPS_RTCM_DECODE_ENABLED1592if (!option_set(DriverOptions::DisableRTCMDecode)) {1593const uint16_t mask = (1U << unsigned(chan));1594rtcm.seen_mav_channels |= mask;1595if (option_set(DriverOptions::AlwaysRTCMDecode) ||1596(rtcm.seen_mav_channels & ~mask) != 0) {1597/*1598we are seeing RTCM on multiple mavlink channels. We will run1599the data through a full per-channel RTCM decoder1600*/1601if (parse_rtcm_injection(chan, packet)) {1602return;1603}1604}1605}1606#endif16071608handle_gps_rtcm_fragment(packet.flags, packet.data, packet.len);1609}16101611#if AP_GPS_RTCM_DECODE_ENABLED1612/*1613fully parse RTCM data coming in from a MAVLink channel, when we have1614a full message inject it to the GPS. This approach allows for 2 or1615more MAVLink channels to be used for the same RTCM data, allowing1616for redundent transports for maximum reliability at the cost of some1617extra CPU and a bit of re-assembly lag1618*/1619bool AP_GPS::parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm_data_t &pkt)1620{1621if (static_cast<int>(chan) >= MAVLINK_COMM_NUM_BUFFERS) {1622return false;1623}1624if (rtcm.parsers[chan] == nullptr) {1625rtcm.parsers[chan] = NEW_NOTHROW RTCM3_Parser();1626if (rtcm.parsers[chan] == nullptr) {1627return false;1628}1629GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS: RTCM parsing for chan %u", unsigned(chan));1630}1631for (uint16_t i=0; i<pkt.len; i++) {1632if (rtcm.parsers[chan]->read(pkt.data[i])) {1633// we have a full message, inject it1634const uint8_t *buf = nullptr;1635uint16_t len = rtcm.parsers[chan]->get_len(buf);16361637// see if we have already sent it. This prevents1638// duplicates from multiple sources1639const uint32_t crc = crc_crc32(0, buf, len);16401641#if HAL_LOGGING_ENABLED1642AP::logger().WriteStreaming("RTCM", "TimeUS,Chan,RTCMId,Len,CRC", "s#---", "F----", "QBHHI",1643AP_HAL::micros64(),1644uint8_t(chan),1645rtcm.parsers[chan]->get_id(),1646len,1647crc);1648#endif16491650bool already_seen = false;1651for (uint8_t c=0; c<ARRAY_SIZE(rtcm.sent_crc); c++) {1652if (rtcm.sent_crc[c] == crc) {1653// we have already sent this message1654already_seen = true;1655break;1656}1657}1658if (already_seen) {1659continue;1660}1661rtcm.sent_crc[rtcm.sent_idx] = crc;1662rtcm.sent_idx = (rtcm.sent_idx+1) % ARRAY_SIZE(rtcm.sent_crc);16631664if (buf != nullptr && len > 0) {1665inject_data(buf, len);1666}1667rtcm.parsers[chan]->reset();1668}1669}1670return true;1671}1672#endif // AP_GPS_RTCM_DECODE_ENABLED16731674#if HAL_LOGGING_ENABLED1675void AP_GPS::Write_AP_Logger_Log_Startup_messages()1676{1677for (uint8_t instance=0; instance<num_instances; instance++) {1678if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {1679continue;1680}1681drivers[instance]->Write_AP_Logger_Log_Startup_messages();1682}1683}1684#endif16851686/*1687return the expected lag (in seconds) in the position and velocity readings from the gps1688return true if the GPS hardware configuration is known or the delay parameter has been set1689*/1690bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const1691{1692// always ensure a lag is provided1693lag_sec = 0.1f;16941695if (instance >= GPS_MAX_INSTANCES) {1696return false;1697}16981699#if AP_GPS_BLENDED_ENABLED1700// return lag of blended GPS1701if (instance == GPS_BLENDED_INSTANCE) {1702return drivers[instance]->get_lag(lag_sec);1703}1704#endif17051706if (params[instance].delay_ms > 0) {1707// if the user has specified a non zero time delay, always return that value1708lag_sec = 0.001f * (float)params[instance].delay_ms;1709// the user is always right !!1710return true;1711} else if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {1712// no GPS was detected in this instance so return the worst possible lag term1713const auto type = params[instance].type;1714if (type == GPS_TYPE_NONE) {1715lag_sec = 0.0f;1716return true;1717}1718return type == GPS_TYPE_AUTO;1719} else {1720// the user has not specified a delay so we determine it from the GPS type1721return drivers[instance]->get_lag(lag_sec);1722}1723}17241725// return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin1726const Vector3f &AP_GPS::get_antenna_offset(uint8_t instance) const1727{1728if (instance >= GPS_MAX_INSTANCES) {1729// we have to return a reference so use instance 01730return params[0].antenna_offset;1731}17321733#if AP_GPS_BLENDED_ENABLED1734if (instance == GPS_BLENDED_INSTANCE) {1735// return an offset for the blended GPS solution1736return ((AP_GPS_Blended*)drivers[instance])->get_antenna_offset();1737}1738#endif17391740return params[instance].antenna_offset;1741}17421743/*1744returns the desired gps update rate in milliseconds1745this does not provide any guarantee that the GPS is updating at the requested1746rate it is simply a helper for use in the backends for determining what rate1747they should be configuring the GPS to run at1748*/1749uint16_t AP_GPS::get_rate_ms(uint8_t instance) const1750{1751// sanity check1752if (instance >= num_instances || params[instance].rate_ms <= 0) {1753return GPS_MAX_RATE_MS;1754}1755return MIN(params[instance].rate_ms, GPS_MAX_RATE_MS);1756}17571758bool AP_GPS::is_healthy(uint8_t instance) const1759{1760if (instance >= GPS_MAX_INSTANCES) {1761return false;1762}17631764if (get_type(_primary.get()) == GPS_TYPE_NONE) {1765return false;1766}17671768#ifndef HAL_BUILD_AP_PERIPH1769/*1770on AP_Periph handling of timing is done by the flight controller1771receiving the DroneCAN messages1772*/1773/*1774allow two lost frames before declaring the GPS unhealthy, but1775require the average frame rate to be close to 5Hz.17761777We allow for a rate of 3Hz average for a moving baseline rover1778due to the packet loss that happens with the RTCMv3 data and the1779fact that the rate of yaw data is not critical1780*/1781const uint8_t delay_threshold = 2;1782const float delay_avg_max = is_rtk_rover(instance) ? 333 : 215;1783const GPS_timing &t = timing[instance];1784bool delay_ok = (t.delayed_count < delay_threshold) &&1785t.average_delta_ms < delay_avg_max &&1786state[instance].lagged_sample_count < 5;1787if (!delay_ok) {1788return false;1789}1790#endif // HAL_BUILD_AP_PERIPH17911792return drivers[instance] != nullptr &&1793drivers[instance]->is_healthy();1794}17951796bool AP_GPS::prepare_for_arming(void) {1797bool all_passed = true;1798for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {1799if (drivers[i] != nullptr) {1800all_passed &= drivers[i]->prepare_for_arming();1801}1802}1803return all_passed;1804}18051806bool AP_GPS::pre_arm_checks(char failure_msg[], uint16_t failure_msg_len)1807{1808// the DroneCAN class has additional checks for DroneCAN-specific1809// parameters:1810#if AP_GPS_DRONECAN_ENABLED1811if (!AP_GPS_DroneCAN::inter_instance_pre_arm_checks(failure_msg, failure_msg_len)) {1812return false;1813}1814#endif18151816for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {1817if (is_rtk_rover(i)) {1818if (AP_HAL::millis() - state[i].gps_yaw_time_ms > 15000) {1819hal.util->snprintf(failure_msg, failure_msg_len, "GPS[%u] yaw not available", unsigned(i+1));1820return false;1821}1822}1823}18241825#if AP_GPS_BLENDED_ENABLED1826if (!drivers[GPS_BLENDED_INSTANCE]->is_healthy()) {1827hal.util->snprintf(failure_msg, failure_msg_len, "GPS blending unhealthy");1828return false;1829}1830#endif18311832return true;1833}18341835bool AP_GPS::logging_failed(void) const {1836if (!logging_enabled()) {1837return false;1838}18391840for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {1841if ((drivers[i] != nullptr) && !(drivers[i]->logging_healthy())) {1842return true;1843}1844}18451846return false;1847}18481849// get iTOW, if supported, zero otherwie1850uint32_t AP_GPS::get_itow(uint8_t instance) const1851{1852if (instance >= GPS_MAX_RECEIVERS || drivers[instance] == nullptr) {1853return 0;1854}1855return drivers[instance]->get_last_itow_ms();1856}18571858bool AP_GPS::get_error_codes(uint8_t instance, uint32_t &error_codes) const1859{1860if (instance >= GPS_MAX_RECEIVERS || drivers[instance] == nullptr) {1861return false;1862}18631864return drivers[instance]->get_error_codes(error_codes);1865}18661867// get the difference between WGS84 and AMSL. A positive value means1868// the AMSL height is higher than WGS84 ellipsoid height1869bool AP_GPS::get_undulation(uint8_t instance, float &undulation) const1870{1871if (!state[instance].have_undulation) {1872return false;1873}1874undulation = state[instance].undulation;1875return true;1876}18771878#if HAL_LOGGING_ENABLED1879// Logging support:1880// Write an GPS packet1881void AP_GPS::Write_GPS(uint8_t i)1882{1883const uint64_t time_us = AP_HAL::micros64();1884const Location &loc = location(i);18851886float yaw_deg=0, yaw_accuracy_deg=0;1887uint32_t yaw_time_ms;1888gps_yaw_deg(i, yaw_deg, yaw_accuracy_deg, yaw_time_ms);18891890const struct log_GPS pkt {1891LOG_PACKET_HEADER_INIT(LOG_GPS_MSG),1892time_us : time_us,1893instance : i,1894status : (uint8_t)status(i),1895gps_week_ms : time_week_ms(i),1896gps_week : time_week(i),1897num_sats : num_sats(i),1898hdop : get_hdop(i),1899latitude : loc.lat,1900longitude : loc.lng,1901altitude : loc.alt,1902ground_speed : ground_speed(i),1903ground_course : ground_course(i),1904vel_z : velocity(i).z,1905yaw : yaw_deg,1906used : (uint8_t)(AP::gps().primary_sensor() == i)1907};1908AP::logger().WriteBlock(&pkt, sizeof(pkt));19091910/* write auxiliary accuracy information as well */1911float hacc = 0, vacc = 0, sacc = 0;1912float undulation = 0;1913horizontal_accuracy(i, hacc);1914vertical_accuracy(i, vacc);1915speed_accuracy(i, sacc);1916get_undulation(i, undulation);1917struct log_GPA pkt2{1918LOG_PACKET_HEADER_INIT(LOG_GPA_MSG),1919time_us : time_us,1920instance : i,1921vdop : get_vdop(i),1922hacc : (uint16_t)MIN((hacc*100), UINT16_MAX),1923vacc : (uint16_t)MIN((vacc*100), UINT16_MAX),1924sacc : (uint16_t)MIN((sacc*100), UINT16_MAX),1925yaw_accuracy : yaw_accuracy_deg,1926have_vv : (uint8_t)have_vertical_velocity(i),1927sample_ms : last_message_time_ms(i),1928delta_ms : last_message_delta_time_ms(i),1929undulation : undulation,1930rtcm_fragments_used: rtcm_stats.fragments_used,1931rtcm_fragments_discarded: rtcm_stats.fragments_discarded1932};1933AP::logger().WriteBlock(&pkt2, sizeof(pkt2));1934}1935#endif19361937bool AP_GPS::is_rtk_base(uint8_t instance) const1938{1939switch (get_type(instance)) {1940case GPS_TYPE_UBLOX_RTK_BASE:1941case GPS_TYPE_UAVCAN_RTK_BASE:1942return true;1943default:1944break;1945}1946return false;1947}19481949bool AP_GPS::is_rtk_rover(uint8_t instance) const1950{1951switch (get_type(instance)) {1952case GPS_TYPE_UBLOX_RTK_ROVER:1953case GPS_TYPE_UAVCAN_RTK_ROVER:1954return true;1955default:1956break;1957}1958return false;1959}19601961/*1962get GPS based yaw1963*/1964bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, uint32_t &time_ms) const1965{1966#if GPS_MAX_RECEIVERS > 11967if (is_rtk_base(instance) && is_rtk_rover(instance^1)) {1968// return the yaw from the rover1969instance ^= 1;1970}1971#endif1972if (!have_gps_yaw(instance)) {1973return false;1974}1975yaw_deg = state[instance].gps_yaw;19761977// get lagged timestamp1978time_ms = state[instance].gps_yaw_time_ms;1979float lag_s;1980if (get_lag(instance, lag_s)) {1981uint32_t lag_ms = lag_s * 1000;1982time_ms -= lag_ms;1983}19841985if (state[instance].have_gps_yaw_accuracy) {1986accuracy_deg = state[instance].gps_yaw_accuracy;1987} else {1988// fall back to 10 degrees as a generic default1989accuracy_deg = 10;1990}1991return true;1992}19931994/*1995* Old parameter metadata. Until we have versioned parameters, keeping1996* old parameters around for a while can help with an adjustment1997* period.1998*/19992000// @Param: _TYPE2001// @DisplayName: 1st GPS type2002// @Description: GPS type of 1st GPS.Renamed in 4.6 and later to GPS1_TYPE2003// @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover,24:UnicoreNMEA,25:UnicoreMovingBaselineNMEA,26:SBF-DualAntenna2004// @RebootRequired: True2005// @User: Advanced2006// @Legacy: only included here so GCSs running stable can get the description. Omitted in the Wiki.20072008// @Param: _TYPE22009// @CopyFieldsFrom: GPS_TYPE2010// @DisplayName: 2nd GPS type.Renamed in 4.6 to GPS2_TYPE2011// @Description: GPS type of 2nd GPS2012// @Legacy: 4.5 param20132014// @Param: _GNSS_MODE2015// @DisplayName: GNSS system configuration2016// @Description: Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured).Renamed in 4.6 and later to GPS1_GNSS_MODE.2017// @Legacy: 4.5 param2018// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLONASS2019// @User: Advanced20202021// @Param: _GNSS_MODE22022// @DisplayName: GNSS system configuration.2023// @Description: Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured). Renamed in 4.6 and later to GPS2_GNSS_MODE2024// @Legacy: 4.5 param2025// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLONASS2026// @User: Advanced20272028// @Param: _RATE_MS2029// @DisplayName: GPS update rate in milliseconds2030// @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.Renamed in 4.6 and later to GPS1_RATE_MS2031// @Legacy: 4.5 param2032// @Units: ms2033// @Values: 100:10Hz,125:8Hz,200:5Hz2034// @Range: 50 2002035// @User: Advanced20362037// @Param: _RATE_MS22038// @DisplayName: GPS 2 update rate in milliseconds2039// @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.Renamed in 4.6 and later to GPS2_RATE_MS2040// @Legacy: 4.5 param2041// @Units: ms2042// @Values: 100:10Hz,125:8Hz,200:5Hz2043// @Range: 50 2002044// @User: Advanced20452046// @Param: _POS1_X2047// @DisplayName: Antenna X position offset2048// @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.Renamed in 4.6 and later to GPS1_POS_X.2049// @Legacy: 4.5 param2050// @Units: m2051// @Range: -5 52052// @Increment: 0.012053// @User: Advanced20542055// @Param: _POS1_Y2056// @DisplayName: Antenna Y position offset2057// @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.Renamed in 4.6 and later to GPS1_POS_Y.2058// @Legacy: 4.5 param2059// @Units: m2060// @Range: -5 52061// @Increment: 0.012062// @User: Advanced20632064// @Param: _POS1_Z2065// @DisplayName: Antenna Z position offset2066// @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.Renamed in 4.6 and later to GPS1_POS_Z.2067// @Legacy: 4.5 param2068// @Units: m2069// @Range: -5 52070// @Increment: 0.012071// @User: Advanced20722073// @Param: _POS2_X2074// @DisplayName: Antenna X position offset2075// @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.Renamed in 4.6 and later to GPS2_POS_X.2076// @Legacy: 4.5 param2077// @Units: m2078// @Range: -5 52079// @Increment: 0.012080// @User: Advanced20812082// @Param: _POS2_Y2083// @DisplayName: Antenna Y position offset2084// @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.Renamed in 4.6 and later to GPS2_POS_Y.2085// @Legacy: 4.5 param2086// @Units: m2087// @Range: -5 52088// @Increment: 0.012089// @User: Advanced20902091// @Param: _POS2_Z2092// @DisplayName: Antenna Z position offset2093// @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.Renamed in 4.6 and later to GPS2_POS_Z.2094// @Legacy: 4.5 param2095// @Units: m2096// @Range: -5 52097// @Increment: 0.012098// @User: Advanced20992100// @Param: _DELAY_MS2101// @DisplayName: GPS delay in milliseconds2102// @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.Renamed in 4.6 and later to GPS1_DELAY_MS.2103// @Legacy: 4.5 param2104// @Units: ms2105// @Range: 0 2502106// @User: Advanced2107// @RebootRequired: True21082109// @Param: _DELAY_MS22110// @DisplayName: GPS 2 delay in milliseconds2111// @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.Renamed in 4.6 and later to GPS2_DELAY_MS.2112// @Legacy: 4.5 param2113// @Units: ms2114// @Range: 0 2502115// @User: Advanced2116// @RebootRequired: True21172118// @Param: _COM_PORT2119// @DisplayName: GPS physical COM port2120// @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS,Renamed in 4.6 and later to GPS1_COM_PORT.2121// @Legacy: 4.5 param2122// @Range: 0 102123// @Increment: 12124// @User: Advanced2125// @Values: 0:COM1(RS232) on GSOF, 1:COM2(TTL) on GSOF2126// @RebootRequired: True21272128// @Param: _COM_PORT22129// @DisplayName: GPS physical COM port2130// @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS.Renamed in 4.6 and later to GPS1_COM_PORT.2131// @Legacy: 4.5 param2132// @Range: 0 102133// @Increment: 12134// @User: Advanced2135// @RebootRequired: True21362137// @Group: _MB1_2138// @Path: MovingBase.cpp2139// @Legacy: 4.5 param21402141// @Group: _MB2_2142// @Path: MovingBase.cpp2143// @Legacy: 4.5 param21442145// @Param: _CAN_NODEID12146// @DisplayName: GPS Node ID 12147// @Description: GPS Node id for first-discovered GPS.Renamed in 4.6 and later to GPS1_CAN_NODEID.2148// @Legacy: 4.5 param2149// @ReadOnly: True2150// @User: Advanced21512152// @Param: _CAN_NODEID22153// @DisplayName: GPS Node ID 22154// @Description: GPS Node id for second-discovered GPS.Renamed in 4.6 and later to GPS2_CAN_NODEID.2155// @Legacy: 4.5 param2156// @ReadOnly: True2157// @User: Advanced21582159/*2160* end old parameter metadata2161*/21622163namespace AP {21642165AP_GPS &gps()2166{2167return *AP_GPS::get_singleton();2168}21692170};21712172#endif // AP_GPS_ENABLED217321742175