2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
26 #include "common/axis.h"
27 #include "common/time.h"
31 #define GPS_DEGREES_DIVIDER 10000000L
34 #define GPS_MIN_SAT_COUNT 4 // number of sats to trigger low sat count sanity check
39 } gpsCoordinateType_e
;
56 #define SBAS_MODE_MAX SBAS_GAGAN
65 GPS_BAUDRATE_115200
= 0,
73 GPS_AUTOCONFIG_OFF
= 0,
89 #define GPS_BAUDRATE_MAX GPS_BAUDRATE_9600
91 typedef struct gpsCoordinateDDDMMmmmm_s
{
94 } gpsCoordinateDDDMMmmmm_t
;
96 /* LLH Location in NEU axis system */
97 typedef struct gpsLocation_s
{
98 int32_t lat
; // latitude * 1e+7
99 int32_t lon
; // longitude * 1e+7
100 int32_t altCm
; // altitude in 0.01m
103 /* A value below 100 means great accuracy is possible with GPS satellite constellation */
104 typedef struct gpsDilution_s
{
105 uint16_t pdop
; // positional DOP - 3D (* 100)
106 uint16_t hdop
; // horizontal DOP - 2D (* 100)
107 uint16_t vdop
; // vertical DOP - 1D (* 100)
110 /* Only available on U-blox protocol */
111 typedef struct gpsAccuracy_s
{
112 uint32_t hAcc
; // horizontal accuracy in mm
113 uint32_t vAcc
; // vertical accuracy in mm
114 uint32_t sAcc
; // speed accuracy in mm/s
117 typedef struct gpsSolutionData_s
{
121 uint16_t speed3d
; // speed in 0.1m/s
122 uint16_t groundSpeed
; // speed in 0.1m/s
123 uint16_t groundCourse
; // degrees * 10
127 typedef struct gpsData_s
{
128 uint32_t errors
; // gps error counter - crc error/lost of data/sync etc..
130 uint32_t lastMessage
; // last time valid GPS data was received (millis)
131 uint32_t lastLastMessage
; // last-last valid GPS message. Used to calculate delta.
133 uint32_t state_position
; // incremental variable for loops
134 uint32_t state_ts
; // timestamp for last state_position increment
135 uint8_t state
; // GPS thread state. Used for detecting cable disconnects and configuring attached devices
136 uint8_t baudrateIndex
; // index into auto-detecting or current baudrate
138 uint8_t ackWaitingMsgId
; // Message id when waiting for ACK
139 uint8_t ackTimeoutCounter
; // Ack timeout counter
140 ubloxAckState_e ackState
;
145 #define GPS_PACKET_LOG_ENTRY_COUNT 21 // To make this useful we should log as many packets as we can fit characters a single line of a OLED display.
146 extern char gpsPacketLog
[GPS_PACKET_LOG_ENTRY_COUNT
];
148 extern int32_t GPS_home
[2];
149 extern uint16_t GPS_distanceToHome
; // distance to home point in meters
150 extern uint32_t GPS_distanceToHomeCm
; // distance to home point in cm
151 extern int16_t GPS_directionToHome
; // direction to home or hol point in degrees
152 extern uint32_t GPS_distanceFlownInCm
; // distance flown since armed in centimeters
153 extern int16_t GPS_angle
[ANGLE_INDEX_COUNT
]; // it's the angles that must be applied for GPS correction
154 extern float GPS_scaleLonDown
; // this is used to offset the shrinking longitude as we go towards the poles
155 extern int16_t nav_takeoff_bearing
;
158 GPS_DIRECT_TICK
= 1 << 0,
159 GPS_MSP_UPDATE
= 1 << 1
162 extern gpsData_t gpsData
;
163 extern gpsSolutionData_t gpsSol
;
165 #define GPS_SV_MAXSATS_LEGACY 16U
166 #define GPS_SV_MAXSATS_M8N 32U
167 #define GPS_SV_MAXSATS_M9N 42U
169 extern uint8_t GPS_update
; // toogle to distinct a GPS position update (directly or via MSP)
170 extern uint32_t GPS_packetCount
;
171 extern uint32_t GPS_svInfoReceivedCount
;
172 extern uint8_t GPS_numCh
; // Number of channels
173 extern uint8_t GPS_svinfo_chn
[GPS_SV_MAXSATS_M8N
]; // When NumCh is 16 or less: Channel number
174 // When NumCh is more than 16: GNSS Id
175 // 0 = GPS, 1 = SBAS, 2 = Galileo, 3 = BeiDou
176 // 4 = IMES, 5 = QZSS, 6 = Glonass
177 extern uint8_t GPS_svinfo_svid
[GPS_SV_MAXSATS_M8N
]; // Satellite ID
178 extern uint8_t GPS_svinfo_quality
[GPS_SV_MAXSATS_M8N
]; // When NumCh is 16 or less: Bitfield Qualtity
179 // When NumCh is more than 16: flags
180 // bits 2..0: signal quality indicator
182 // 1 = searching signal
183 // 2 = signal acquired
184 // 3 = signal detected but unusable
185 // 4 = code locked and time synchronized
186 // 5,6,7 = code and carrier locked and time synchronized
188 // 1 = signal currently being used for navigaion
189 // bits 5..4: signal health flag
194 // 1 = differential correction data available for this SV
196 // 1 = carrier smoothed pseudorange used
197 extern uint8_t GPS_svinfo_cno
[GPS_SV_MAXSATS_M8N
]; // Carrier to Noise Ratio (Signal Strength)
199 #define GPS_DBHZ_MIN 0
200 #define GPS_DBHZ_MAX 55
202 #define TASK_GPS_RATE 100
203 #define TASK_GPS_RATE_FAST 1000
206 void gpsUpdate(timeUs_t currentTimeUs
);
207 bool gpsNewFrame(uint8_t c
);
208 bool gpsIsHealthy(void); // Check for healthy communications
210 void gpsEnablePassthrough(struct serialPort_s
*gpsPassthroughPort
);
211 void onGpsNewData(void);
212 void GPS_reset_home_position(void);
213 void GPS_calc_longitude_scaling(int32_t lat
);
214 void GPS_distance_cm_bearing(int32_t *currentLat1
, int32_t *currentLon1
, int32_t *destinationLat2
, int32_t *destinationLon2
, uint32_t *dist
, int32_t *bearing
);
215 void gpsSetFixState(bool state
);
216 float getGpsDataIntervalSeconds(void);