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_SBF.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// Septentrio GPS driver for ArduPilot.17// Code by Michael Oborne18//19#pragma once2021#include "AP_GPS.h"22#include "GPS_Backend.h"2324#if AP_GPS_SBF_ENABLED2526#define SBF_DISK_ACTIVITY (1 << 7)27#define SBF_DISK_FULL (1 << 8)28#define SBF_DISK_MOUNTED (1 << 9)2930class AP_GPS_SBF : public AP_GPS_Backend31{32public:33AP_GPS_SBF(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);34~AP_GPS_SBF();3536AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }3738// Methods39bool read() override;4041const char *name() const override { return "SBF"; }4243bool is_configured (void) const override;4445void broadcast_configuration_failure_reason(void) const override;4647#if HAL_GCS_ENABLED48bool supports_mavlink_gps_rtk_message(void) const override { return true; };49#endif5051// get the velocity lag, returns true if the driver is confident in the returned value52bool get_lag(float &lag_sec) const override { lag_sec = 0.08f; return true; } ;5354bool is_healthy(void) const override;5556bool logging_healthy(void) const override;5758bool prepare_for_arming(void) override;5960bool get_error_codes(uint32_t &error_codes) const override { error_codes = RxError; return true; };6162private:6364bool parse(uint8_t temp);65bool process_message();6667static const uint8_t SBF_PREAMBLE1 = '$';68static const uint8_t SBF_PREAMBLE2 = '@';6970uint8_t _init_blob_index;71uint32_t _init_blob_time;72enum class Config_State {73Baud_Rate,74SSO,75Blob,76SBAS,77SGA,78Constellation,79Complete80};81Config_State config_step;82char *config_string;83static constexpr const char* _initialisation_blob[] = {84"srd,Moderate,UAV",85"sem,PVT,5",86"spm,Rover,all",87"sso,Stream2,Dsk1,postprocess+event+comment+ReceiverStatus,msec100",88#if defined (GPS_SBF_EXTRA_CONFIG)89GPS_SBF_EXTRA_CONFIG90#endif91};92static constexpr const char* sbas_off = "sst, -SBAS";93static constexpr const char* sbas_on_blob[] = {94"snt,+GEOL1+GEOL5",95"sst,+SBAS",96"ssbc,auto,Operational,MixedSystems,auto",97};98uint32_t _config_last_ack_time;99100const char* _port_enable = "\nSSSSSSSSSS\n";101102uint32_t crc_error_counter = 0;103uint32_t RxState;104uint32_t RxError;105106void mount_disk(void) const;107void unmount_disk(void) const;108bool _has_been_armed;109110enum sbf_ids {111DOP = 4001,112PVTGeodetic = 4007,113ReceiverStatus = 4014,114BaseVectorGeod = 4028,115VelCovGeodetic = 5908,116AttEulerCov = 5939,117AuxAntPositions = 5942,118};119120struct PACKED msg4007 // PVTGeodetic121{122uint32_t TOW;123uint16_t WNc;124uint8_t Mode;125uint8_t Error;126double Latitude;127double Longitude;128double Height;129float Undulation;130float Vn;131float Ve;132float Vu;133float COG;134double RxClkBias;135float RxClkDrift;136uint8_t TimeSystem;137uint8_t Datum;138uint8_t NrSV;139uint8_t WACorrInfo;140uint16_t ReferenceID;141uint16_t MeanCorrAge;142uint32_t SignalInfo;143uint8_t AlertFlag;144// rev1145uint8_t NrBases;146uint16_t PPPInfo;147// rev2148uint16_t Latency;149uint16_t HAccuracy;150uint16_t VAccuracy;151uint8_t Misc;152};153154struct PACKED msg4001 // DOP155{156uint32_t TOW;157uint16_t WNc;158uint8_t NrSV;159uint8_t Reserved;160uint16_t PDOP;161uint16_t TDOP;162uint16_t HDOP;163uint16_t VDOP;164float HPL;165float VPL;166};167168struct PACKED msg4014 // ReceiverStatus (v2)169{170uint32_t TOW;171uint16_t WNc;172uint8_t CPULoad;173uint8_t ExtError;174uint32_t UpTime;175uint32_t RxState;176uint32_t RxError;177// remaining data is AGCData, which we don't have a use for, don't extract the data178};179180struct PACKED VectorInfoGeod {181uint8_t NrSV;182uint8_t Error;183uint8_t Mode;184uint8_t Misc;185double DeltaEast;186double DeltaNorth;187double DeltaUp;188float DeltaVe;189float DeltaVn;190float DeltaVu;191uint16_t Azimuth;192int16_t Elevation;193uint8_t ReferenceID;194uint16_t CorrAge;195uint32_t SignalInfo;196};197198struct PACKED msg4028 // BaseVectorGeod199{200uint32_t TOW;201uint16_t WNc;202uint8_t N; // number of baselines203uint8_t SBLength;204VectorInfoGeod info; // there can be multiple baselines here, but we will only consume the first one, so don't worry about anything after205};206207struct PACKED msg5908 // VelCovGeodetic208{209uint32_t TOW;210uint16_t WNc;211uint8_t Mode;212uint8_t Error;213float Cov_VnVn;214float Cov_VeVe;215float Cov_VuVu;216float Cov_DtDt;217float Cov_VnVe;218float Cov_VnVu;219float Cov_VnDt;220float Cov_VeVu;221float Cov_VeDt;222float Cov_VuDt;223};224225struct PACKED msg5939 // AttEulerCoV226{227uint32_t TOW; // receiver time stamp, 0.001s228uint16_t WNc; // receiver time stamp, 1 week229uint8_t Reserved; // unused230uint8_t Error; // error code. bit 0-1:antenna 1, bit 2-3:antenna2, bit 7: when att not requested231// 00b:no error, 01b:not enough meausurements, 10b:antennas are on one line, 11b:inconsistent with manual anntena pos info232float Cov_HeadHead; // heading estimate variance233float Cov_PitchPitch; // pitch estimate variance234float Cov_RollRoll; // roll estimate variance235float Cov_HeadPitch; // covariance between Euler angle estimates. Always set to Do-No-Use values236float Cov_HeadRoll;237float Cov_PitchRoll;238};239240struct PACKED AuxAntPositionSubBlock {241uint8_t NrSV; // total number of satellites tracked by the antenna242uint8_t Error; // aux antenna position error code243uint8_t AmbiguityType; // aux antenna positions obtained with 0: fixed ambiguities, 1: float ambiguities244uint8_t AuxAntID; // aux antenna ID: 1 for the first auxiliary antenna, 2 for the second, etc.245double DeltaEast; // position in East direction (relative to main antenna)246double DeltaNorth; // position in North direction (relative to main antenna)247double DeltaUp; // position in Up direction (relative to main antenna)248double EastVel; // velocity in East direction (relative to main antenna)249double NorthVel; // velocity in North direction (relative to main antenna)250double UpVel; // velocity in Up direction (relative to main antenna)251};252253struct PACKED msg5942 // AuxAntPositions254{255uint32_t TOW;256uint16_t WNc;257uint8_t N; // number of AuxAntPosition sub-blocks in this AuxAntPositions block258uint8_t SBLength; // length of one sub-block in bytes259AuxAntPositionSubBlock ant1; // first aux antennas position260};261262union PACKED msgbuffer {263msg4007 msg4007u;264msg4001 msg4001u;265msg4014 msg4014u;266msg4028 msg4028u;267msg5908 msg5908u;268msg5939 msg5939u;269msg5942 msg5942u;270uint8_t bytes[256];271};272273struct sbf_msg_parser_t274{275enum276{277PREAMBLE1 = 0,278PREAMBLE2,279CRC1,280CRC2,281BLOCKID1,282BLOCKID2,283LENGTH1,284LENGTH2,285DATA,286COMMAND_LINE // used to parse command responses287} sbf_state;288uint16_t preamble;289uint16_t crc;290uint16_t blockid;291uint16_t length;292msgbuffer data;293uint16_t read;294} sbf_msg;295296enum {297SOFTWARE = (1 << 3), // set upon detection of a software warning or error. This bit is reset by the command lif, error298WATCHDOG = (1 << 4), // set when the watch-dog expired at least once since the last power-on.299CONGESTION = (1 << 6), // set when an output data congestion has been detected on at least one of the communication ports of the receiver during the last second.300MISSEDEVENT = (1 << 8), // set when an external event congestion has been detected during the last second. It indicates that the receiver is receiving too many events on its EVENTx pins.301CPUOVERLOAD = (1 << 9), // set when the CPU load is larger than 90%. If this bit is set, receiver operation may be unreliable and the user must decrease the processing load by following the recommendations in the User Manual.302INVALIDCONFIG = (1 << 10), // set if one or more configuration file (permission or channel configuration) is invalid or absent.303OUTOFGEOFENCE = (1 << 11), // set if the receiver is currently out of its permitted region of operation (geo-fencing).304};305306static constexpr const char *portIdentifiers[] = { "COM", "USB", "IP1", "NTR", "IPS", "IPR" };307char portIdentifier[5];308uint8_t portLength;309bool readyForCommand;310};311#endif312313314