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/GPS_Backend.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*/1415/*16GPS driver backend class17*/18#pragma once1920#include "AP_GPS_config.h"2122#if AP_GPS_ENABLED2324#include <GCS_MAVLink/GCS_MAVLink.h>25#include <GCS_MAVLink/GCS_config.h>26#include <AP_RTC/JitterCorrection.h>27#include "AP_GPS.h"28#include "AP_GPS_config.h"2930#ifndef AP_GPS_DEBUG_LOGGING_ENABLED31// enable this to log all bytes from the GPS. Also needs a call to32// log_data() in each backend33#define AP_GPS_DEBUG_LOGGING_ENABLED 034#endif3536#ifndef AP_GPS_MB_MIN_LAG37#define AP_GPS_MB_MIN_LAG 0.05f38#endif3940#ifndef AP_GPS_MB_MAX_LAG41#define AP_GPS_MB_MAX_LAG 0.25f42#endif4344#if AP_GPS_DEBUG_LOGGING_ENABLED45#include <AP_HAL/utility/RingBuffer.h>46#endif4748class AP_GPS_Backend49{50public:51AP_GPS_Backend(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);5253// we declare a virtual destructor so that GPS drivers can54// override with a custom destructor if need be.55virtual ~AP_GPS_Backend(void) {}5657// The read() method is the only one needed in each driver. It58// should return true when the backend has successfully received a59// valid packet from the GPS.60virtual bool read() = 0;6162// Highest status supported by this GPS.63// Allows external system to identify type of receiver connected.64virtual AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D; }6566virtual bool is_configured(void) const { return true; }6768virtual void inject_data(const uint8_t *data, uint16_t len);6970#if HAL_GCS_ENABLED71//MAVLink methods72virtual bool supports_mavlink_gps_rtk_message() const { return false; }73#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED74virtual void send_mavlink_gps_rtk(mavlink_channel_t chan);75#endif76virtual void handle_msg(const mavlink_message_t &msg) { return ; }77#endif7879virtual void broadcast_configuration_failure_reason(void) const { return ; }8081#if HAL_MSP_GPS_ENABLED82virtual void handle_msp(const MSP::msp_gps_data_message_t &pkt) { return; }83#endif84#if HAL_EXTERNAL_AHRS_ENABLED85virtual void handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt) { return; }86#endif8788// driver specific lag, returns true if the driver is confident in the provided lag89virtual bool get_lag(float &lag) const { lag = 0.2f; return true; }9091// driver specific health, returns true if the driver is healthy92virtual bool is_healthy(void) const { return true; }93// returns true if the GPS is doing any logging it is expected to94virtual bool logging_healthy(void) const { return true; }9596virtual const char *name() const = 0;9798void broadcast_gps_type() const;99#if HAL_LOGGING_ENABLED100virtual void Write_AP_Logger_Log_Startup_messages() const;101#endif102103virtual bool prepare_for_arming(void) { return true; }104105// optional support for retrieving RTCMv3 data from a moving baseline base106virtual bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len) { return false; }107virtual void clear_RTCMV3(void) {};108109virtual bool get_error_codes(uint32_t &error_codes) const { return false; }110111// return iTOW of last message, or zero if not supported112uint32_t get_last_itow_ms(void) const;113114// check if an option is set115bool option_set(const AP_GPS::DriverOptions option) const {116return gps.option_set(option);117}118119protected:120AP_HAL::UARTDriver *port; ///< UART we are attached to121AP_GPS &gps; ///< access to frontend (for parameters)122AP_GPS::GPS_State &state; ///< public state for this instance123AP_GPS::Params ¶ms;124125uint64_t _last_pps_time_us;126JitterCorrection jitter_correction;127uint32_t _last_itow_ms;128bool _have_itow;129130/*131fill in 3D velocity from 2D components132*/133void fill_3d_velocity(void);134135/*136fill ground course and speed from velocity137*/138void velocity_to_speed_course(AP_GPS::GPS_State &s);139140/*141fill in time_week_ms and time_week from BCD date and time components142assumes MTK19 millisecond form of bcd_time143*/144void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds);145146void _detection_message(char *buffer, uint8_t buflen) const;147148bool should_log() const;149150/*151set a timestamp based on arrival time on uart at current byte,152assuming the message started nbytes ago153*/154void set_uart_timestamp(uint16_t nbytes);155156void check_new_itow(uint32_t itow, uint32_t msg_length);157158#if GPS_MOVING_BASELINE159bool calculate_moving_base_yaw(const float reported_heading_deg, const float reported_distance, const float reported_D);160bool calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, const float reported_heading_deg, const float reported_distance, const float reported_D);161#endif //GPS_MOVING_BASELINE162163// get GPS type, for subtype config164AP_GPS::GPS_Type get_type() const {165return gps.get_type(state.instance);166}167168virtual void set_pps_desired_freq(uint8_t freq) {}169170#if AP_GPS_DEBUG_LOGGING_ENABLED171// log some data for debugging172void log_data(const uint8_t *data, uint16_t length);173#endif174175// set alt in location, honouring GPS driver option for ellipsoid height176void set_alt_amsl_cm(AP_GPS::GPS_State &_state, int32_t alt_amsl_cm);177178private:179// itow from previous message180uint64_t _pseudo_itow;181int32_t _pseudo_itow_delta_ms;182uint32_t _last_ms;183uint32_t _rate_ms;184uint32_t _last_rate_ms;185uint16_t _rate_counter;186187#if AP_GPS_DEBUG_LOGGING_ENABLED188// support raw GPS logging189static struct loginfo {190int fd = -1;191ByteBuffer buf{16000};192} logging[2];193static bool log_thread_created;194static void logging_loop(void);195void logging_start(void);196#endif197198};199200#endif // AP_GPS_ENABLED201202203