vtx: fix VTX_SETTINGS_POWER_COUNT and add dummy entries to saPowerNames
[inav.git] / src / main / io / gps.h
blobc14db4a76307ca7e06b84aef29ce6a8cdb901f79
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #pragma once
20 #include <stdbool.h>
21 #include <time.h>
23 #include "config/parameter_group.h"
25 #include "common/time.h"
27 #define GPS_DBHZ_MIN 0
28 #define GPS_DBHZ_MAX 55
30 #define LAT 0
31 #define LON 1
33 #define GPS_DEGREES_DIVIDER 10000000L
35 typedef enum {
36 GPS_UBLOX = 0,
37 GPS_MSP,
38 GPS_FAKE,
39 GPS_PROVIDER_COUNT
40 } gpsProvider_e;
42 typedef enum {
43 SBAS_AUTO = 0,
44 SBAS_EGNOS,
45 SBAS_WAAS,
46 SBAS_MSAS,
47 SBAS_GAGAN,
48 SBAS_SPAN,
49 SBAS_NONE
50 } sbasMode_e;
52 #define SBAS_MODE_MAX SBAS_GAGAN
54 typedef enum {
55 GPS_BAUDRATE_115200 = 0,
56 GPS_BAUDRATE_57600,
57 GPS_BAUDRATE_38400,
58 GPS_BAUDRATE_19200,
59 GPS_BAUDRATE_9600,
60 GPS_BAUDRATE_230400,
61 GPS_BAUDRATE_460800,
62 GPS_BAUDRATE_921600,
63 GPS_BAUDRATE_COUNT
64 } gpsBaudRate_e;
66 typedef enum {
67 GPS_AUTOCONFIG_OFF = 0,
68 GPS_AUTOCONFIG_ON,
69 } gpsAutoConfig_e;
71 typedef enum {
72 GPS_AUTOBAUD_OFF = 0,
73 GPS_AUTOBAUD_ON
74 } gpsAutoBaud_e;
76 typedef enum {
77 GPS_DYNMODEL_PEDESTRIAN = 0,
78 GPS_DYNMODEL_AUTOMOTIVE,
79 GPS_DYNMODEL_AIR_1G,
80 GPS_DYNMODEL_AIR_2G,
81 GPS_DYNMODEL_AIR_4G,
82 GPS_DYNMODEL_SEA,
83 GPS_DYNMODEL_MOWER,
84 } gpsDynModel_e;
86 typedef enum {
87 GPS_NO_FIX = 0,
88 GPS_FIX_2D,
89 GPS_FIX_3D
90 } gpsFixType_e;
92 #define GPS_BAUDRATE_MAX GPS_BAUDRATE_9600
94 typedef struct gpsConfig_s {
95 gpsProvider_e provider;
96 sbasMode_e sbasMode;
97 gpsAutoConfig_e autoConfig;
98 gpsAutoBaud_e autoBaud;
99 gpsDynModel_e dynModel;
100 bool ubloxUseGalileo;
101 bool ubloxUseBeidou;
102 bool ubloxUseGlonass;
103 uint8_t gpsMinSats;
104 uint8_t ubloxNavHz;
105 gpsBaudRate_e autoBaudMax;
106 } gpsConfig_t;
108 PG_DECLARE(gpsConfig_t, gpsConfig);
110 typedef struct gpsCoordinateDDDMMmmmm_s {
111 int16_t dddmm;
112 int16_t mmmm;
113 } gpsCoordinateDDDMMmmmm_t;
115 /* LLH Location in NEU axis system */
116 typedef struct gpsLocation_s {
117 int32_t lat; // Latitude * 1e+7
118 int32_t lon; // Longitude * 1e+7
119 int32_t alt; // Altitude in centimeters (meters * 100)
120 } gpsLocation_t;
122 #define HDOP_SCALE (100)
124 typedef struct gpsSolutionData_s {
125 struct {
126 bool hasNewData;
127 bool gpsHeartbeat; // Toggle each update
128 bool validVelNE;
129 bool validVelD;
130 bool validEPE; // EPH/EPV values are valid - actual accuracy
131 bool validTime;
132 } flags;
134 gpsFixType_e fixType;
135 uint8_t numSat;
137 gpsLocation_t llh;
138 int16_t velNED[3];
140 int16_t groundSpeed;
141 int16_t groundCourse;
143 uint16_t eph; // horizontal accuracy (cm)
144 uint16_t epv; // vertical accuracy (cm)
146 uint16_t hdop; // generic HDOP value (*HDOP_SCALE)
148 dateTime_t time; // GPS time in UTC
150 } gpsSolutionData_t;
152 typedef struct {
153 uint16_t lastMessageDt;
154 uint32_t errors; // gps error counter - crc error/lost of data/sync etc..
155 uint32_t timeouts;
156 uint32_t packetCount;
157 } gpsStatistics_t;
159 extern gpsSolutionData_t gpsSol;
160 extern gpsStatistics_t gpsStats;
162 struct magDev_s;
163 void gpsPreInit(void);
164 void gpsInit(void);
165 // Called periodically from GPS task. Returns true iff the GPS
166 // information was updated.
167 bool gpsUpdate(void);
168 void updateGpsIndicator(timeUs_t currentTimeUs);
169 bool isGPSHealthy(void);
170 bool isGPSHeadingValid(void);
171 struct serialPort_s;
172 void gpsEnablePassthrough(struct serialPort_s *gpsPassthroughPort);
173 void mspGPSReceiveNewData(const uint8_t * bufferPtr);
175 const char *getGpsHwVersion(void);
176 uint8_t getGpsProtoMajorVersion(void);
177 uint8_t getGpsProtoMinorVersion(void);
179 int getGpsBaudrate(void);
180 int gpsBaudRateToInt(gpsBaudRate_e baudrate);
182 #if defined(USE_GPS_FAKE)
183 void gpsFakeSet(
184 gpsFixType_e fixType,
185 uint8_t numSat,
186 int32_t lat,
187 int32_t lon,
188 int32_t alt,
189 int16_t groundSpeed,
190 int16_t groundCourse,
191 int16_t velNED_X,
192 int16_t velNED_Y,
193 int16_t velNED_Z,
194 time_t time);
195 #endif