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.h
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#pragma once1516#include "AP_GPS_config.h"1718#if AP_GPS_ENABLED1920#include <AP_HAL/AP_HAL.h>21#include <inttypes.h>22#include <AP_Common/AP_Common.h>23#include <AP_Common/Location.h>24#include <AP_Param/AP_Param.h>25#include "GPS_detect_state.h"26#include <AP_Math/AP_Math.h>27#include <AP_MSP/msp.h>28#include <AP_ExternalAHRS/AP_ExternalAHRS.h>29#include <SITL/SIM_GPS.h>30#include <GCS_MAVLink/GCS_MAVLink.h>3132#define GPS_UNKNOWN_DOP UINT16_MAX // set unknown DOP's to maximum value, which is also correct for MAVLink3334// the number of GPS leap seconds - copied into SIM_GPS.cpp35#define GPS_LEAPSECONDS_MILLIS 18000ULL3637#define UNIX_OFFSET_MSEC (17000ULL * 86400ULL + 52ULL * 10ULL * AP_MSEC_PER_WEEK - GPS_LEAPSECONDS_MILLIS)3839#ifndef GPS_MOVING_BASELINE40#define GPS_MOVING_BASELINE GPS_MAX_RECEIVERS>141#endif4243#if GPS_MOVING_BASELINE44#include "MovingBase.h"45#endif // GPS_MOVING_BASELINE4647class AP_GPS_Backend;48class RTCM3_Parser;4950/// @class AP_GPS51/// GPS driver main class52class AP_GPS53{54friend class AP_GPS_Blended;55friend class AP_GPS_ERB;56friend class AP_GPS_GSOF;57friend class AP_GPS_MAV;58friend class AP_GPS_MSP;59friend class AP_GPS_ExternalAHRS;60friend class AP_GPS_NMEA;61friend class AP_GPS_NOVA;62friend class AP_GPS_PX4;63friend class AP_GPS_SBF;64friend class AP_GPS_SBP;65friend class AP_GPS_SBP2;66friend class AP_GPS_SIRF;67friend class AP_GPS_UBLOX;68friend class AP_GPS_Backend;69friend class AP_GPS_DroneCAN;7071public:72AP_GPS();7374/* Do not allow copies */75CLASS_NO_COPY(AP_GPS);7677static AP_GPS *get_singleton() {78return _singleton;79}8081// allow threads to lock against GPS update82HAL_Semaphore &get_semaphore(void) {83return rsem;84}8586// GPS driver types87enum GPS_Type {88GPS_TYPE_NONE = 0,89GPS_TYPE_AUTO = 1,90GPS_TYPE_UBLOX = 2,91// GPS_TYPE_MTK = 3, // driver removed92// GPS_TYPE_MTK19 = 4, // driver removed93GPS_TYPE_NMEA = 5,94GPS_TYPE_SIRF = 6,95GPS_TYPE_HIL = 7,96GPS_TYPE_SBP = 8,97GPS_TYPE_UAVCAN = 9,98GPS_TYPE_SBF = 10,99GPS_TYPE_GSOF = 11,100GPS_TYPE_ERB = 13,101GPS_TYPE_MAV = 14,102GPS_TYPE_NOVA = 15,103GPS_TYPE_HEMI = 16, // hemisphere NMEA104GPS_TYPE_UBLOX_RTK_BASE = 17,105GPS_TYPE_UBLOX_RTK_ROVER = 18,106GPS_TYPE_MSP = 19,107GPS_TYPE_ALLYSTAR = 20, // AllyStar NMEA108GPS_TYPE_EXTERNAL_AHRS = 21,109GPS_TYPE_UAVCAN_RTK_BASE = 22,110GPS_TYPE_UAVCAN_RTK_ROVER = 23,111GPS_TYPE_UNICORE_NMEA = 24,112GPS_TYPE_UNICORE_MOVINGBASE_NMEA = 25,113GPS_TYPE_SBF_DUAL_ANTENNA = 26,114#if HAL_SIM_GPS_ENABLED115GPS_TYPE_SITL = 100,116#endif117};118119// convenience methods for working out what general type an instance is:120bool is_rtk_base(uint8_t instance) const;121bool is_rtk_rover(uint8_t instance) const;122123// params for an instance:124class Params {125public:126// Constructor127Params(void);128129AP_Enum<GPS_Type> type;130AP_Int8 gnss_mode;131AP_Int16 rate_ms; // this parameter should always be accessed using get_rate_ms()132AP_Vector3f antenna_offset;133AP_Int16 delay_ms;134AP_Int8 com_port;135#if HAL_ENABLE_DRONECAN_DRIVERS136AP_Int32 node_id;137AP_Int32 override_node_id;138#endif139#if GPS_MOVING_BASELINE140MovingBase mb_params;141#endif // GPS_MOVING_BASELINE142143static const struct AP_Param::GroupInfo var_info[];144};145146/// GPS status codes. These are kept aligned with MAVLink by147/// static_assert in AP_GPS.cpp148enum GPS_Status {149NO_GPS = 0, ///< No GPS connected/detected150NO_FIX = 1, ///< Receiving valid GPS messages but no lock151GPS_OK_FIX_2D = 2, ///< Receiving valid messages and 2D lock152GPS_OK_FIX_3D = 3, ///< Receiving valid messages and 3D lock153GPS_OK_FIX_3D_DGPS = 4, ///< Receiving valid messages and 3D lock with differential improvements154GPS_OK_FIX_3D_RTK_FLOAT = 5, ///< Receiving valid messages and 3D RTK Float155GPS_OK_FIX_3D_RTK_FIXED = 6, ///< Receiving valid messages and 3D RTK Fixed156};157158// GPS navigation engine settings. Not all GPS receivers support159// this160enum GPS_Engine_Setting {161GPS_ENGINE_NONE = -1,162GPS_ENGINE_PORTABLE = 0,163GPS_ENGINE_STATIONARY = 2,164GPS_ENGINE_PEDESTRIAN = 3,165GPS_ENGINE_AUTOMOTIVE = 4,166GPS_ENGINE_SEA = 5,167GPS_ENGINE_AIRBORNE_1G = 6,168GPS_ENGINE_AIRBORNE_2G = 7,169GPS_ENGINE_AIRBORNE_4G = 8170};171172// role for auto-config173enum GPS_Role {174GPS_ROLE_NORMAL,175GPS_ROLE_MB_BASE,176GPS_ROLE_MB_ROVER,177};178179// GPS Covariance Types matching ROS2 sensor_msgs/msg/NavSatFix180enum class CovarianceType : uint8_t {181UNKNOWN = 0, ///< The GPS does not support any accuracy metrics182APPROXIMATED = 1, ///< The accuracy is approximated through metrics such as HDOP/VDOP183DIAGONAL_KNOWN = 2, ///< The diagonal (east, north, up) components of covariance are reported by the GPS184KNOWN = 3, ///< The full covariance array is reported by the GPS185};186187/*188The GPS_State structure is filled in by the backend driver as it189parses each message from the GPS.190*/191struct GPS_State {192uint8_t instance; // the instance number of this GPS193194// all the following fields must all be filled by the backend driver195GPS_Status status; ///< driver fix status196uint32_t time_week_ms; ///< GPS time (milliseconds from start of GPS week)197uint16_t time_week; ///< GPS week number198Location location; ///< last fix location199float ground_speed; ///< ground speed in m/s200float ground_course; ///< ground course in degrees, wrapped 0-360201float gps_yaw; ///< GPS derived yaw information, if available (degrees)202uint32_t gps_yaw_time_ms; ///< timestamp of last GPS yaw reading203bool gps_yaw_configured; ///< GPS is configured to provide yaw204uint16_t hdop; ///< horizontal dilution of precision, scaled by a factor of 100 (155 means the HDOP value is 1.55)205uint16_t vdop; ///< vertical dilution of precision, scaled by a factor of 100 (155 means the VDOP value is 1.55)206uint8_t num_sats; ///< Number of visible satellites207Vector3f velocity; ///< 3D velocity in m/s, in NED format208float speed_accuracy; ///< 3D velocity RMS accuracy estimate in m/s209float horizontal_accuracy; ///< horizontal RMS accuracy estimate in m210float vertical_accuracy; ///< vertical RMS accuracy estimate in m211float gps_yaw_accuracy; ///< heading accuracy of the GPS in degrees212bool have_vertical_velocity; ///< does GPS give vertical velocity? Set to true only once available.213bool have_speed_accuracy; ///< does GPS give speed accuracy? Set to true only once available.214bool have_horizontal_accuracy; ///< does GPS give horizontal position accuracy? Set to true only once available.215bool have_vertical_accuracy; ///< does GPS give vertical position accuracy? Set to true only once available.216bool have_gps_yaw; ///< does GPS give yaw? Set to true only once available.217bool have_gps_yaw_accuracy; ///< does the GPS give a heading accuracy estimate? Set to true only once available218float undulation; //<height that WGS84 is above AMSL at the current location219bool have_undulation; ///<do we have a value for the undulation220uint32_t last_gps_time_ms; ///< the system time we got the last GPS timestamp, milliseconds221bool announced_detection; ///< true once we have announced GPS has been seen to the user222uint64_t last_corrected_gps_time_us;///< the system time we got the last corrected GPS timestamp, microseconds223bool corrected_timestamp_updated; ///< true if the corrected timestamp has been updated224uint32_t lagged_sample_count; ///< number of samples with 50ms more lag than expected225226// all the following fields must only all be filled by RTK capable backend drivers227uint32_t rtk_time_week_ms; ///< GPS Time of Week of last baseline in milliseconds228uint16_t rtk_week_number; ///< GPS Week Number of last baseline229uint32_t rtk_age_ms; ///< GPS age of last baseline correction in milliseconds (0 when no corrections, 0xFFFFFFFF indicates overflow)230uint8_t rtk_num_sats; ///< Current number of satellites used for RTK calculation231uint8_t rtk_baseline_coords_type; ///< Coordinate system of baseline. 0 == ECEF, 1 == NED232int32_t rtk_baseline_x_mm; ///< Current baseline in ECEF x or NED north component in mm233int32_t rtk_baseline_y_mm; ///< Current baseline in ECEF y or NED east component in mm234int32_t rtk_baseline_z_mm; ///< Current baseline in ECEF z or NED down component in mm235uint32_t rtk_accuracy; ///< Current estimate of 3D baseline accuracy (receiver dependent, typical 0 to 9999)236int32_t rtk_iar_num_hypotheses; ///< Current number of integer ambiguity hypotheses237238// UBX Relative Position and Heading message information239float relPosHeading; ///< Reported Heading in degrees240float relPosLength; ///< Reported Position horizontal distance in meters241float relPosD; ///< Reported Vertical distance in meters242float accHeading; ///< Reported Heading Accuracy in degrees243uint32_t relposheading_ts; ///< True if new data has been received since last time it was false244};245246/// Startup initialisation.247void init();248249// ethod for APPPeriph to set the default type for the first GPS instance:250void set_default_type_for_gps1(uint8_t default_type) {251params[0].type.set_default(default_type);252}253254/// Update GPS state based on possible bytes received from the module.255/// This routine must be called periodically (typically at 10Hz or256/// more) to process incoming data.257void update(void);258259// Pass mavlink data to message handlers (for MAV type)260void handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg);261#if HAL_MSP_GPS_ENABLED262void handle_msp(const MSP::msp_gps_data_message_t &pkt);263#endif264#if HAL_EXTERNAL_AHRS_ENABLED265// Retrieve the first instance ID that is configured as type GPS_TYPE_EXTERNAL_AHRS.266// Can be used by external AHRS systems that only report one GPS to get the instance ID.267// Returns true if an instance was found, false otherwise.268bool get_first_external_instance(uint8_t& instance) const WARN_IF_UNUSED;269void handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt, const uint8_t instance);270#endif271272// Accessor functions273274// return number of active GPS sensors. Note that if the first GPS275// is not present but the 2nd is then we return 2. Note that a blended276// GPS solution is treated as an additional sensor.277uint8_t num_sensors(void) const;278279// Return the index of the primary sensor which is the index of the sensor contributing to280// the output. A blended solution is available as an additional instance281uint8_t primary_sensor(void) const {282return primary_instance;283}284285/// Query GPS status286GPS_Status status(uint8_t instance) const {287if (_force_disable_gps && state[instance].status > NO_FIX) {288return NO_FIX;289}290return state[instance].status;291}292GPS_Status status(void) const {293return status(primary_instance);294}295296// return a single human-presentable character representing the297// fix type. For space-constrained human-readable displays298char status_onechar(void) const {299switch (status()) {300case AP_GPS::NO_GPS:301return ' ';302case AP_GPS::NO_FIX:303return '-';304case AP_GPS::GPS_OK_FIX_2D:305return '2';306case AP_GPS::GPS_OK_FIX_3D:307return '3';308case AP_GPS::GPS_OK_FIX_3D_DGPS:309return '4';310case AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT:311return '5';312case AP_GPS::GPS_OK_FIX_3D_RTK_FIXED:313return '6';314}315// should never reach here; compiler flags guarantees this.316return '?';317}318319// Query the highest status this GPS supports (always reports GPS_OK_FIX_3D for the blended GPS)320GPS_Status highest_supported_status(uint8_t instance) const WARN_IF_UNUSED;321322// location of last fix323const Location &location(uint8_t instance) const {324return state[instance].location;325}326const Location &location() const {327return location(primary_instance);328}329330// get the difference between WGS84 and AMSL. A positive value means331// the AMSL height is higher than WGS84 ellipsoid height332bool get_undulation(uint8_t instance, float &undulation) const;333334// get the difference between WGS84 and AMSL. A positive value means335// the AMSL height is higher than WGS84 ellipsoid height336bool get_undulation(float &undulation) const {337return get_undulation(primary_instance, undulation);338}339340// report speed accuracy341bool speed_accuracy(uint8_t instance, float &sacc) const;342bool speed_accuracy(float &sacc) const {343return speed_accuracy(primary_instance, sacc);344}345346bool horizontal_accuracy(uint8_t instance, float &hacc) const;347bool horizontal_accuracy(float &hacc) const {348return horizontal_accuracy(primary_instance, hacc);349}350351bool vertical_accuracy(uint8_t instance, float &vacc) const;352bool vertical_accuracy(float &vacc) const {353return vertical_accuracy(primary_instance, vacc);354}355356CovarianceType position_covariance(const uint8_t instance, Matrix3f& cov) const WARN_IF_UNUSED;357358// 3D velocity in NED format359const Vector3f &velocity(uint8_t instance) const {360return state[instance].velocity;361}362const Vector3f &velocity() const {363return velocity(primary_instance);364}365366// ground speed in m/s367float ground_speed(uint8_t instance) const {368return state[instance].ground_speed;369}370float ground_speed() const {371return ground_speed(primary_instance);372}373374// ground speed in cm/s375uint32_t ground_speed_cm(void) const {376return ground_speed() * 100;377}378379// ground course in degrees380float ground_course(uint8_t instance) const {381return state[instance].ground_course;382}383float ground_course() const {384return ground_course(primary_instance);385}386// ground course in centi-degrees387int32_t ground_course_cd(uint8_t instance) const {388return ground_course(instance) * 100;389}390int32_t ground_course_cd() const {391return ground_course_cd(primary_instance);392}393394// yaw in degrees if available395bool gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, uint32_t &time_ms) const;396bool gps_yaw_deg(float &yaw_deg, float &accuracy_deg, uint32_t &time_ms) const {397return gps_yaw_deg(primary_instance, yaw_deg, accuracy_deg, time_ms);398}399400// number of locked satellites401uint8_t num_sats(uint8_t instance) const {402return state[instance].num_sats;403}404uint8_t num_sats() const {405return num_sats(primary_instance);406}407408// GPS time of week in milliseconds409uint32_t time_week_ms(uint8_t instance) const {410return state[instance].time_week_ms;411}412uint32_t time_week_ms() const {413return time_week_ms(primary_instance);414}415416// GPS week417uint16_t time_week(uint8_t instance) const {418return state[instance].time_week;419}420uint16_t time_week() const {421return time_week(primary_instance);422}423424// horizontal dilution of precision425uint16_t get_hdop(uint8_t instance) const {426return state[instance].hdop;427}428uint16_t get_hdop() const {429return get_hdop(primary_instance);430}431432// vertical dilution of precision433uint16_t get_vdop(uint8_t instance) const {434return state[instance].vdop;435}436uint16_t get_vdop() const {437return get_vdop(primary_instance);438}439440// the time we got our last fix in system milliseconds. This is441// used when calculating how far we might have moved since that fix442uint32_t last_fix_time_ms(uint8_t instance) const {443return timing[instance].last_fix_time_ms;444}445uint32_t last_fix_time_ms(void) const {446return last_fix_time_ms(primary_instance);447}448449// the time we last processed a message in milliseconds. This is450// used to indicate that we have new GPS data to process451uint32_t last_message_time_ms(uint8_t instance) const {452return timing[instance].last_message_time_ms;453}454uint32_t last_message_time_ms(void) const {455return last_message_time_ms(primary_instance);456}457458// system time delta between the last two reported positions459uint16_t last_message_delta_time_ms(uint8_t instance) const {460return timing[instance].delta_time_ms;461}462uint16_t last_message_delta_time_ms(void) const {463return last_message_delta_time_ms(primary_instance);464}465466// return true if the GPS supports vertical velocity values467bool have_vertical_velocity(uint8_t instance) const {468return state[instance].have_vertical_velocity;469}470bool have_vertical_velocity(void) const {471return have_vertical_velocity(primary_instance);472}473474// return true if the GPS currently has yaw available475bool have_gps_yaw(uint8_t instance) const {476return !_force_disable_gps_yaw && state[instance].have_gps_yaw;477}478bool have_gps_yaw(void) const {479return have_gps_yaw(primary_instance);480}481482// return true if the GPS is configured to provide yaw. This will483// be true if we expect the GPS to provide yaw, even if it484// currently is not able to provide yaw485bool have_gps_yaw_configured(uint8_t instance) const {486return state[instance].gps_yaw_configured;487}488489// the expected lag (in seconds) in the position and velocity readings from the gps490// return true if the GPS hardware configuration is known or the lag parameter has been set manually491bool get_lag(uint8_t instance, float &lag_sec) const;492bool get_lag(float &lag_sec) const {493return get_lag(primary_instance, lag_sec);494}495496// return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin497const Vector3f &get_antenna_offset(uint8_t instance) const;498499// lock out a GPS port, allowing another application to use the port500void lock_port(uint8_t instance, bool locked);501502//MAVLink Status Sending503void send_mavlink_gps_raw(mavlink_channel_t chan);504void send_mavlink_gps2_raw(mavlink_channel_t chan);505506void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst);507508// Returns true if there is an unconfigured GPS, and provides the instance number of the first non configured GPS509bool first_unconfigured_gps(uint8_t &instance) const WARN_IF_UNUSED;510void broadcast_first_configuration_failure_reason(void) const;511512// pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned513bool all_consistent(float &distance) const;514515// handle sending of initialisation strings to the GPS - only used by backends516void send_blob_start(uint8_t instance);517void send_blob_start(uint8_t instance, const char *_blob, uint16_t size);518void send_blob_update(uint8_t instance);519520// return last fix time since the 1/1/1970 in microseconds521uint64_t time_epoch_usec(uint8_t instance) const;522uint64_t time_epoch_usec(void) const {523return time_epoch_usec(primary_instance);524}525526uint64_t last_message_epoch_usec(uint8_t instance) const;527uint64_t last_message_epoch_usec() const {528return last_message_epoch_usec(primary_instance);529}530531// convert GPS week and millis to unix epoch in ms532static uint64_t istate_time_to_epoch_ms(uint16_t gps_week, uint32_t gps_ms);533534static const struct AP_Param::GroupInfo var_info[];535536#if HAL_LOGGING_ENABLED537void Write_AP_Logger_Log_Startup_messages();538#endif539540// indicate which bit in LOG_BITMASK indicates gps logging enabled541void set_log_gps_bit(uint32_t bit) { _log_gps_bit = bit; }542543// report if the gps is healthy (this is defined as existing, an update at a rate greater than 4Hz,544// as well as any driver specific behaviour)545bool is_healthy(uint8_t instance) const;546bool is_healthy(void) const { return is_healthy(primary_instance); }547548// returns true if all GPS instances have passed all final arming checks/state changes549bool prepare_for_arming(void);550551// returns true if all GPS backend drivers are OK with the concept552// of the vehicle arming. this is for backends to be able to553// spout pre arm error messages554bool pre_arm_checks(char failure_msg[], uint16_t failure_msg_len);555556// returns false if any GPS drivers are not performing their logging appropriately557bool logging_failed(void) const;558559bool logging_present(void) const { return _raw_data != 0; }560bool logging_enabled(void) const { return _raw_data != 0; }561562// used to disable GPS for GPS failure testing in flight563void force_disable(bool disable) {564_force_disable_gps = disable;565}566567// used to disable GPS yaw for GPS failure testing in flight568void set_force_disable_yaw(bool disable) {569_force_disable_gps_yaw = disable;570}571572// handle possibly fragmented RTCM injection data573void handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_t len);574575// get configured type by instance576GPS_Type get_type(uint8_t instance) const {577return instance>=ARRAY_SIZE(params) ? GPS_Type::GPS_TYPE_NONE : params[instance].type;578}579580// get iTOW, if supported, zero otherwie581uint32_t get_itow(uint8_t instance) const;582583bool get_error_codes(uint8_t instance, uint32_t &error_codes) const;584bool get_error_codes(uint32_t &error_codes) const { return get_error_codes(primary_instance, error_codes); }585586enum class SBAS_Mode : int8_t {587Disabled = 0,588Enabled = 1,589DoNotChange = 2,590};591592#if GPS_MOVING_BASELINE593// methods used by UAVCAN GPS driver and AP_Periph for moving baseline594void inject_MBL_data(uint8_t* data, uint16_t length);595bool get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) WARN_IF_UNUSED;596bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len);597void clear_RTCMV3();598#endif // GPS_MOVING_BASELINE599600#if !AP_GPS_BLENDED_ENABLED601uint8_t get_auto_switch_type() const { return _auto_switch; }602#endif603604protected:605606// configuration parameters607Params params[GPS_MAX_INSTANCES];608AP_Int8 _navfilter;609AP_Int8 _auto_switch;610AP_Int16 _sbp_logmask;611AP_Int8 _inject_to;612uint32_t _last_instance_swap_ms;613AP_Enum<SBAS_Mode> _sbas_mode;614AP_Int8 _min_elevation;615AP_Int8 _raw_data;616AP_Int8 _save_config;617AP_Int8 _auto_config;618AP_Int8 _blend_mask;619AP_Int16 _driver_options;620AP_Int8 _primary;621622uint32_t _log_gps_bit = -1;623624enum DriverOptions : int16_t {625UBX_MBUseUart2 = (1U << 0U),626SBF_UseBaseForYaw = (1U << 1U),627UBX_Use115200 = (1U << 2U),628UAVCAN_MBUseDedicatedBus = (1 << 3U),629HeightEllipsoid = (1U << 4),630GPSL5HealthOverride = (1U << 5),631AlwaysRTCMDecode = (1U << 6),632DisableRTCMDecode = (1U << 7),633};634635// check if an option is set636bool option_set(const DriverOptions option) const {637return (uint8_t(_driver_options.get()) & uint8_t(option)) != 0;638}639640private:641static AP_GPS *_singleton;642HAL_Semaphore rsem;643644// returns the desired gps update rate in milliseconds645// this does not provide any guarantee that the GPS is updating at the requested646// rate it is simply a helper for use in the backends for determining what rate647// they should be configuring the GPS to run at648uint16_t get_rate_ms(uint8_t instance) const;649650struct GPS_timing {651// the time we got our last fix in system milliseconds652uint32_t last_fix_time_ms;653654// the time we got our last message in system milliseconds655uint32_t last_message_time_ms;656657// delta time between the last pair of GPS updates in system milliseconds658uint16_t delta_time_ms;659660// count of delayed frames661uint8_t delayed_count;662663// the average time delta664float average_delta_ms;665};666// Note allowance for an additional instance to contain blended data667GPS_timing timing[GPS_MAX_INSTANCES];668GPS_State state[GPS_MAX_INSTANCES];669AP_GPS_Backend *drivers[GPS_MAX_INSTANCES];670AP_HAL::UARTDriver *_port[GPS_MAX_RECEIVERS];671672/// primary GPS instance673uint8_t primary_instance;674675/// number of GPS instances present676uint8_t num_instances;677678// which ports are locked679uint8_t locked_ports;680681// state of auto-detection process, per instance682struct detect_state {683uint32_t last_baud_change_ms;684uint8_t current_baud;685uint32_t probe_baud;686bool auto_detected_baud;687#if AP_GPS_UBLOX_ENABLED688struct UBLOX_detect_state ublox_detect_state;689#endif690#if AP_GPS_SIRF_ENABLED691struct SIRF_detect_state sirf_detect_state;692#endif693#if AP_GPS_NMEA_ENABLED694struct NMEA_detect_state nmea_detect_state;695#endif696#if AP_GPS_SBP_ENABLED697struct SBP_detect_state sbp_detect_state;698#endif699#if AP_GPS_SBP2_ENABLED700struct SBP2_detect_state sbp2_detect_state;701#endif702#if AP_GPS_ERB_ENABLED703struct ERB_detect_state erb_detect_state;704#endif705} detect_state[GPS_MAX_RECEIVERS];706707struct {708const char *blob;709uint16_t remaining;710} initblob_state[GPS_MAX_RECEIVERS];711712static const uint32_t _baudrates[];713static const char _initialisation_blob[];714static const char _initialisation_raw_blob[];715716void detect_instance(uint8_t instance);717// run detection step for one GPS instance. If this finds a GPS then it718// will return it - otherwise nullptr719AP_GPS_Backend *_detect_instance(uint8_t instance);720721void update_instance(uint8_t instance);722723/*724buffer for re-assembling RTCM data for GPS injection.725The 8 bit flags field in GPS_RTCM_DATA is interpreted as:7261 bit for "is fragmented"7272 bits for fragment number7285 bits for sequence number729730The rtcm_buffer is allocated on first use. Once a block of data731is successfully reassembled it is injected into all active GPS732backends. This assumes we don't want more than 4*180=720 bytes733in a RTCM data block734*/735struct rtcm_buffer {736uint8_t fragments_received;737uint8_t sequence;738uint8_t fragment_count;739uint16_t total_length;740uint8_t buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*4];741} *rtcm_buffer;742743struct {744uint16_t fragments_used;745uint16_t fragments_discarded;746} rtcm_stats;747748// re-assemble GPS_RTCM_DATA message749void handle_gps_rtcm_data(mavlink_channel_t chan, const mavlink_message_t &msg);750void handle_gps_inject(const mavlink_message_t &msg);751752//Inject a packet of raw binary to a GPS753void inject_data(const uint8_t *data, uint16_t len);754void inject_data(uint8_t instance, const uint8_t *data, uint16_t len);755756#if AP_GPS_BLENDED_ENABLED757bool _output_is_blended; // true when a blended GPS solution being output758#endif759760bool should_log() const;761762bool needs_uart(GPS_Type type) const;763764#if GPS_MAX_RECEIVERS > 1765/// Update primary instance766void update_primary(void);767#endif768769// helper function for mavlink gps yaw770uint16_t gps_yaw_cdeg(uint8_t instance) const;771772// Auto configure types773enum GPS_AUTO_CONFIG {774GPS_AUTO_CONFIG_DISABLE = 0,775GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY = 1,776GPS_AUTO_CONFIG_ENABLE_ALL = 2,777};778779enum class GPSAutoSwitch {780NONE = 0,781USE_BEST = 1,782BLEND = 2,783//USE_SECOND = 3, deprecated for new primary param784USE_PRIMARY_IF_3D_FIX = 4,785};786787// used for flight testing with GPS loss788bool _force_disable_gps;789790// used for flight testing with GPS yaw loss791bool _force_disable_gps_yaw;792793// logging support794void Write_GPS(uint8_t instance);795796#if AP_GPS_RTCM_DECODE_ENABLED797/*798per mavlink channel RTCM decoder, enabled with RTCM decode799option in GPS_DRV_OPTIONS800*/801struct {802RTCM3_Parser *parsers[MAVLINK_COMM_NUM_BUFFERS];803uint32_t sent_crc[32];804uint8_t sent_idx;805uint16_t seen_mav_channels;806} rtcm;807bool parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm_data_t &pkt);808#endif809810void convert_parameters();811};812813namespace AP {814AP_GPS &gps();815};816817#endif // AP_GPS_ENABLED818819820