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_SBP.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//16// Swift Navigation SBP GPS driver for ArduPilot.17// Code by Niels Joubert18//19// Swift Binary Protocol format: http://docs.swift-nav.com/20//21#pragma once2223#include "AP_GPS.h"24#include "GPS_Backend.h"2526#if AP_GPS_SBP_ENABLED27class AP_GPS_SBP : public AP_GPS_Backend28{29public:30AP_GPS_SBP(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);3132AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }3334#if HAL_GCS_ENABLED35bool supports_mavlink_gps_rtk_message() const override { return true; }36#endif3738// Methods39bool read() override;4041void inject_data(const uint8_t *data, uint16_t len) override;4243static bool _detect(struct SBP_detect_state &state, uint8_t data);4445const char *name() const override { return "SBP"; }4647private:4849// ************************************************************************50// Swift Navigation SBP protocol types and definitions51// ************************************************************************5253struct sbp_parser_state_t {54enum {55WAITING = 0,56GET_TYPE = 1,57GET_SENDER = 2,58GET_LEN = 3,59GET_MSG = 4,60GET_CRC = 561} state:8;62uint16_t msg_type;63uint16_t sender_id;64uint16_t crc;65uint8_t msg_len;66uint8_t n_read;67uint8_t msg_buff[256];68} parser_state;6970static const uint8_t SBP_PREAMBLE = 0x55;7172//Message types supported by this driver73static const uint16_t SBP_STARTUP_MSGTYPE = 0xFF00;74static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF;75static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0100;76static const uint16_t SBP_DOPS_MSGTYPE = 0x0206;77static const uint16_t SBP_POS_ECEF_MSGTYPE = 0x0200;78static const uint16_t SBP_POS_LLH_MSGTYPE = 0x0201;79static const uint16_t SBP_BASELINE_ECEF_MSGTYPE = 0x0202;80static const uint16_t SBP_BASELINE_NED_MSGTYPE = 0x0203;81static const uint16_t SBP_VEL_ECEF_MSGTYPE = 0x0204;82static const uint16_t SBP_VEL_NED_MSGTYPE = 0x0205;83static const uint16_t SBP_TRACKING_STATE_MSGTYPE = 0x0016;84static const uint16_t SBP_IAR_STATE_MSGTYPE = 0x0019;8586// Heartbeat87// struct sbp_heartbeat_t {88// uint32_t flags; //< Status flags (reserved)89// }; // 4 bytes90struct PACKED sbp_heartbeat_t {91bool sys_error : 1;92bool io_error : 1;93bool nap_error : 1;94uint8_t res : 5;95uint8_t protocol_minor : 8;96uint8_t protocol_major : 8;97uint8_t res2 : 7;98bool ext_antenna : 1;99}; // 4 bytes100101// GPS Time102struct PACKED sbp_gps_time_t {103uint16_t wn; //< GPS week number (unit: weeks)104uint32_t tow; //< GPS Time of Week rounded to the nearest ms (unit: ms)105int32_t ns; //< Nanosecond remainder of rounded tow (unit: ns)106uint8_t flags; //< Status flags (reserved)107}; // 11 bytes108109// Dilution of Precision110struct PACKED sbp_dops_t {111uint32_t tow; //< GPS Time of Week (unit: ms)112uint16_t gdop; //< Geometric Dilution of Precision (unit: 0.01)113uint16_t pdop; //< Position Dilution of Precision (unit: 0.01)114uint16_t tdop; //< Time Dilution of Precision (unit: 0.01)115uint16_t hdop; //< Horizontal Dilution of Precision (unit: 0.01)116uint16_t vdop; //< Vertical Dilution of Precision (unit: 0.01)117}; // 14 bytes118119// Geodetic position solution.120struct PACKED sbp_pos_llh_t {121uint32_t tow; //< GPS Time of Week (unit: ms)122double lat; //< Latitude (unit: degrees)123double lon; //< Longitude (unit: degrees)124double height; //< Height (unit: meters)125uint16_t h_accuracy; //< Horizontal position accuracy estimate (unit: mm)126uint16_t v_accuracy; //< Vertical position accuracy estimate (unit: mm)127uint8_t n_sats; //< Number of satellites used in solution128uint8_t flags; //< Status flags129}; // 34 bytes130131// Velocity in NED Velocity in local North East Down (NED) coordinates.132struct PACKED sbp_vel_ned_t {133uint32_t tow; //< GPS Time of Week (unit: ms)134int32_t n; //< Velocity North coordinate (unit: mm/s)135int32_t e; //< Velocity East coordinate (unit: mm/s)136int32_t d; //< Velocity Down coordinate (unit: mm/s)137uint16_t h_accuracy; //< Horizontal velocity accuracy estimate (unit: mm/s)138uint16_t v_accuracy; //< Vertical velocity accuracy estimate (unit: mm/s)139uint8_t n_sats; //< Number of satellites used in solution140uint8_t flags; //< Status flags (reserved)141}; // 22 bytes142143// Activity and Signal-to-Noise data of a tracking channel on the GPS.144struct PACKED sbp_tracking_state_t {145uint8_t state; //< 0 if disabled, 1 if running146uint8_t prn; //< PRN identifier of tracked satellite147float cn0; //< carrier to noise power ratio.148};149150// Integer Ambiguity Resolution state - how is the RTK resolution doing?151struct PACKED sbp_iar_state_t {152uint32_t num_hypotheses;153};154155void _sbp_process();156void _sbp_process_message();157bool _attempt_state_update();158159// ************************************************************************160// Internal Received Messages State161// ************************************************************************162uint32_t last_heatbeat_received_ms;163uint32_t last_injected_data_ms;164165struct sbp_gps_time_t last_gps_time;166struct sbp_dops_t last_dops;167struct sbp_pos_llh_t last_pos_llh_spp;168struct sbp_pos_llh_t last_pos_llh_rtk;169struct sbp_vel_ned_t last_vel_ned;170uint32_t last_iar_num_hypotheses;171172uint32_t last_full_update_tow;173uint32_t last_full_update_cpu_ms;174175// ************************************************************************176// Monitoring and Performance Counting177// ************************************************************************178179uint32_t crc_error_counter;180181// ************************************************************************182// Logging to AP_Logger183// ************************************************************************184185void logging_log_full_update();186void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff);187188189};190#endif191192193