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/>.
31 #include "build/build_config.h"
32 #include "build/debug.h"
34 #include "common/axis.h"
35 #include "common/gps_conversion.h"
36 #include "common/maths.h"
37 #include "common/utils.h"
39 #include "config/feature.h"
41 #include "drivers/light_led.h"
42 #include "drivers/time.h"
44 #include "io/beeper.h"
46 #include "io/dashboard.h"
49 #include "io/serial.h"
51 #include "config/config.h"
53 #include "fc/gps_lap_timer.h"
54 #include "fc/runtime_config.h"
56 #include "flight/imu.h"
57 #include "flight/pid.h"
58 #include "flight/gps_rescue.h"
60 #include "scheduler/scheduler.h"
62 #include "sensors/sensors.h"
63 #include "common/typeconversion.h"
65 // **********************
67 // **********************
69 uint16_t GPS_distanceToHome
; // distance to home point in meters
70 uint32_t GPS_distanceToHomeCm
;
71 int16_t GPS_directionToHome
; // direction to home or hol point in degrees * 10
72 uint32_t GPS_distanceFlownInCm
; // distance flown since armed in centimeters
74 #define GPS_DISTANCE_FLOWN_MIN_SPEED_THRESHOLD_CM_S 15 // 0.54 km/h 0.335 mph
76 gpsSolutionData_t gpsSol
;
77 uint8_t GPS_update
= 0; // toogle to distinct a GPS position update (directly or via MSP)
79 uint8_t GPS_numCh
; // Details on numCh/svinfo in gps.h
80 uint8_t GPS_svinfo_chn
[GPS_SV_MAXSATS_M8N
];
81 uint8_t GPS_svinfo_svid
[GPS_SV_MAXSATS_M8N
];
82 uint8_t GPS_svinfo_quality
[GPS_SV_MAXSATS_M8N
];
83 uint8_t GPS_svinfo_cno
[GPS_SV_MAXSATS_M8N
];
85 // GPS LOST_COMMUNICATION timeout in ms (max time between received nav solutions)
86 #define GPS_TIMEOUT_MS 2500
87 // Timeout for waiting for an ACK or NAK response to a configuration command
88 #define UBLOX_ACK_TIMEOUT_MS 150
89 // Time allowed for module to respond to baud rate change during initial configuration
90 #define GPS_CONFIG_BAUD_CHANGE_INTERVAL 330 // Time to wait, in ms, between 'test this baud rate' messages
91 #define GPS_CONFIG_CHANGE_INTERVAL 110 // Time to wait, in ms, between CONFIG steps
92 #define GPS_BAUDRATE_TEST_COUNT 3 // Number of times to repeat the test message when setting baudrate
93 #define GPS_RECV_TIME_MAX 25 // Max permitted time, in us, for the Receive Data process
94 // Decay the estimated max task duration by 1/(1 << GPS_TASK_DECAY_SHIFT) on every invocation
95 #define GPS_TASK_DECAY_SHIFT 9 // Smoothing factor for GPS task re-scheduler
97 static serialPort_t
*gpsPort
;
98 static float gpsDataIntervalSeconds
;
100 typedef struct gpsInitData_s
{
102 uint8_t baudrateIndex
; // see baudRate_e
106 // UBX will cycle through these until valid data is received
107 static const gpsInitData_t gpsInitData
[] = {
108 { GPS_BAUDRATE_115200
, BAUD_115200
, "$PUBX,41,1,0003,0001,115200,0*1E\r\n" },
109 { GPS_BAUDRATE_57600
, BAUD_57600
, "$PUBX,41,1,0003,0001,57600,0*2D\r\n" },
110 { GPS_BAUDRATE_38400
, BAUD_38400
, "$PUBX,41,1,0003,0001,38400,0*26\r\n" },
111 { GPS_BAUDRATE_19200
, BAUD_19200
, "$PUBX,41,1,0003,0001,19200,0*23\r\n" },
112 { GPS_BAUDRATE_9600
, BAUD_9600
, "$PUBX,41,1,0003,0001,9600,0*16\r\n" }
115 #define GPS_INIT_DATA_ENTRY_COUNT ARRAYLEN(gpsInitData)
117 #define DEFAULT_BAUD_RATE_INDEX 0
120 #define MAX_VALSET_SIZE 128
129 CLASS_NMEA_STD
= 0xf0,
132 MSG_NAV_POSLLH
= 0x02,
133 MSG_NAV_STATUS
= 0x03,
137 MSG_NAV_VELNED
= 0x12,
138 MSG_NAV_SVINFO
= 0x30,
140 MSG_CFG_VALSET
= 0x8a,
141 MSG_CFG_VALGET
= 0x8b,
145 MSG_CFG_SET_RATE
= 0x01,
147 MSG_CFG_NAV_SETTINGS
= 0x24,
148 MSG_CFG_NAVX_SETTINGS
= 0x23,
158 } ubxProtocolBytes_e
;
161 UBX_POWER_MODE_FULL
= 0x00,
162 UBX_POWER_MODE_PSMOO
= 0x01,
163 UBX_POWER_MODE_PSMCT
= 0x02,
166 #define UBLOX_MODE_ENABLED 0x1
167 #define UBLOX_MODE_TEST 0x2
169 #define UBLOX_USAGE_RANGE 0x1
170 #define UBLOX_USAGE_DIFFCORR 0x2
171 #define UBLOX_USAGE_INTEGRITY 0x4
173 #define UBLOX_GNSS_ENABLE 0x1
174 #define UBLOX_GNSS_DEFAULT_SIGCFGMASK 0x10000
176 typedef struct ubxHeader_s
{
184 typedef struct ubxConfigblock_s
{
192 typedef struct ubxPollMsg_s
{
197 typedef struct ubxCfgMsg_s
{
203 typedef struct ubxCfgRate_s
{
209 typedef struct ubxCfgValSet_s
{
213 uint8_t cfgData
[MAX_VALSET_SIZE
];
216 typedef struct ubxCfgValGet_s
{
220 uint8_t cfgData
[MAX_VALSET_SIZE
];
223 typedef struct ubxCfgSbas_s
{
231 typedef struct ubxCfgGnss_s
{
235 uint8_t numConfigBlocks
;
236 ubxConfigblock_t configblocks
[7];
239 typedef struct ubxCfgPms_s
{
241 uint8_t powerSetupValue
;
244 uint8_t reserved1
[2];
247 typedef struct ubxCfgNav5_s
{
252 uint32_t fixedAltVar
;
259 uint8_t staticHoldThresh
;
260 uint8_t dgnssTimeout
;
261 uint8_t cnoThreshNumSVs
;
263 uint8_t reserved0
[2];
264 uint16_t staticHoldMaxDist
;
266 uint8_t reserved1
[5];
269 typedef struct ubxCfgNav5x_s
{
273 uint8_t reserved0
[2];
279 uint8_t reserved2
[2];
281 uint16_t wknRollover
;
282 uint8_t sigAttenCompMode
;
284 uint8_t reserved4
[2];
285 uint8_t reserved5
[2];
288 uint8_t reserved6
[2];
289 uint8_t reserved7
[4];
290 uint8_t reserved8
[3];
294 typedef union ubxPayload_s
{
295 ubxPollMsg_t poll_msg
;
297 ubxCfgRate_t cfg_rate
;
298 ubxCfgValSet_t cfg_valset
;
299 ubxCfgValGet_t cfg_valget
;
300 ubxCfgNav5_t cfg_nav5
;
301 ubxCfgNav5x_t cfg_nav5x
;
302 ubxCfgSbas_t cfg_sbas
;
303 ubxCfgGnss_t cfg_gnss
;
307 typedef struct ubxMessage_s
{
309 ubxPayload_t payload
;
310 } __attribute__((packed
)) ubxMessage_t
;
313 UBLOX_DETECT_UNIT
, // 0
314 UBLOX_SLOW_NAV_RATE
, // 1.
315 UBLOX_MSG_DISABLE_NMEA
, // 2. Disable NMEA, config message
316 UBLOX_MSG_VGS
, // 3. VGS: Course over ground and Ground speed
317 UBLOX_MSG_GSV
, // 4. GSV: GNSS Satellites in View
318 UBLOX_MSG_GLL
, // 5. GLL: Latitude and longitude, with time of position fix and status
319 UBLOX_MSG_GGA
, // 6. GGA: Global positioning system fix data
320 UBLOX_MSG_GSA
, // 7. GSA: GNSS DOP and Active Satellites
321 UBLOX_MSG_RMC
, // 8. RMC: Recommended Minimum data
322 UBLOX_ACQUIRE_MODEL
, // 9
323 // UBLOX_CFG_ANA, // . ANA: if M10, enable autonomous mode : temporarily disabled.
324 UBLOX_SET_SBAS
, // 10. Sets SBAS
325 UBLOX_SET_PMS
, // 11. Sets Power Mode
326 UBLOX_MSG_NAV_PVT
, // 12. set NAV-PVT rate
327 UBLOX_MSG_SOL
, // 13. set SOL MSG rate
328 UBLOX_MSG_POSLLH
, // 14. set POSLLH MSG rate
329 UBLOX_MSG_STATUS
, // 15: set STATUS MSG rate
330 UBLOX_MSG_VELNED
, // 16. set VELNED MSG rate
331 UBLOX_MSG_DOP
, // 17. MSG_NAV_DOP
332 UBLOX_SAT_INFO
, // 18. MSG_NAV_SAT message
333 UBLOX_SET_NAV_RATE
, // 19. set to user requested GPS sample rate
334 UBLOX_MSG_CFG_GNSS
, // 20. For not SBAS or GALILEO
335 UBLOX_CONFIG_COMPLETE
// 21. Config finished, start receiving data
336 } ubloxStatePosition_e
;
338 baudRate_e initBaudRateIndex
;
339 size_t initBaudRateCycleCount
;
340 #endif // USE_GPS_UBLOX
345 // Functions & data used *only* in support of the dashboard device (OLED display).
346 // Note this should be refactored to move dashboard functionality to the dashboard module, and only have generic hooks in the gps module...
348 char dashboardGpsPacketLog
[GPS_PACKET_LOG_ENTRY_COUNT
]; // OLED display of a char for each packet type/event received.
349 char *dashboardGpsPacketLogCurrentChar
= dashboardGpsPacketLog
; // Current character of log being updated.
350 uint32_t dashboardGpsPacketCount
= 0; // Packet received count.
351 uint32_t dashboardGpsNavSvInfoRcvCount
= 0; // Count of times sat info updated.
353 static void shiftPacketLog(void)
357 for (i
= ARRAYLEN(dashboardGpsPacketLog
) - 1; i
> 0 ; i
--) {
358 dashboardGpsPacketLog
[i
] = dashboardGpsPacketLog
[i
-1];
362 static void logErrorToPacketLog(void)
365 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_ERROR
;
368 #endif // USE_DASHBOARD
370 static void gpsNewData(uint16_t c
);
372 static bool gpsNewFrameNMEA(char c
);
375 static bool gpsNewFrameUBLOX(uint8_t data
);
378 static void gpsSetState(gpsState_e state
)
380 gpsData
.lastNavMessage
= gpsData
.now
;
381 sensorsClear(SENSOR_GPS
);
382 gpsData
.state
= state
;
383 gpsData
.state_position
= 0;
384 gpsData
.state_ts
= gpsData
.now
;
385 gpsData
.ackState
= UBLOX_ACK_IDLE
;
390 gpsDataIntervalSeconds
= 0.1f
;
391 gpsData
.userBaudRateIndex
= 0;
392 gpsData
.timeouts
= 0;
393 gpsData
.state_ts
= millis();
395 gpsData
.ubloxUsingFlightModel
= false;
397 gpsData
.updateRateHz
= 10; // initialise at 10hz
398 gpsData
.platformVersion
= UBX_VERSION_UNDEF
;
402 memset(dashboardGpsPacketLog
, 0x00, sizeof(dashboardGpsPacketLog
));
405 // init gpsData structure. if we're not actually enabled, don't bother doing anything else
406 gpsSetState(GPS_STATE_UNKNOWN
);
408 if (gpsConfig()->provider
== GPS_MSP
) { // no serial ports used when GPS_MSP is configured
409 gpsSetState(GPS_STATE_INITIALIZED
);
413 const serialPortConfig_t
*gpsPortConfig
= findSerialPortConfig(FUNCTION_GPS
);
414 if (!gpsPortConfig
) {
418 // set the user's intended baud rate
419 initBaudRateIndex
= BAUD_COUNT
;
420 initBaudRateCycleCount
= 0;
421 gpsData
.userBaudRateIndex
= DEFAULT_BAUD_RATE_INDEX
;
422 for (unsigned i
= 0; i
< GPS_INIT_DATA_ENTRY_COUNT
; i
++) {
423 if (gpsInitData
[i
].baudrateIndex
== gpsPortConfig
->gps_baudrateIndex
) {
424 gpsData
.userBaudRateIndex
= i
;
428 // the user's intended baud rate will be used as the initial baud rate when connecting
429 gpsData
.tempBaudRateIndex
= gpsData
.userBaudRateIndex
;
431 portMode_e mode
= MODE_RXTX
;
432 portOptions_e options
= SERIAL_NOT_INVERTED
;
434 #if defined(GPS_NMEA_TX_ONLY)
435 if (gpsConfig()->provider
== GPS_NMEA
) {
440 if ((gpsPortConfig
->identifier
>= SERIAL_PORT_USART1
) && (gpsPortConfig
->identifier
<= SERIAL_PORT_USART_MAX
)){
441 options
|= SERIAL_CHECK_TX
;
444 // no callback - buffer will be consumed in gpsUpdate()
445 gpsPort
= openSerialPort(gpsPortConfig
->identifier
, FUNCTION_GPS
, NULL
, NULL
, baudRates
[gpsInitData
[gpsData
.userBaudRateIndex
].baudrateIndex
], mode
, options
);
450 // signal GPS "thread" to initialize when it gets to it
451 gpsSetState(GPS_STATE_DETECT_BAUD
);
452 // NB gpsData.state_position is set to zero by gpsSetState(), requesting the fastest baud rate option first time around.
456 const uint8_t ubloxUTCStandardConfig_int
[5] = {
457 UBLOX_UTC_STANDARD_AUTO
,
458 UBLOX_UTC_STANDARD_USNO
,
459 UBLOX_UTC_STANDARD_EU
,
460 UBLOX_UTC_STANDARD_SU
,
461 UBLOX_UTC_STANDARD_NTSC
464 struct ubloxVersion_s ubloxVersionMap
[] = {
465 [UBX_VERSION_UNDEF
] = {~0, "UNKNOWN"},
466 [UBX_VERSION_M5
] = {0x00040005, "M5"},
467 [UBX_VERSION_M6
] = {0x00040007, "M6"},
468 [UBX_VERSION_M7
] = {0x00070000, "M7"},
469 [UBX_VERSION_M8
] = {0x00080000, "M8"},
470 [UBX_VERSION_M9
] = {0x00190000, "M9"},
471 [UBX_VERSION_M10
] = {0x000A0000, "M10"},
474 static uint8_t ubloxAddValSet(ubxMessage_t
* tx_buffer
, ubxValGetSetBytes_e key
, const uint8_t * payload
, const uint8_t offset
) {
476 switch((key
>> (8 * 3)) & 0xff) {
493 if (offset
+ 4 + len
> MAX_VALSET_SIZE
)
498 tx_buffer
->payload
.cfg_valset
.cfgData
[offset
+ 0] = (uint8_t)(key
>> (8 * 0));
499 tx_buffer
->payload
.cfg_valset
.cfgData
[offset
+ 1] = (uint8_t)(key
>> (8 * 1));
500 tx_buffer
->payload
.cfg_valset
.cfgData
[offset
+ 2] = (uint8_t)(key
>> (8 * 2));
501 tx_buffer
->payload
.cfg_valset
.cfgData
[offset
+ 3] = (uint8_t)(key
>> (8 * 3));
503 for (size_t i
= 0; i
< len
; ++i
) {
504 tx_buffer
->payload
.cfg_valset
.cfgData
[offset
+ 4 + i
] = payload
[i
];
510 // the following lines are not being used, because we are not currently sending ubloxValGet messages
512 static size_t ubloxAddValGet(ubxMessage_t
* tx_buffer
, ubxValGetSetBytes_e key
, size_t offset
) {
513 const uint8_t zeroes
[8] = {0};
515 return ubloxAddValSet(tx_buffer
, key
, zeroes
, offset
);
518 static size_t ubloxValGet(ubxMessage_t
* tx_buffer
, ubxValGetSetBytes_e key
, ubloxValLayer_e layer
)
520 tx_buffer
->header
.preamble1
= PREAMBLE1
;
521 tx_buffer
->header
.preamble2
= PREAMBLE2
;
522 tx_buffer
->header
.msg_class
= CLASS_CFG
;
523 tx_buffer
->header
.msg_id
= MSG_CFG_VALGET
;
525 tx_buffer
->payload
.cfg_valget
.version
= 1;
526 tx_buffer
->payload
.cfg_valget
.layer
= layer
;
527 tx_buffer
->payload
.cfg_valget
.position
= 0;
529 return ubloxAddValGet(tx_buffer
, key
, 0);
533 static uint8_t ubloxValSet(ubxMessage_t
* tx_buffer
, ubxValGetSetBytes_e key
, uint8_t * payload
, ubloxValLayer_e layer
) {
534 memset(&tx_buffer
->payload
.cfg_valset
, 0, sizeof(ubxCfgValSet_t
));
536 // tx_buffer->payload.cfg_valset.version = 0;
537 tx_buffer
->payload
.cfg_valset
.layer
= layer
;
538 // tx_buffer->payload.cfg_valset.reserved[0] = 0;
539 // tx_buffer->payload.cfg_valset.reserved[1] = 0;
541 return ubloxAddValSet(tx_buffer
, key
, payload
, 0);
544 static void ubloxSendByteUpdateChecksum(const uint8_t data
, uint8_t *checksumA
, uint8_t *checksumB
)
547 *checksumB
+= *checksumA
;
548 serialWrite(gpsPort
, data
);
551 static void ubloxSendDataUpdateChecksum(const uint8_t *data
, uint8_t len
, uint8_t *checksumA
, uint8_t *checksumB
)
554 ubloxSendByteUpdateChecksum(*data
, checksumA
, checksumB
);
559 static void ubloxSendMessage(const uint8_t *data
, uint8_t len
, bool skipAck
)
561 uint8_t checksumA
= 0, checksumB
= 0;
562 serialWrite(gpsPort
, data
[0]);
563 serialWrite(gpsPort
, data
[1]);
564 ubloxSendDataUpdateChecksum(&data
[2], len
- 2, &checksumA
, &checksumB
);
565 serialWrite(gpsPort
, checksumA
);
566 serialWrite(gpsPort
, checksumB
);
567 // Save state for ACK waiting
568 gpsData
.ackWaitingMsgId
= data
[3]; //save message id for ACK
569 gpsData
.ackState
= skipAck
? UBLOX_ACK_GOT_ACK
: UBLOX_ACK_WAITING
;
570 gpsData
.lastMessageSent
= gpsData
.now
;
573 static void ubloxSendClassMessage(ubxProtocolBytes_e class_id
, ubxProtocolBytes_e msg_id
, uint16_t length
)
575 ubxMessage_t tx_buffer
;
576 tx_buffer
.header
.preamble1
= PREAMBLE1
;
577 tx_buffer
.header
.preamble2
= PREAMBLE2
;
578 tx_buffer
.header
.msg_class
= class_id
;
579 tx_buffer
.header
.msg_id
= msg_id
;
580 tx_buffer
.header
.length
= length
;
581 ubloxSendMessage((const uint8_t *) &tx_buffer
, length
+ 6, false);
584 static void ubloxSendConfigMessage(ubxMessage_t
*message
, uint8_t msg_id
, uint8_t length
, bool skipAck
)
586 message
->header
.preamble1
= PREAMBLE1
;
587 message
->header
.preamble2
= PREAMBLE2
;
588 message
->header
.msg_class
= CLASS_CFG
;
589 message
->header
.msg_id
= msg_id
;
590 message
->header
.length
= length
;
591 ubloxSendMessage((const uint8_t *) message
, length
+ 6, skipAck
);
594 static void ubloxSendPollMessage(uint8_t msg_id
)
596 ubxMessage_t tx_buffer
;
597 tx_buffer
.header
.preamble1
= PREAMBLE1
;
598 tx_buffer
.header
.preamble2
= PREAMBLE2
;
599 tx_buffer
.header
.msg_class
= CLASS_CFG
;
600 tx_buffer
.header
.msg_id
= msg_id
;
601 tx_buffer
.header
.length
= 0;
602 ubloxSendMessage((const uint8_t *) &tx_buffer
, 6, false);
605 static void ubloxSendNAV5Message(uint8_t model
) {
606 DEBUG_SET(DEBUG_GPS_CONNECTION
, 0, model
);
607 ubxMessage_t tx_buffer
;
608 if (gpsData
.ubloxM9orAbove
) {
610 payload
[0] = (model
== 0 ? 0 : model
+ 1);
611 size_t offset
= ubloxValSet(&tx_buffer
, CFG_NAVSPG_DYNMODEL
, payload
, UBX_VAL_LAYER_RAM
); // 5
613 // the commented out payload lines are those which only set the M9 or above module to default values.
615 // payload[0] = 3; // set 2D/3D fix mode to auto, which is the default
616 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_FIXMODE, payload, offset); // 10
618 payload
[0] = ubloxUTCStandardConfig_int
[gpsConfig()->gps_ublox_utc_standard
];
619 offset
+= ubloxAddValSet(&tx_buffer
, CFG_NAVSPG_UTCSTANDARD
, payload
, offset
); // 15
622 // payload[1] = (uint8_t)(0 >> (8 * 1));
623 // payload[2] = (uint8_t)(0 >> (8 * 2));
624 // payload[3] = (uint8_t)(0 >> (8 * 3)); // all payloads are zero, the default MSL for 2D fix
625 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_CONSTR_ALT, payload, offset); // 23
627 // payload[0] = (uint8_t)(10000 >> (8 * 0));
628 // payload[1] = (uint8_t)(10000 >> (8 * 1));
629 // payload[2] = (uint8_t)(10000 >> (8 * 2));
630 // payload[3] = (uint8_t)(10000 >> (8 * 3)); // // all payloads are 1000, the default 2D variance factor
631 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_CONSTR_ALTVAR, payload, offset); // 31
633 // payload[0] = 5; // sets the default minimum elevation in degrees to the default of 5
634 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_INFIL_MINELEV, payload, offset); // 36
636 // payload[0] = (uint8_t)(250 >> (8 * 0));
637 // payload[1] = (uint8_t)(250 >> (8 * 1)); // sets the output filter PDOP mask to default of 250
638 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_OUTFIL_PDOP, payload, offset); // 42
640 // payload[0] = (uint8_t)(250 >> (8 * 0));
641 // payload[1] = (uint8_t)(250 >> (8 * 1));
642 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_OUTFIL_TDOP, payload, offset); // 48
644 // payload[0] = (uint8_t)(100 >> (8 * 0));
645 // payload[1] = (uint8_t)(100 >> (8 * 1));
646 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_OUTFIL_PACC, payload, offset); // 54
648 // payload[0] = (uint8_t)(300 >> (8 * 0));
649 // payload[1] = (uint8_t)(300 >> (8 * 1));
650 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_OUTFIL_TACC, payload, offset); // 60
653 // offset += ubloxAddValSet(&tx_buffer, CFG_MOT_GNSSSPEED_THRS, payload, offset); // 65
655 // payload[0] = (uint8_t)(200 >> (8 * 0));
656 // payload[1] = (uint8_t)(200 >> (8 * 1));
657 // offset += ubloxAddValSet(&tx_buffer, CFG_MOT_GNSSDIST_THRS, payload, offset); // 71
659 // payload[0] = (uint8_t)(60 >> (8 * 0));
660 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_CONSTR_DGNSSTO, payload, offset); // 76
663 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_INFIL_NCNOTHRS, payload, offset); // 81
666 // offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_INFIL_CNOTHRS, payload, offset); // 86
668 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_VALSET
, offsetof(ubxCfgValSet_t
, cfgData
) + offset
, true);
670 memset(&tx_buffer
, 0, sizeof(ubxMessage_t
));
671 tx_buffer
.payload
.cfg_nav5
.mask
= 0xFFFF;
672 tx_buffer
.payload
.cfg_nav5
.dynModel
= model
== 0 ? 0 : model
+ 1; //no model with value 1
673 tx_buffer
.payload
.cfg_nav5
.fixMode
= 3;
674 tx_buffer
.payload
.cfg_nav5
.fixedAlt
= 0;
675 tx_buffer
.payload
.cfg_nav5
.fixedAltVar
= 10000;
676 tx_buffer
.payload
.cfg_nav5
.minElev
= 5;
677 tx_buffer
.payload
.cfg_nav5
.drLimit
= 0;
678 tx_buffer
.payload
.cfg_nav5
.pDOP
= 250;
679 tx_buffer
.payload
.cfg_nav5
.tDOP
= 250;
680 tx_buffer
.payload
.cfg_nav5
.pAcc
= 100;
681 tx_buffer
.payload
.cfg_nav5
.tAcc
= 300;
682 tx_buffer
.payload
.cfg_nav5
.staticHoldThresh
= 0;
683 tx_buffer
.payload
.cfg_nav5
.dgnssTimeout
= 60;
684 tx_buffer
.payload
.cfg_nav5
.cnoThreshNumSVs
= 0;
685 tx_buffer
.payload
.cfg_nav5
.cnoThresh
= 0;
686 tx_buffer
.payload
.cfg_nav5
.staticHoldMaxDist
= 200;
687 tx_buffer
.payload
.cfg_nav5
.utcStandard
= ubloxUTCStandardConfig_int
[gpsConfig()->gps_ublox_utc_standard
];
689 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_NAV_SETTINGS
, sizeof(ubxCfgNav5_t
), false);
693 // *** Assist Now Autonomous temporarily disabled until a subsequent PR either includes, or removes it ***
694 // static void ubloxSendNavX5Message(void) {
695 // ubxMessage_t tx_buffer;
697 // if (gpsData.ubloxM9orAbove) {
698 // uint8_t payload[1];
700 // size_t offset = ubloxValSet(&tx_buffer, CFG_ANA_USE_ANA, payload, UBX_VAL_LAYER_RAM); // 5
702 // ubloxSendConfigMessage(&tx_buffer, MSG_CFG_VALSET, offsetof(ubxCfgValSet_t, cfgData) + offset, true);
704 // memset(&tx_buffer, 0, sizeof(ubxMessage_t));
706 // tx_buffer.payload.cfg_nav5x.version = 0x0002;
708 // tx_buffer.payload.cfg_nav5x.mask1 = 0x4000;
709 // tx_buffer.payload.cfg_nav5x.mask2 = 0x0;
710 // tx_buffer.payload.cfg_nav5x.minSVs = 0;
711 // tx_buffer.payload.cfg_nav5x.maxSVs = 0;
712 // tx_buffer.payload.cfg_nav5x.minCNO = 0;
713 // tx_buffer.payload.cfg_nav5x.reserved1 = 0;
714 // tx_buffer.payload.cfg_nav5x.iniFix3D = 0;
715 // tx_buffer.payload.cfg_nav5x.ackAiding = 0;
716 // tx_buffer.payload.cfg_nav5x.wknRollover = 0;
717 // tx_buffer.payload.cfg_nav5x.sigAttenCompMode = 0;
718 // tx_buffer.payload.cfg_nav5x.usePPP = 0;
720 // tx_buffer.payload.cfg_nav5x.aopCfg = 0x1; //bit 0 = useAOP
722 // tx_buffer.payload.cfg_nav5x.useAdr = 0;
724 // ubloxSendConfigMessage(&tx_buffer, MSG_CFG_NAVX_SETTINGS, sizeof(ubxCfgNav5x_t), false);
728 static void ubloxSetPowerModeValSet(uint8_t powerSetupValue
)
730 ubxMessage_t tx_buffer
;
733 payload
[0] = powerSetupValue
;
735 size_t offset
= ubloxValSet(&tx_buffer
, CFG_PM_OPERATEMODE
, payload
, UBX_VAL_LAYER_RAM
);
737 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_VALSET
, offsetof(ubxCfgValSet_t
, cfgData
) + offset
, true);
740 static void ubloxSendPowerMode(void)
742 if (gpsData
.ubloxM9orAbove
) {
743 ubloxSetPowerModeValSet(UBX_POWER_MODE_FULL
);
744 } else if (gpsData
.ubloxM8orAbove
) {
745 ubxMessage_t tx_buffer
;
746 tx_buffer
.payload
.cfg_pms
.version
= 0;
747 tx_buffer
.payload
.cfg_pms
.powerSetupValue
= UBX_POWER_MODE_FULL
;
748 tx_buffer
.payload
.cfg_pms
.period
= 0;
749 tx_buffer
.payload
.cfg_pms
.onTime
= 0;
750 tx_buffer
.payload
.cfg_pms
.reserved1
[0] = 0;
751 tx_buffer
.payload
.cfg_pms
.reserved1
[1] = 0;
752 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_PMS
, sizeof(ubxCfgPms_t
), false);
754 // M7 and below do not support this type of power mode, so we leave at default.
757 static void ubloxSetMessageRate(uint8_t messageClass
, uint8_t messageID
, uint8_t rate
)
759 ubxMessage_t tx_buffer
;
760 tx_buffer
.payload
.cfg_msg
.msgClass
= messageClass
;
761 tx_buffer
.payload
.cfg_msg
.msgID
= messageID
;
762 tx_buffer
.payload
.cfg_msg
.rate
= rate
;
763 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_MSG
, sizeof(ubxCfgMsg_t
), false);
766 static void ubloxSetMessageRateValSet(ubxValGetSetBytes_e msgClass
, uint8_t rate
)
768 ubxMessage_t tx_buffer
;
773 size_t offset
= ubloxValSet(&tx_buffer
, msgClass
, payload
, UBX_VAL_LAYER_RAM
);
775 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_VALSET
, offsetof(ubxCfgValSet_t
, cfgData
) + offset
, true);
778 static void ubloxDisableNMEAValSet(void)
780 ubxMessage_t tx_buffer
;
786 // size_t offset = ubloxValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_GGA_I2C, payload, UBX_VAL_LAYER_RAM);
787 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_GGA_SPI, payload, offset);
788 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_GGA_UART1, payload, offset);
789 size_t offset
= ubloxValSet(&tx_buffer
, CFG_MSGOUT_NMEA_ID_GGA_UART1
, payload
, UBX_VAL_LAYER_RAM
);
791 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_VTG_I2C, payload, offset);
792 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_VTG_SPI, payload, offset);
793 offset
+= ubloxAddValSet(&tx_buffer
, CFG_MSGOUT_NMEA_ID_VTG_UART1
, payload
, offset
);
795 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_GSV_I2C, payload, offset);
796 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_GSV_SPI, payload, offset);
797 offset
+= ubloxAddValSet(&tx_buffer
, CFG_MSGOUT_NMEA_ID_GSV_UART1
, payload
, offset
);
799 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_GLL_I2C, payload, offset);
800 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_GLL_SPI, payload, offset);
801 offset
+= ubloxAddValSet(&tx_buffer
, CFG_MSGOUT_NMEA_ID_GLL_UART1
, payload
, offset
);
803 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_GSA_I2C, payload, offset);
804 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_GSA_SPI, payload, offset);
805 offset
+= ubloxAddValSet(&tx_buffer
, CFG_MSGOUT_NMEA_ID_GSA_UART1
, payload
, offset
);
807 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_RMC_I2C, payload, offset);
808 // offset += ubloxAddValSet(&tx_buffer, CFG_MSGOUT_NMEA_ID_RMC_SPI, payload, offset);
809 offset
+= ubloxAddValSet(&tx_buffer
, CFG_MSGOUT_NMEA_ID_RMC_UART1
, payload
, offset
);
811 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_VALSET
, offsetof(ubxCfgValSet_t
, cfgData
) + offset
, true);
814 static void ubloxSetNavRate(uint16_t measRate
, uint16_t navRate
, uint8_t timeRef
)
816 uint16_t measRateMilliseconds
= 1000 / measRate
;
818 ubxMessage_t tx_buffer
;
819 if (gpsData
.ubloxM9orAbove
) {
822 payload
[0] = (uint8_t)(measRateMilliseconds
>> (8 * 0));
823 payload
[1] = (uint8_t)(measRateMilliseconds
>> (8 * 1));
825 offset
= ubloxValSet(&tx_buffer
, CFG_RATE_MEAS
, payload
, UBX_VAL_LAYER_RAM
);
827 payload
[0] = (uint8_t)(navRate
>> (8 * 0));
828 payload
[1] = (uint8_t)(navRate
>> (8 * 1));
830 offset
+= ubloxAddValSet(&tx_buffer
, CFG_RATE_NAV
, payload
, 6);
832 payload
[0] = timeRef
;
833 //rate timeref is E1 = U1
834 offset
+= ubloxAddValSet(&tx_buffer
, CFG_RATE_TIMEREF
, payload
, 12);
836 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_VALSET
, offsetof(ubxCfgValSet_t
, cfgData
) + offset
, false);
838 tx_buffer
.payload
.cfg_rate
.measRate
= measRateMilliseconds
;
839 tx_buffer
.payload
.cfg_rate
.navRate
= navRate
;
840 tx_buffer
.payload
.cfg_rate
.timeRef
= timeRef
;
841 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_RATE
, sizeof(ubxCfgRate_t
), true);
845 static void ubloxSetSbas(void)
847 ubxMessage_t tx_buffer
;
849 if (gpsData
.ubloxM9orAbove
) {
851 payload
[0] = gpsConfig()->sbasMode
!= SBAS_NONE
;
853 size_t offset
= ubloxValSet(&tx_buffer
, CFG_SBAS_USE_TESTMODE
, payload
, UBX_VAL_LAYER_RAM
);
856 offset
+= ubloxAddValSet(&tx_buffer
, CFG_SBAS_USE_RANGING
, payload
, offset
);
857 offset
+= ubloxAddValSet(&tx_buffer
, CFG_SBAS_USE_DIFFCORR
, payload
, offset
);
859 if (gpsConfig()->sbas_integrity
) {
860 offset
+= ubloxAddValSet(&tx_buffer
, CFG_SBAS_USE_INTEGRITY
, payload
, offset
);
863 uint64_t mask
= SBAS_SEARCH_ALL
;
864 switch (gpsConfig()->sbasMode
) {
866 mask
= SBAS_SEARCH_PRN(123) | SBAS_SEARCH_PRN(126) | SBAS_SEARCH_PRN(136);
869 mask
= SBAS_SEARCH_PRN(131) | SBAS_SEARCH_PRN(133) | SBAS_SEARCH_PRN(135) | SBAS_SEARCH_PRN(138);
872 mask
= SBAS_SEARCH_PRN(129) | SBAS_SEARCH_PRN(137);
875 mask
= SBAS_SEARCH_PRN(127) | SBAS_SEARCH_PRN(128) | SBAS_SEARCH_PRN(132);
882 payload
[0] = (uint8_t)(mask
>> (8 * 0));
883 payload
[1] = (uint8_t)(mask
>> (8 * 1));
884 payload
[2] = (uint8_t)(mask
>> (8 * 2));
885 payload
[3] = (uint8_t)(mask
>> (8 * 3));
886 payload
[4] = (uint8_t)(mask
>> (8 * 4));
887 payload
[5] = (uint8_t)(mask
>> (8 * 5));
888 payload
[6] = (uint8_t)(mask
>> (8 * 6));
889 payload
[7] = (uint8_t)(mask
>> (8 * 7));
891 offset
+= ubloxAddValSet(&tx_buffer
, CFG_SBAS_PRNSCANMASK
, payload
, offset
);
893 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_VALSET
, offsetof(ubxCfgValSet_t
, cfgData
) + offset
, true);
895 //NOTE: default ublox config for sbas mode is: UBLOX_MODE_ENABLED, test is disabled
896 tx_buffer
.payload
.cfg_sbas
.mode
= UBLOX_MODE_TEST
;
897 if (gpsConfig()->sbasMode
!= SBAS_NONE
) {
898 tx_buffer
.payload
.cfg_sbas
.mode
|= UBLOX_MODE_ENABLED
;
901 // NOTE: default ublox config for sbas mode is: UBLOX_USAGE_RANGE | UBLOX_USAGE_DIFFCORR, integrity is disabled
902 tx_buffer
.payload
.cfg_sbas
.usage
= UBLOX_USAGE_RANGE
| UBLOX_USAGE_DIFFCORR
;
903 if (gpsConfig()->sbas_integrity
) {
904 tx_buffer
.payload
.cfg_sbas
.usage
|= UBLOX_USAGE_INTEGRITY
;
907 tx_buffer
.payload
.cfg_sbas
.maxSBAS
= 3;
908 tx_buffer
.payload
.cfg_sbas
.scanmode2
= 0;
909 switch (gpsConfig()->sbasMode
) {
911 tx_buffer
.payload
.cfg_sbas
.scanmode1
= 0;
914 tx_buffer
.payload
.cfg_sbas
.scanmode1
= 0x00010048; //PRN123, PRN126, PRN136
917 tx_buffer
.payload
.cfg_sbas
.scanmode1
= 0x0004A800; //PRN131, PRN133, PRN135, PRN138
920 tx_buffer
.payload
.cfg_sbas
.scanmode1
= 0x00020200; //PRN129, PRN137
923 tx_buffer
.payload
.cfg_sbas
.scanmode1
= 0x00001180; //PRN127, PRN128, PRN132
926 tx_buffer
.payload
.cfg_sbas
.scanmode1
= 0;
929 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_SBAS
, sizeof(ubxCfgSbas_t
), false);
933 void setSatInfoMessageRate(uint8_t divisor
)
935 // enable satInfoMessage at 1:5 of the nav rate if configurator is connected
936 if (gpsData
.ubloxM9orAbove
) {
937 ubloxSetMessageRateValSet(CFG_MSGOUT_UBX_NAV_SAT_UART1
, divisor
);
938 } else if (gpsData
.ubloxM8orAbove
) {
939 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_SAT
, divisor
);
941 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_SVINFO
, divisor
);
945 #endif // USE_GPS_UBLOX
948 void gpsConfigureNmea(void)
950 // minimal support for NMEA, we only:
951 // - set the FC's GPS port to the user's configured rate, and
952 // - send any NMEA custom commands to the GPS Module
953 // the user must configure the power-up baud rate of the module to be fast enough for their data rate
954 // Note: we always parse all incoming NMEA messages
955 DEBUG_SET(DEBUG_GPS_CONNECTION
, 4, (gpsData
.state
* 100 + gpsData
.state_position
));
957 // wait 500ms between changes
958 if (cmp32(gpsData
.now
, gpsData
.state_ts
) < 500) {
961 gpsData
.state_ts
= gpsData
.now
;
963 // Check that the GPS transmit buffer is empty
964 if (!isSerialTransmitBufferEmpty(gpsPort
)) {
968 switch (gpsData
.state
) {
970 case GPS_STATE_DETECT_BAUD
:
971 // no attempt to read the baud rate of the GPS module, or change it
972 gpsSetState(GPS_STATE_CHANGE_BAUD
);
975 case GPS_STATE_CHANGE_BAUD
:
976 #if !defined(GPS_NMEA_TX_ONLY)
977 if (gpsData
.state_position
< 1) {
978 // set the FC's baud rate to the user's configured baud rate
979 serialSetBaudRate(gpsPort
, baudRates
[gpsInitData
[gpsData
.userBaudRateIndex
].baudrateIndex
]);
980 gpsData
.state_position
++;
981 } else if (gpsData
.state_position
< 2) {
982 // send NMEA custom commands to select which messages being sent, data rate etc
983 // use PUBX, MTK, SiRF or GTK format commands, depending on module type
984 static int commandOffset
= 0;
985 const char *commands
= gpsConfig()->nmeaCustomCommands
;
986 const char *cmd
= commands
+ commandOffset
;
987 // skip leading whitespaces and get first command length
989 while (*cmd
&& (commandLen
= strcspn(cmd
, " \0")) == 0) {
990 cmd
++; // skip separators
993 // Send the current command to the GPS
994 serialWriteBuf(gpsPort
, (uint8_t *)cmd
, commandLen
);
995 serialWriteBuf(gpsPort
, (uint8_t *)"\r\n", 2);
996 // Move to the next command
999 // skip trailing whitespaces
1000 while (*cmd
&& strcspn(cmd
, " \0") == 0) cmd
++;
1002 // more commands to send
1003 commandOffset
= cmd
- commands
;
1005 gpsData
.state_position
++;
1008 gpsData
.state_position
++;
1009 gpsSetState(GPS_STATE_RECEIVING_DATA
);
1011 #else // !GPS_NMEA_TX_ONLY
1012 gpsSetState(GPS_STATE_RECEIVING_DATA
);
1013 #endif // !GPS_NMEA_TX_ONLY
1017 #endif // USE_GPS_NMEA
1019 #ifdef USE_GPS_UBLOX
1021 void gpsConfigureUblox(void)
1024 // Wait until GPS transmit buffer is empty
1025 if (!isSerialTransmitBufferEmpty(gpsPort
)) {
1029 switch (gpsData
.state
) {
1030 case GPS_STATE_DETECT_BAUD
:
1032 DEBUG_SET(DEBUG_GPS_CONNECTION
, 3, baudRates
[gpsInitData
[gpsData
.tempBaudRateIndex
].baudrateIndex
] / 100);
1034 // check to see if there has been a response to the version command
1035 // initially the FC will be at the user-configured baud rate.
1036 if (gpsData
.platformVersion
> UBX_VERSION_UNDEF
) {
1037 // set the GPS module's serial port to the user's intended baud rate
1038 serialPrint(gpsPort
, gpsInitData
[gpsData
.userBaudRateIndex
].ubx
);
1039 // use this baud rate for re-connections
1040 gpsData
.tempBaudRateIndex
= gpsData
.userBaudRateIndex
;
1041 // we're done here, let's move the the next state
1042 gpsSetState(GPS_STATE_CHANGE_BAUD
);
1046 // Send MON-VER messages at GPS_CONFIG_BAUD_CHANGE_INTERVAL for GPS_BAUDRATE_TEST_COUNT times
1047 static bool messageSent
= false;
1048 static uint8_t messageCounter
= 0;
1049 DEBUG_SET(DEBUG_GPS_CONNECTION
, 2, initBaudRateCycleCount
* 100 + messageCounter
);
1051 if (messageCounter
< GPS_BAUDRATE_TEST_COUNT
) {
1053 gpsData
.platformVersion
= UBX_VERSION_UNDEF
;
1054 ubloxSendClassMessage(CLASS_MON
, MSG_MON_VER
, 0);
1055 gpsData
.ackState
= UBLOX_ACK_IDLE
; // ignore ACK for this message
1058 if (cmp32(gpsData
.now
, gpsData
.state_ts
) > GPS_CONFIG_BAUD_CHANGE_INTERVAL
) {
1059 gpsData
.state_ts
= gpsData
.now
;
1060 messageSent
= false;
1066 gpsData
.state_ts
= gpsData
.now
;
1068 // failed to connect at that rate after five attempts
1069 // try other GPS baudrates, starting at 9600 and moving up
1070 if (gpsData
.tempBaudRateIndex
== 0) {
1071 gpsData
.tempBaudRateIndex
= GPS_BAUDRATE_MAX
; // slowest baud rate 9600
1073 gpsData
.tempBaudRateIndex
--;
1075 // set the FC baud rate to the new temp baud rate
1076 serialSetBaudRate(gpsPort
, baudRates
[gpsInitData
[gpsData
.tempBaudRateIndex
].baudrateIndex
]);
1077 initBaudRateCycleCount
++;
1081 case GPS_STATE_CHANGE_BAUD
:
1082 // give time for the GPS module's serial port to settle
1083 // very important for M8 to give the module a lot of time before sending commands
1084 // M10 only need about 200ms but M8 and below sometimes need as long as 1000ms
1085 if (cmp32(gpsData
.now
, gpsData
.state_ts
) < (3 * GPS_CONFIG_BAUD_CHANGE_INTERVAL
)) {
1088 // set the FC's serial port to the configured rate
1089 serialSetBaudRate(gpsPort
, baudRates
[gpsInitData
[gpsData
.userBaudRateIndex
].baudrateIndex
]);
1090 DEBUG_SET(DEBUG_GPS_CONNECTION
, 3, baudRates
[gpsInitData
[gpsData
.userBaudRateIndex
].baudrateIndex
] / 100);
1091 // then start sending configuration settings
1092 gpsSetState(GPS_STATE_CONFIGURE
);
1095 case GPS_STATE_CONFIGURE
:
1096 // Either use specific config file for GPS or let dynamically upload config
1097 if (gpsConfig()->autoConfig
== GPS_AUTOCONFIG_OFF
) {
1098 gpsSetState(GPS_STATE_RECEIVING_DATA
);
1102 // Add delay to stabilize the connection
1103 if (cmp32(gpsData
.now
, gpsData
.state_ts
) < 1000) {
1107 if (gpsData
.ackState
== UBLOX_ACK_IDLE
) {
1109 // short delay before between commands, including the first command
1110 static uint32_t last_state_position_time
= 0;
1111 if (last_state_position_time
== 0) {
1112 last_state_position_time
= gpsData
.now
;
1114 if (cmp32(gpsData
.now
, last_state_position_time
) < GPS_CONFIG_CHANGE_INTERVAL
) {
1117 last_state_position_time
= gpsData
.now
;
1119 switch (gpsData
.state_position
) {
1120 // if a UBX command is sent, ack is supposed to give position++ once the reply happens
1121 case UBLOX_DETECT_UNIT
: // 400 in debug
1122 if (gpsData
.platformVersion
== UBX_VERSION_UNDEF
) {
1123 ubloxSendClassMessage(CLASS_MON
, MSG_MON_VER
, 0);
1125 gpsData
.state_position
++;
1128 case UBLOX_SLOW_NAV_RATE
: // 401 in debug
1129 ubloxSetNavRate(1, 1, 1); // throttle nav data rate to one per second, until configured
1131 case UBLOX_MSG_DISABLE_NMEA
:
1132 if (gpsData
.ubloxM9orAbove
) {
1133 ubloxDisableNMEAValSet();
1134 gpsData
.state_position
= UBLOX_MSG_RMC
; // skip UBX NMEA entries - goes to RMC plus one, or ACQUIRE_MODEL
1136 gpsData
.state_position
++;
1139 case UBLOX_MSG_VGS
: //Disable NMEA Messages
1140 ubloxSetMessageRate(CLASS_NMEA_STD
, MSG_NMEA_VTG
, 0); // VGS: Course over ground and Ground speed
1143 ubloxSetMessageRate(CLASS_NMEA_STD
, MSG_NMEA_GSV
, 0); // GSV: GNSS Satellites in View
1146 ubloxSetMessageRate(CLASS_NMEA_STD
, MSG_NMEA_GLL
, 0); // GLL: Latitude and longitude, with time of position fix and status
1149 ubloxSetMessageRate(CLASS_NMEA_STD
, MSG_NMEA_GGA
, 0); // GGA: Global positioning system fix data
1152 ubloxSetMessageRate(CLASS_NMEA_STD
, MSG_NMEA_GSA
, 0); // GSA: GNSS DOP and Active Satellites
1155 ubloxSetMessageRate(CLASS_NMEA_STD
, MSG_NMEA_RMC
, 0); // RMC: Recommended Minimum data
1157 case UBLOX_ACQUIRE_MODEL
:
1158 ubloxSendNAV5Message(gpsConfig()->gps_ublox_acquire_model
);
1160 // *** temporarily disabled
1161 // case UBLOX_CFG_ANA:
1162 // i f (gpsData.ubloxM7orAbove) { // NavX5 support existed in M5 - in theory we could remove that check
1163 // ubloxSendNavX5Message();
1165 // gpsData.state_position++;
1168 case UBLOX_SET_SBAS
:
1172 if (gpsData
.ubloxM8orAbove
) {
1173 ubloxSendPowerMode();
1175 gpsData
.state_position
++;
1178 case UBLOX_MSG_NAV_PVT
: //Enable NAV-PVT Messages
1179 if (gpsData
.ubloxM9orAbove
) {
1180 ubloxSetMessageRateValSet(CFG_MSGOUT_UBX_NAV_PVT_UART1
, 1);
1181 } else if (gpsData
.ubloxM7orAbove
) {
1182 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_PVT
, 1);
1184 gpsData
.state_position
++;
1187 // if NAV-PVT is enabled, we don't need the older nav messages
1189 if (gpsData
.ubloxM9orAbove
) {
1190 // SOL is deprecated above M8
1191 gpsData
.state_position
++;
1192 } else if (gpsData
.ubloxM7orAbove
) {
1193 // use NAV-PVT, so don't use NAV-SOL
1194 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_SOL
, 0);
1196 // Only use NAV-SOL below M7
1197 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_SOL
, 1);
1200 case UBLOX_MSG_POSLLH
:
1201 if (gpsData
.ubloxM7orAbove
) {
1202 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_POSLLH
, 0);
1204 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_POSLLH
, 1);
1207 case UBLOX_MSG_STATUS
:
1208 if (gpsData
.ubloxM7orAbove
) {
1209 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_STATUS
, 0);
1211 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_STATUS
, 1);
1214 case UBLOX_MSG_VELNED
:
1215 if (gpsData
.ubloxM7orAbove
) {
1216 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_VELNED
, 0);
1218 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_VELNED
, 1);
1222 // nav-pvt has what we need and is available M7 and above
1223 if (gpsData
.ubloxM9orAbove
) {
1224 ubloxSetMessageRateValSet(CFG_MSGOUT_UBX_NAV_DOP_UART1
, 0);
1225 } else if (gpsData
.ubloxM7orAbove
) {
1226 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_DOP
, 0);
1228 ubloxSetMessageRate(CLASS_NAV
, MSG_NAV_DOP
, 1);
1231 case UBLOX_SAT_INFO
:
1232 // enable by default, turned off when armed and receiving data to reduce in-flight traffic
1233 setSatInfoMessageRate(5);
1235 case UBLOX_SET_NAV_RATE
:
1236 // set the nav solution rate to the user's configured update rate
1237 gpsData
.updateRateHz
= gpsConfig()->gps_update_rate_hz
;
1238 ubloxSetNavRate(gpsData
.updateRateHz
, 1, 1);
1240 case UBLOX_MSG_CFG_GNSS
:
1241 if ((gpsConfig()->sbasMode
== SBAS_NONE
) || (gpsConfig()->gps_ublox_use_galileo
)) {
1242 ubloxSendPollMessage(MSG_CFG_GNSS
); // poll messages wait for ACK
1244 gpsData
.state_position
++;
1247 case UBLOX_CONFIG_COMPLETE
:
1248 gpsSetState(GPS_STATE_RECEIVING_DATA
);
1250 // TO DO: (separate PR) add steps that remove I2C or SPI data on ValSet aware units, eg
1251 // ubloxSetMessageRateValSet(CFG_MSGOUT_UBX_NAV_SAT_I2C, 0);
1252 // ubloxSetMessageRateValSet(CFG_MSGOUT_UBX_NAV_SAT_SPI, 0);
1258 // check the ackState after changing CONFIG state, or every iteration while not UBLOX_ACK_IDLE
1259 switch (gpsData
.ackState
) {
1260 case UBLOX_ACK_IDLE
:
1262 case UBLOX_ACK_WAITING
:
1263 if (cmp32(gpsData
.now
, gpsData
.lastMessageSent
) > UBLOX_ACK_TIMEOUT_MS
){
1264 // give up, treat it like receiving ack
1265 gpsData
.ackState
= UBLOX_ACK_GOT_ACK
;
1268 case UBLOX_ACK_GOT_ACK
:
1269 // move forward one position, and clear the ack state
1270 gpsData
.state_position
++;
1271 gpsData
.ackState
= UBLOX_ACK_IDLE
;
1273 case UBLOX_ACK_GOT_NACK
:
1274 // this is the tricky bit
1275 // and we absolutely must get the unit type right
1276 if (gpsData
.state_position
== UBLOX_DETECT_UNIT
) {
1277 gpsSetState(GPS_STATE_CONFIGURE
);
1278 gpsData
.ackState
= UBLOX_ACK_IDLE
;
1280 // otherwise, for testing: just ignore nacks
1281 gpsData
.state_position
++;
1282 gpsData
.ackState
= UBLOX_ACK_IDLE
;
1290 #endif // USE_GPS_UBLOX
1292 void gpsConfigureHardware(void)
1294 switch (gpsConfig()->provider
) {
1302 #ifdef USE_GPS_UBLOX
1303 gpsConfigureUblox();
1311 static void updateGpsIndicator(timeUs_t currentTimeUs
)
1313 static uint32_t GPSLEDTime
;
1314 if ((int32_t)(currentTimeUs
- GPSLEDTime
) >= 0 && STATE(GPS_FIX
) && (gpsSol
.numSat
>= gpsRescueConfig()->minSats
)) {
1315 GPSLEDTime
= currentTimeUs
+ 150000;
1320 void gpsUpdate(timeUs_t currentTimeUs
)
1322 static timeDelta_t gpsStateDurationFractionUs
[GPS_STATE_COUNT
];
1323 timeDelta_t executeTimeUs
;
1324 gpsState_e gpsCurrentState
= gpsData
.state
;
1325 gpsData
.now
= millis();
1328 DEBUG_SET(DEBUG_GPS_CONNECTION
, 7, serialRxBytesWaiting(gpsPort
));
1329 static uint8_t wait
= 0;
1330 static bool isFast
= false;
1331 while (serialRxBytesWaiting(gpsPort
)) {
1334 rescheduleTask(TASK_SELF
, TASK_PERIOD_HZ(TASK_GPS_RATE_FAST
));
1337 if (cmpTimeUs(micros(), currentTimeUs
) > GPS_RECV_TIME_MAX
) {
1340 // Add every byte to _buffer, when enough bytes are received, convert data to values
1341 gpsNewData(serialRead(gpsPort
));
1345 } else if (wait
== 1) {
1347 // wait one iteration be sure the buffer is empty, then reset to the slower task interval
1349 rescheduleTask(TASK_SELF
, TASK_PERIOD_HZ(TASK_GPS_RATE
));
1351 } else if (gpsConfig()->provider
== GPS_MSP
) {
1352 if (GPS_update
& GPS_MSP_UPDATE
) { // GPS data received via MSP
1353 if (gpsData
.state
== GPS_STATE_INITIALIZED
) {
1354 gpsSetState(GPS_STATE_RECEIVING_DATA
);
1357 // Data is available
1358 DEBUG_SET(DEBUG_GPS_CONNECTION
, 3, gpsData
.now
- gpsData
.lastNavMessage
); // interval since last Nav data was received
1359 gpsData
.lastNavMessage
= gpsData
.now
;
1360 sensorsSet(SENSOR_GPS
);
1362 GPS_update
^= GPS_DIRECT_TICK
;
1366 GPS_update
&= ~GPS_MSP_UPDATE
;
1368 DEBUG_SET(DEBUG_GPS_CONNECTION
, 2, gpsData
.now
- gpsData
.lastNavMessage
); // time since last Nav data, updated each GPS task interval
1369 // check for no data/gps timeout/cable disconnection etc
1370 if (cmp32(gpsData
.now
, gpsData
.lastNavMessage
) > GPS_TIMEOUT_MS
) {
1371 gpsSetState(GPS_STATE_LOST_COMMUNICATION
);
1376 switch (gpsData
.state
) {
1377 case GPS_STATE_UNKNOWN
:
1378 case GPS_STATE_INITIALIZED
:
1381 case GPS_STATE_DETECT_BAUD
:
1382 case GPS_STATE_CHANGE_BAUD
:
1383 case GPS_STATE_CONFIGURE
:
1384 gpsConfigureHardware();
1387 case GPS_STATE_LOST_COMMUNICATION
:
1389 // previously we would attempt a different baud rate here if gps auto-baud was enabled. that code has been removed.
1391 DISABLE_STATE(GPS_FIX
);
1392 gpsSetState(GPS_STATE_DETECT_BAUD
);
1395 case GPS_STATE_RECEIVING_DATA
:
1396 #ifdef USE_GPS_UBLOX
1397 if (gpsConfig()->provider
!= GPS_MSP
) {
1398 if (gpsConfig()->autoConfig
== GPS_AUTOCONFIG_ON
) {
1399 // when we are connected up, and get a 3D fix, enable the 'flight' fix model
1400 if (!gpsData
.ubloxUsingFlightModel
&& STATE(GPS_FIX
)) {
1401 gpsData
.ubloxUsingFlightModel
= true;
1402 ubloxSendNAV5Message(gpsConfig()->gps_ublox_flight_model
);
1407 DEBUG_SET(DEBUG_GPS_CONNECTION
, 2, gpsData
.now
- gpsData
.lastNavMessage
); // time since last Nav data, updated each GPS task interval
1408 // check for no data/gps timeout/cable disconnection etc
1409 if (cmp32(gpsData
.now
, gpsData
.lastNavMessage
) > GPS_TIMEOUT_MS
) {
1410 gpsSetState(GPS_STATE_LOST_COMMUNICATION
);
1415 DEBUG_SET(DEBUG_GPS_CONNECTION
, 4, (gpsData
.state
* 100 + gpsData
.state_position
));
1416 DEBUG_SET(DEBUG_GPS_CONNECTION
, 6, gpsData
.ackState
);
1418 if (sensors(SENSOR_GPS
)) {
1419 updateGpsIndicator(currentTimeUs
);
1422 static bool hasBeeped
= false;
1423 if (!ARMING_FLAG(ARMED
)) {
1424 if (!gpsConfig()->gps_set_home_point_once
) {
1425 // clear the home fix icon between arms if the user configuration is to reset home point between arms
1426 DISABLE_STATE(GPS_FIX_HOME
);
1428 // while disarmed, beep when requirements for a home fix are met
1429 // ?? should we also beep if home fix requirements first appear after arming?
1430 if (!hasBeeped
&& STATE(GPS_FIX
) && gpsSol
.numSat
>= gpsRescueConfig()->minSats
) {
1431 beeper(BEEPER_READY_BEEP
);
1436 DEBUG_SET(DEBUG_GPS_DOP
, 0, gpsSol
.numSat
);
1437 DEBUG_SET(DEBUG_GPS_DOP
, 1, gpsSol
.dop
.pdop
);
1438 DEBUG_SET(DEBUG_GPS_DOP
, 2, gpsSol
.dop
.hdop
);
1439 DEBUG_SET(DEBUG_GPS_DOP
, 3, gpsSol
.dop
.vdop
);
1441 executeTimeUs
= micros() - currentTimeUs
;
1442 if (executeTimeUs
> (gpsStateDurationFractionUs
[gpsCurrentState
] >> GPS_TASK_DECAY_SHIFT
)) {
1443 gpsStateDurationFractionUs
[gpsCurrentState
] += (2 << GPS_TASK_DECAY_SHIFT
);
1445 // Slowly decay the max time
1446 gpsStateDurationFractionUs
[gpsCurrentState
]--;
1448 schedulerSetNextStateTime(gpsStateDurationFractionUs
[gpsCurrentState
] >> GPS_TASK_DECAY_SHIFT
);
1450 DEBUG_SET(DEBUG_GPS_CONNECTION
, 5, executeTimeUs
);
1451 // keeping temporarily, to be used when debugging the scheduler stuff
1452 // DEBUG_SET(DEBUG_GPS_CONNECTION, 6, (gpsStateDurationFractionUs[gpsCurrentState] >> GPS_TASK_DECAY_SHIFT));
1455 static void gpsNewData(uint16_t c
)
1457 DEBUG_SET(DEBUG_GPS_CONNECTION
, 1, gpsSol
.navIntervalMs
);
1458 if (!gpsNewFrame(c
)) {
1459 // no new nav solution data
1462 if (gpsData
.state
== GPS_STATE_RECEIVING_DATA
) {
1463 DEBUG_SET(DEBUG_GPS_CONNECTION
, 3, gpsData
.now
- gpsData
.lastNavMessage
); // interval since last Nav data was received
1464 gpsData
.lastNavMessage
= gpsData
.now
;
1465 sensorsSet(SENSOR_GPS
);
1466 // use the baud rate debug once receiving data
1468 GPS_update
^= GPS_DIRECT_TICK
;
1472 #ifdef USE_GPS_UBLOX
1473 ubloxVersion_e
ubloxParseVersion(const uint32_t version
) {
1474 for (size_t i
= 0; i
< ARRAYLEN(ubloxVersionMap
); ++i
) {
1475 if (version
== ubloxVersionMap
[i
].hw
) {
1476 return (ubloxVersion_e
) i
;
1480 return UBX_VERSION_UNDEF
;// (ubloxVersion_e) version;
1484 bool gpsNewFrame(uint8_t c
)
1486 switch (gpsConfig()->provider
) {
1487 case GPS_NMEA
: // NMEA
1489 return gpsNewFrameNMEA(c
);
1492 case GPS_UBLOX
: // UBX binary
1493 #ifdef USE_GPS_UBLOX
1494 return gpsNewFrameUBLOX(c
);
1503 // Check for healthy communications
1504 bool gpsIsHealthy(void)
1506 return (gpsData
.state
== GPS_STATE_RECEIVING_DATA
);
1509 /* This is a light implementation of a GPS frame decoding
1510 This should work with most of modern GPS devices configured to output 5 frames.
1511 It assumes there are some NMEA GGA frames to decode on the serial bus
1512 Now verifies checksum correctly before applying data
1514 Here we use only the following data :
1517 - GPS fix is/is not ok
1518 - GPS num sat (4 is enough to be +/- reliable)
1520 - GPS altitude (for OSD displaying)
1521 - GPS speed (for OSD displaying)
1531 // This code is used for parsing NMEA data
1533 /* Alex optimization
1534 The latitude or longitude is coded this way in NMEA frames
1535 dm.f coded as degrees + minutes + minute decimal
1537 - d can be 1 or more char long. generally: 2 char long for latitude, 3 char long for longitude
1538 - m is always 2 char long
1539 - f can be 1 or more char long
1540 This function converts this format in a unique unsigned long where 1 degree = 10 000 000
1542 EOS increased the precision here, even if we think that the gps is not precise enough, with 10e5 precision it has 76cm resolution
1543 with 10e7 it's around 1 cm now. Increasing it further is irrelevant, since even 1cm resolution is unrealistic, however increased
1544 resolution also increased precision of nav calculations
1545 static uint32_t GPS_coord_to_degrees(char *coordinateString)
1547 char *p = s, *d = s;
1548 uint8_t min, deg = 0;
1549 uint16_t frac = 0, mult = 10000;
1551 while (*p) { // parse the string until its end
1553 frac += (*p - '0') * mult; // calculate only fractional part on up to 5 digits (d != s condition is true when the . is located)
1557 d = p; // locate '.' char in the string
1563 deg *= 10; // convert degrees : all chars before minutes ; for the first iteration, deg = 0
1564 deg += *(s++) - '0';
1566 min = *(d - 1) - '0' + (*(d - 2) - '0') * 10; // convert minutes : 2 previous char before '.'
1567 return deg * 10000000UL + (min * 100000UL + frac) * 10UL / 6;
1573 static uint32_t grab_fields(char *src
, uint8_t mult
)
1574 { // convert string to uint32
1578 for (i
= 0; src
[i
] != 0; i
++) {
1579 if ((i
== 0) && (src
[0] == '-')) { // detect negative sign
1581 continue; // jump to next character if the first one was a negative sign
1583 if (src
[i
] == '.') {
1592 if (src
[i
] >= '0' && src
[i
] <= '9') {
1593 tmp
+= src
[i
] - '0';
1596 return 0; // out of bounds
1599 return isneg
? -tmp
: tmp
; // handle negative altitudes
1602 typedef struct gpsDataNmea_s
{
1611 uint16_t ground_course
;
1616 static void parseFieldNmea(gpsDataNmea_t
*data
, char *str
, uint8_t gpsFrame
, uint8_t idx
)
1618 static uint8_t svMessageNum
= 0;
1619 uint8_t svSatNum
= 0, svPacketIdx
= 0, svSatParam
= 0;
1623 case FRAME_GGA
: //************* GPGGA FRAME parsing
1626 data
->time
= ((uint8_t)(str
[5] - '0') * 10 + (uint8_t)(str
[7] - '0')) * 100;
1629 data
->latitude
= GPS_coord_to_degrees(str
);
1632 if (str
[0] == 'S') data
->latitude
*= -1;
1635 data
->longitude
= GPS_coord_to_degrees(str
);
1638 if (str
[0] == 'W') data
->longitude
*= -1;
1641 gpsSetFixState(str
[0] > '0');
1644 data
->numSat
= grab_fields(str
, 0);
1647 data
->altitudeCm
= grab_fields(str
, 1) * 10; // altitude in centimeters. Note: NMEA delivers altitude with 1 or 3 decimals. It's safer to cut at 0.1m and multiply by 10
1652 case FRAME_RMC
: //************* GPRMC FRAME parsing
1655 data
->time
= grab_fields(str
, 2); // UTC time hhmmss.ss
1658 data
->speed
= ((grab_fields(str
, 1) * 5144L) / 1000L); // speed in cm/s added by Mis
1661 data
->ground_course
= (grab_fields(str
, 1)); // ground course deg * 10
1664 data
->date
= grab_fields(str
, 0); // date dd/mm/yy
1672 // Total number of messages of this type in this cycle
1676 svMessageNum
= grab_fields(str
, 0);
1679 // Total number of SVs visible
1680 GPS_numCh
= MIN(grab_fields(str
, 0), GPS_SV_MAXSATS_LEGACY
);
1686 svPacketIdx
= (idx
- 4) / 4 + 1; // satellite number in packet, 1-4
1687 svSatNum
= svPacketIdx
+ (4 * (svMessageNum
- 1)); // global satellite number
1688 svSatParam
= idx
- 3 - (4 * (svPacketIdx
- 1)); // parameter number for satellite
1690 if (svSatNum
> GPS_SV_MAXSATS_LEGACY
)
1693 switch (svSatParam
) {
1696 GPS_svinfo_chn
[svSatNum
- 1] = svSatNum
;
1697 GPS_svinfo_svid
[svSatNum
- 1] = grab_fields(str
, 0);
1700 // Elevation, in degrees, 90 maximum
1703 // Azimuth, degrees from True North, 000 through 359
1706 // SNR, 00 through 99 dB (null when not tracking)
1707 GPS_svinfo_cno
[svSatNum
- 1] = grab_fields(str
, 0);
1708 GPS_svinfo_quality
[svSatNum
- 1] = 0; // only used by ublox
1712 #ifdef USE_DASHBOARD
1713 dashboardGpsNavSvInfoRcvCount
++;
1720 data
->pdop
= grab_fields(str
, 2); // pDOP * 100
1723 data
->hdop
= grab_fields(str
, 2); // hDOP * 100
1726 data
->vdop
= grab_fields(str
, 2); // vDOP * 100
1733 static bool writeGpsSolutionNmea(gpsSolutionData_t
*sol
, const gpsDataNmea_t
*data
, uint8_t gpsFrame
)
1735 int navDeltaTimeMs
= 100;
1736 const uint32_t msInTenSeconds
= 10000;
1740 #ifdef USE_DASHBOARD
1741 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_NMEA_GGA
;
1743 if (STATE(GPS_FIX
)) {
1744 sol
->llh
.lat
= data
->latitude
;
1745 sol
->llh
.lon
= data
->longitude
;
1746 sol
->numSat
= data
->numSat
;
1747 sol
->llh
.altCm
= data
->altitudeCm
;
1749 navDeltaTimeMs
= (msInTenSeconds
+ data
->time
- gpsData
.lastNavSolTs
) % msInTenSeconds
;
1750 gpsData
.lastNavSolTs
= data
->time
;
1751 sol
->navIntervalMs
= constrain(navDeltaTimeMs
, 100, 2500);
1752 // return only one true statement to trigger one "newGpsDataReady" flag per GPS loop
1756 #ifdef USE_DASHBOARD
1757 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_NMEA_GSA
;
1759 sol
->dop
.pdop
= data
->pdop
;
1760 sol
->dop
.hdop
= data
->hdop
;
1761 sol
->dop
.vdop
= data
->vdop
;
1765 #ifdef USE_DASHBOARD
1766 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_NMEA_RMC
;
1768 sol
->groundSpeed
= data
->speed
;
1769 sol
->groundCourse
= data
->ground_course
;
1771 // This check will miss 00:00:00.00, but we shouldn't care - next report will be valid
1772 if(!rtcHasTime() && data
->date
!= 0 && data
->time
!= 0) {
1773 dateTime_t temp_time
;
1774 temp_time
.year
= (data
->date
% 100) + 2000;
1775 temp_time
.month
= (data
->date
/ 100) % 100;
1776 temp_time
.day
= (data
->date
/ 10000) % 100;
1777 temp_time
.hours
= (data
->time
/ 1000000) % 100;
1778 temp_time
.minutes
= (data
->time
/ 10000) % 100;
1779 temp_time
.seconds
= (data
->time
/ 100) % 100;
1780 temp_time
.millis
= (data
->time
& 100) * 10;
1781 rtcSetDateTime(&temp_time
);
1791 static bool gpsNewFrameNMEA(char c
)
1793 static gpsDataNmea_t gps_msg
;
1794 static char string
[15];
1795 static uint8_t param
= 0, offset
= 0, parity
= 0;
1796 static uint8_t checksum_param
, gps_frame
= NO_FRAME
;
1797 bool receivedNavMessage
= false;
1810 if (param
== 0) { // frame identification (5 chars, e.g. "GPGGA", "GNGGA", "GLGGA", ...)
1811 gps_frame
= NO_FRAME
;
1812 if (strcmp(&string
[2], "GGA") == 0) {
1813 gps_frame
= FRAME_GGA
;
1814 } else if (strcmp(&string
[2], "RMC") == 0) {
1815 gps_frame
= FRAME_RMC
;
1816 } else if (strcmp(&string
[2], "GSV") == 0) {
1817 gps_frame
= FRAME_GSV
;
1818 } else if (strcmp(&string
[2], "GSA") == 0) {
1819 gps_frame
= FRAME_GSA
;
1823 // parse string and write data into gps_msg
1824 parseFieldNmea(&gps_msg
, string
, gps_frame
, param
);
1836 if (checksum_param
) { //parity checksum
1837 #ifdef USE_DASHBOARD
1840 uint8_t checksum
= 16 * ((string
[0] >= 'A') ? string
[0] - 'A' + 10 : string
[0] - '0') + ((string
[1] >= 'A') ? string
[1] - 'A' + 10 : string
[1] - '0');
1841 if (checksum
== parity
) {
1842 #ifdef USE_DASHBOARD
1843 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_IGNORED
;
1844 dashboardGpsPacketCount
++;
1846 receivedNavMessage
= writeGpsSolutionNmea(&gpsSol
, &gps_msg
, gps_frame
); // // write gps_msg into gpsSol
1848 #ifdef USE_DASHBOARD
1850 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_ERROR
;
1859 string
[offset
++] = c
;
1860 if (!checksum_param
)
1865 return receivedNavMessage
;
1867 #endif // USE_GPS_NMEA
1869 #ifdef USE_GPS_UBLOX
1871 typedef struct ubxNavPosllh_s
{
1872 uint32_t time
; // GPS msToW
1875 int32_t altitude_ellipsoid
;
1876 int32_t altitudeMslMm
;
1877 uint32_t horizontal_accuracy
;
1878 uint32_t vertical_accuracy
;
1881 typedef struct ubxNavStatus_s
{
1882 uint32_t time
; // GPS msToW
1885 uint8_t differential_status
;
1887 uint32_t time_to_first_fix
;
1888 uint32_t uptime
; // milliseconds
1891 typedef struct ubxNavDop_s
{
1892 uint32_t itow
; // GPS Millisecond Time of Week
1893 uint16_t gdop
; // Geometric DOP
1894 uint16_t pdop
; // Position DOP
1895 uint16_t tdop
; // Time DOP
1896 uint16_t vdop
; // Vertical DOP
1897 uint16_t hdop
; // Horizontal DOP
1898 uint16_t ndop
; // Northing DOP
1899 uint16_t edop
; // Easting DOP
1902 typedef struct ubxNavSol_s
{
1911 uint32_t position_accuracy_3d
;
1912 int32_t ecef_x_velocity
;
1913 int32_t ecef_y_velocity
;
1914 int32_t ecef_z_velocity
;
1915 uint32_t speed_accuracy
;
1916 uint16_t position_DOP
;
1922 typedef struct ubxNavPvt_s
{
1952 uint8_t reserved0
[5];
1958 typedef struct ubxNavVelned_s
{
1959 uint32_t time
; // GPS msToW
1966 uint32_t speed_accuracy
;
1967 uint32_t heading_accuracy
;
1970 typedef struct ubxNavSvinfoChannel_s
{
1971 uint8_t chn
; // Channel number, 255 for SVx not assigned to channel
1972 uint8_t svid
; // Satellite ID
1973 uint8_t flags
; // Bitmask
1974 uint8_t quality
; // Bitfield
1975 uint8_t cno
; // Carrier to Noise Ratio (Signal Strength) // dbHz, 0-55.
1976 uint8_t elev
; // Elevation in integer degrees
1977 int16_t azim
; // Azimuth in integer degrees
1978 int32_t prRes
; // Pseudo range residual in centimetres
1979 } ubxNavSvinfoChannel_t
;
1981 typedef struct ubxNavSatSv_s
{
1983 uint8_t svId
; // Satellite ID
1984 uint8_t cno
; // Carrier to Noise Ratio (Signal Strength) // dbHz, 0-55.
1985 int8_t elev
; // Elevation in integer degrees
1986 int16_t azim
; // Azimuth in integer degrees
1987 int16_t prRes
; // Pseudo range residual in decimetres
1988 uint32_t flags
; // Bitmask
1991 typedef struct ubxNavSvinfo_s
{
1992 uint32_t time
; // GPS Millisecond time of week
1993 uint8_t numCh
; // Number of channels
1994 uint8_t globalFlags
; // Bitmask, Chip hardware generation 0:Antaris, 1:u-blox 5, 2:u-blox 6
1995 uint16_t reserved2
; // Reserved
1996 ubxNavSvinfoChannel_t channel
[GPS_SV_MAXSATS_M8N
]; // 32 satellites * 12 bytes
1999 typedef struct ubxNavSat_s
{
2000 uint32_t time
; // GPS Millisecond time of week
2003 uint8_t reserved0
[2];
2004 ubxNavSatSv_t svs
[GPS_SV_MAXSATS_M8N
];
2007 typedef struct ubxAck_s
{
2008 uint8_t clsId
; // Class ID of the acknowledged message
2009 uint8_t msgId
; // Message ID of the acknowledged message
2014 FIX_DEAD_RECKONING
= 1,
2017 FIX_GPS_DEAD_RECKONING
= 4,
2022 NAV_STATUS_FIX_VALID
= 1,
2023 NAV_STATUS_TIME_WEEK_VALID
= 4,
2024 NAV_STATUS_TIME_SECOND_VALID
= 8
2025 } ubxNavStatusBits_e
;
2032 // Do we have a new valid fix?
2033 static bool ubxHaveNewValidFix
= false;
2035 // Do we have new position information?
2036 static bool ubxHaveNewPosition
= false;
2038 // Do we have new speed information?
2039 static bool ubxHaveNewSpeed
= false;
2041 // From the UBX protocol docs, the largest payload we receive is NAV-SAT, which
2042 // is calculated as 8 + 12*numCh. Max reported sats can be up to 56.
2043 // We're using the max for M8 (32) for our sizing, since Configurator only
2044 // supports a max of 32 sats and we want to limit the payload buffer space used.
2045 #define UBLOX_PAYLOAD_SIZE (8 + 12 * GPS_SV_MAXSATS_M8N)
2046 #define UBLOX_MAX_PAYLOAD_SANITY_SIZE 776 // Any returned payload length greater than a 64 sat NAV-SAT is considered unreasonable, and probably corrupted data.
2048 // Received message frame fields.
2049 // - Preamble sync character 1 & 2 are not saved, only detected for parsing.
2050 // - Message class & message ID indicate the type of message receieved.
2051 static uint8_t ubxRcvMsgClass
;
2052 static uint8_t ubxRcvMsgID
;
2053 // - Payload length assembled from the length LSB & MSB bytes.
2054 static uint16_t ubxRcvMsgPayloadLength
;
2055 // - Payload, each message type has its own payload field layout, represented by the elements of this union.
2056 // Note that the size of the buffer is determined by the longest possible payload, currently UBX-NAV-SAT.
2057 // See size define comments above. Warning, this is fragile! If another message type becomes the largest
2058 // payload instead of UBX-NAV-SAT, UBLOX_PAYLOAD_SIZE above needs to be adjusted!
2060 ubxNavPosllh_t ubxNavPosllh
;
2061 ubxNavStatus_t ubxNavStatus
;
2062 ubxNavDop_t ubxNavDop
;
2063 ubxNavSol_t ubxNavSol
;
2064 ubxNavVelned_t ubxNavVelned
;
2065 ubxNavPvt_t ubxNavPvt
;
2066 ubxNavSvinfo_t ubxNavSvinfo
;
2067 ubxNavSat_t ubxNavSat
;
2068 ubxCfgGnss_t ubxCfgGnss
;
2069 ubxMonVer_t ubxMonVer
;
2071 uint8_t rawBytes
[UBLOX_PAYLOAD_SIZE
]; // Used for adding raw bytes to the payload. WARNING: This byte array must be as large as the largest payload for any message type above!
2073 // - Checksum A & B. Uses the 8-bit Fletcher algorithm (TCP standard RFC 1145).
2074 static uint8_t ubxRcvMsgChecksumA
;
2075 static uint8_t ubxRcvMsgChecksumB
;
2077 // Message frame parsing state machine control.
2079 UBX_PARSE_PREAMBLE_SYNC_1
,
2080 UBX_PARSE_PREAMBLE_SYNC_2
,
2081 UBX_PARSE_MESSAGE_CLASS
,
2082 UBX_PARSE_MESSAGE_ID
,
2083 UBX_PARSE_PAYLOAD_LENGTH_LSB
,
2084 UBX_PARSE_PAYLOAD_LENGTH_MSB
,
2085 UBX_PARSE_PAYLOAD_CONTENT
,
2086 UBX_PARSE_CHECKSUM_A
,
2087 UBX_PARSE_CHECKSUM_B
2088 } ubxFrameParseState_e
;
2089 static ubxFrameParseState_e ubxFrameParseState
= UBX_PARSE_PREAMBLE_SYNC_1
;
2090 static uint16_t ubxFrameParsePayloadCounter
;
2092 static void calculateNavInterval (void)
2094 // calculate the interval between nav packets, handling iTow wraparound at the end of the week
2095 const uint32_t weekDurationMs
= 7 * 24 * 3600 * 1000;
2096 const uint32_t navDeltaTimeMs
= (weekDurationMs
+ gpsSol
.time
- gpsData
.lastNavSolTs
) % weekDurationMs
;
2097 gpsData
.lastNavSolTs
= gpsSol
.time
;
2098 // constrain the interval between 50ms / 20hz or 2.5s, when we would get a connection failure anyway
2099 gpsSol
.navIntervalMs
= constrain(navDeltaTimeMs
, 50, 2500);
2102 // SCEDEBUG To help debug which message is slow to process
2103 // static uint8_t lastUbxRcvMsgClass;
2104 // static uint8_t lastUbxRcvMsgID;
2106 // Combines message class & ID for a single value to switch on.
2107 #define CLSMSG(cls, msg) (((cls) << 8) | (msg))
2109 static bool UBLOX_parse_gps(void)
2113 // lastUbxRcvMsgClass = ubxRcvMsgClass;
2114 // lastUbxRcvMsgID = ubxRcvMsgID;
2116 #ifdef USE_DASHBOARD
2117 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_IGNORED
;
2119 switch (CLSMSG(ubxRcvMsgClass
, ubxRcvMsgID
)) {
2121 case CLSMSG(CLASS_MON
, MSG_MON_VER
):
2122 #ifdef USE_DASHBOARD
2123 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_UBLOX_MONVER
;
2125 gpsData
.platformVersion
= ubloxParseVersion(strtoul(ubxRcvMsgPayload
.ubxMonVer
.hwVersion
, NULL
, 16));
2126 gpsData
.ubloxM7orAbove
= gpsData
.platformVersion
>= UBX_VERSION_M7
;
2127 gpsData
.ubloxM8orAbove
= gpsData
.platformVersion
>= UBX_VERSION_M8
;
2128 gpsData
.ubloxM9orAbove
= gpsData
.platformVersion
>= UBX_VERSION_M9
;
2130 case CLSMSG(CLASS_NAV
, MSG_NAV_POSLLH
):
2131 #ifdef USE_DASHBOARD
2132 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_UBLOX_POSLLH
;
2134 //i2c_dataset.time = _buffer.ubxNavPosllh.time;
2135 gpsSol
.llh
.lon
= ubxRcvMsgPayload
.ubxNavPosllh
.longitude
;
2136 gpsSol
.llh
.lat
= ubxRcvMsgPayload
.ubxNavPosllh
.latitude
;
2137 gpsSol
.llh
.altCm
= ubxRcvMsgPayload
.ubxNavPosllh
.altitudeMslMm
/ 10; //alt in cm
2138 gpsSol
.time
= ubxRcvMsgPayload
.ubxNavPosllh
.time
;
2139 calculateNavInterval();
2140 gpsSetFixState(ubxHaveNewValidFix
);
2141 ubxHaveNewPosition
= true;
2143 case CLSMSG(CLASS_NAV
, MSG_NAV_STATUS
):
2144 #ifdef USE_DASHBOARD
2145 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_UBLOX_STATUS
;
2147 ubxHaveNewValidFix
= (ubxRcvMsgPayload
.ubxNavStatus
.fix_status
& NAV_STATUS_FIX_VALID
) && (ubxRcvMsgPayload
.ubxNavStatus
.fix_type
== FIX_3D
);
2148 if (!ubxHaveNewValidFix
)
2149 DISABLE_STATE(GPS_FIX
);
2151 case CLSMSG(CLASS_NAV
, MSG_NAV_DOP
):
2152 #ifdef USE_DASHBOARD
2153 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_UBLOX_DOP
;
2155 gpsSol
.dop
.pdop
= ubxRcvMsgPayload
.ubxNavDop
.pdop
;
2156 gpsSol
.dop
.hdop
= ubxRcvMsgPayload
.ubxNavDop
.hdop
;
2157 gpsSol
.dop
.vdop
= ubxRcvMsgPayload
.ubxNavDop
.vdop
;
2159 case CLSMSG(CLASS_NAV
, MSG_NAV_SOL
):
2160 #ifdef USE_DASHBOARD
2161 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_UBLOX_SOL
;
2163 ubxHaveNewValidFix
= (ubxRcvMsgPayload
.ubxNavSol
.fix_status
& NAV_STATUS_FIX_VALID
) && (ubxRcvMsgPayload
.ubxNavSol
.fix_type
== FIX_3D
);
2164 if (!ubxHaveNewValidFix
)
2165 DISABLE_STATE(GPS_FIX
);
2166 gpsSol
.numSat
= ubxRcvMsgPayload
.ubxNavSol
.satellites
;
2168 //set clock, when gps time is available
2169 if (!rtcHasTime() && (ubxRcvMsgPayload
.ubxNavSol
.fix_status
& NAV_STATUS_TIME_SECOND_VALID
) && (ubxRcvMsgPayload
.ubxNavSol
.fix_status
& NAV_STATUS_TIME_WEEK_VALID
)) {
2170 //calculate rtctime: week number * ms in a week + ms of week + fractions of second + offset to UNIX reference year - 18 leap seconds
2171 rtcTime_t temp_time
= (((int64_t) ubxRcvMsgPayload
.ubxNavSol
.week
) * 7 * 24 * 60 * 60 * 1000) + ubxRcvMsgPayload
.ubxNavSol
.time
+ (ubxRcvMsgPayload
.ubxNavSol
.time_nsec
/ 1000000) + 315964800000LL - 18000;
2176 case CLSMSG(CLASS_NAV
, MSG_NAV_VELNED
):
2177 #ifdef USE_DASHBOARD
2178 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_UBLOX_VELNED
;
2180 gpsSol
.speed3d
= ubxRcvMsgPayload
.ubxNavVelned
.speed_3d
; // cm/s
2181 gpsSol
.groundSpeed
= ubxRcvMsgPayload
.ubxNavVelned
.speed_2d
; // cm/s
2182 gpsSol
.groundCourse
= (uint16_t) (ubxRcvMsgPayload
.ubxNavVelned
.heading_2d
/ 10000); // Heading 2D deg * 100000 rescaled to deg * 10
2183 ubxHaveNewSpeed
= true;
2185 case CLSMSG(CLASS_NAV
, MSG_NAV_PVT
):
2186 #ifdef USE_DASHBOARD
2187 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_UBLOX_SOL
;
2189 ubxHaveNewValidFix
= (ubxRcvMsgPayload
.ubxNavPvt
.flags
& NAV_STATUS_FIX_VALID
) && (ubxRcvMsgPayload
.ubxNavPvt
.fixType
== FIX_3D
);
2190 gpsSol
.time
= ubxRcvMsgPayload
.ubxNavPvt
.time
;
2191 calculateNavInterval();
2192 gpsSol
.llh
.lon
= ubxRcvMsgPayload
.ubxNavPvt
.lon
;
2193 gpsSol
.llh
.lat
= ubxRcvMsgPayload
.ubxNavPvt
.lat
;
2194 gpsSol
.llh
.altCm
= ubxRcvMsgPayload
.ubxNavPvt
.hMSL
/ 10; //alt in cm
2195 gpsSetFixState(ubxHaveNewValidFix
);
2196 ubxHaveNewPosition
= true;
2197 gpsSol
.numSat
= ubxRcvMsgPayload
.ubxNavPvt
.numSV
;
2198 gpsSol
.acc
.hAcc
= ubxRcvMsgPayload
.ubxNavPvt
.hAcc
;
2199 gpsSol
.acc
.vAcc
= ubxRcvMsgPayload
.ubxNavPvt
.vAcc
;
2200 gpsSol
.acc
.sAcc
= ubxRcvMsgPayload
.ubxNavPvt
.sAcc
;
2201 gpsSol
.speed3d
= (uint16_t) sqrtf(powf(ubxRcvMsgPayload
.ubxNavPvt
.gSpeed
/ 10, 2.0f
) + powf(ubxRcvMsgPayload
.ubxNavPvt
.velD
/ 10, 2.0f
));
2202 gpsSol
.groundSpeed
= ubxRcvMsgPayload
.ubxNavPvt
.gSpeed
/ 10; // cm/s
2203 gpsSol
.groundCourse
= (uint16_t) (ubxRcvMsgPayload
.ubxNavPvt
.headMot
/ 10000); // Heading 2D deg * 100000 rescaled to deg * 10
2204 gpsSol
.dop
.pdop
= ubxRcvMsgPayload
.ubxNavPvt
.pDOP
;
2205 ubxHaveNewSpeed
= true;
2207 //set clock, when gps time is available
2208 if (!rtcHasTime() && (ubxRcvMsgPayload
.ubxNavPvt
.valid
& NAV_VALID_DATE
) && (ubxRcvMsgPayload
.ubxNavPvt
.valid
& NAV_VALID_TIME
)) {
2210 dt
.year
= ubxRcvMsgPayload
.ubxNavPvt
.year
;
2211 dt
.month
= ubxRcvMsgPayload
.ubxNavPvt
.month
;
2212 dt
.day
= ubxRcvMsgPayload
.ubxNavPvt
.day
;
2213 dt
.hours
= ubxRcvMsgPayload
.ubxNavPvt
.hour
;
2214 dt
.minutes
= ubxRcvMsgPayload
.ubxNavPvt
.min
;
2215 dt
.seconds
= ubxRcvMsgPayload
.ubxNavPvt
.sec
;
2216 dt
.millis
= (ubxRcvMsgPayload
.ubxNavPvt
.nano
> 0) ? ubxRcvMsgPayload
.ubxNavPvt
.nano
/ 1000 : 0; //up to 5ms of error
2217 rtcSetDateTime(&dt
);
2221 case CLSMSG(CLASS_NAV
, MSG_NAV_SVINFO
):
2222 #ifdef USE_DASHBOARD
2223 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_UBLOX_SVINFO
;
2225 GPS_numCh
= ubxRcvMsgPayload
.ubxNavSvinfo
.numCh
;
2226 // If we're receiving UBX-NAV-SVINFO messages, we detected a module version M7 or older.
2227 // We can receive far more sats than we can handle for Configurator, which is the primary consumer for sat info.
2228 // We're using the max for legacy (16) for our sizing, this smaller sizing triggers Configurator to know it's
2229 // an M7 or earlier module and to use the older sat list format.
2230 // We simply ignore any sats above that max, the down side is we may not see sats used for the solution, but
2231 // the intent in Configurator is to see if sats are being acquired and their strength, so this is not an issue.
2232 if (GPS_numCh
> GPS_SV_MAXSATS_LEGACY
)
2233 GPS_numCh
= GPS_SV_MAXSATS_LEGACY
;
2234 for (i
= 0; i
< GPS_numCh
; i
++) {
2235 GPS_svinfo_chn
[i
] = ubxRcvMsgPayload
.ubxNavSvinfo
.channel
[i
].chn
;
2236 GPS_svinfo_svid
[i
] = ubxRcvMsgPayload
.ubxNavSvinfo
.channel
[i
].svid
;
2237 GPS_svinfo_quality
[i
] = ubxRcvMsgPayload
.ubxNavSvinfo
.channel
[i
].quality
;
2238 GPS_svinfo_cno
[i
] = ubxRcvMsgPayload
.ubxNavSvinfo
.channel
[i
].cno
;
2240 for (; i
< GPS_SV_MAXSATS_LEGACY
; i
++) {
2241 GPS_svinfo_chn
[i
] = 0;
2242 GPS_svinfo_svid
[i
] = 0;
2243 GPS_svinfo_quality
[i
] = 0;
2244 GPS_svinfo_cno
[i
] = 0;
2246 #ifdef USE_DASHBOARD
2247 dashboardGpsNavSvInfoRcvCount
++;
2250 case CLSMSG(CLASS_NAV
, MSG_NAV_SAT
):
2251 #ifdef USE_DASHBOARD
2252 *dashboardGpsPacketLogCurrentChar
= DASHBOARD_LOG_UBLOX_SVINFO
; // The display log only shows SVINFO for both SVINFO and SAT.
2254 GPS_numCh
= ubxRcvMsgPayload
.ubxNavSat
.numSvs
;
2255 // If we're receiving UBX-NAV-SAT messages, we detected a module M8 or newer.
2256 // We can receive far more sats than we can handle for Configurator, which is the primary consumer for sat info.
2257 // We're using the max for M8 (32) for our sizing, since Configurator only supports a max of 32 sats and we
2258 // want to limit the payload buffer space used.
2259 // We simply ignore any sats above that max, the down side is we may not see sats used for the solution, but
2260 // the intent in Configurator is to see if sats are being acquired and their strength, so this is not an issue.
2261 if (GPS_numCh
> GPS_SV_MAXSATS_M8N
)
2262 GPS_numCh
= GPS_SV_MAXSATS_M8N
;
2263 for (i
= 0; i
< GPS_numCh
; i
++) {
2264 GPS_svinfo_chn
[i
] = ubxRcvMsgPayload
.ubxNavSat
.svs
[i
].gnssId
;
2265 GPS_svinfo_svid
[i
] = ubxRcvMsgPayload
.ubxNavSat
.svs
[i
].svId
;
2266 GPS_svinfo_cno
[i
] = ubxRcvMsgPayload
.ubxNavSat
.svs
[i
].cno
;
2267 GPS_svinfo_quality
[i
] = ubxRcvMsgPayload
.ubxNavSat
.svs
[i
].flags
;
2269 for (; i
< GPS_SV_MAXSATS_M8N
; i
++) {
2270 GPS_svinfo_chn
[i
] = 255;
2271 GPS_svinfo_svid
[i
] = 0;
2272 GPS_svinfo_quality
[i
] = 0;
2273 GPS_svinfo_cno
[i
] = 0;
2276 // Setting the number of channels higher than GPS_SV_MAXSATS_LEGACY is the only way to tell BF Configurator we're sending the
2277 // enhanced sat list info without changing the MSP protocol. Also, we're sending the complete list each time even if it's empty, so
2278 // BF Conf can erase old entries shown on screen when channels are removed from the list.
2279 GPS_numCh
= GPS_SV_MAXSATS_M8N
;
2280 #ifdef USE_DASHBOARD
2281 dashboardGpsNavSvInfoRcvCount
++;
2284 case CLSMSG(CLASS_CFG
, MSG_CFG_GNSS
):
2286 bool isSBASenabled
= false;
2287 bool isM8NwithDefaultConfig
= false;
2289 if ((ubxRcvMsgPayload
.ubxCfgGnss
.numConfigBlocks
>= 2) &&
2290 (ubxRcvMsgPayload
.ubxCfgGnss
.configblocks
[1].gnssId
== 1) && //SBAS
2291 (ubxRcvMsgPayload
.ubxCfgGnss
.configblocks
[1].flags
& UBLOX_GNSS_ENABLE
)) { //enabled
2293 isSBASenabled
= true;
2296 if ((ubxRcvMsgPayload
.ubxCfgGnss
.numTrkChHw
== 32) && //M8N
2297 (ubxRcvMsgPayload
.ubxCfgGnss
.numTrkChUse
== 32) &&
2298 (ubxRcvMsgPayload
.ubxCfgGnss
.numConfigBlocks
== 7) &&
2299 (ubxRcvMsgPayload
.ubxCfgGnss
.configblocks
[2].gnssId
== 2) && //Galileo
2300 (ubxRcvMsgPayload
.ubxCfgGnss
.configblocks
[2].resTrkCh
== 4) && //min channels
2301 (ubxRcvMsgPayload
.ubxCfgGnss
.configblocks
[2].maxTrkCh
== 8) && //max channels
2302 !(ubxRcvMsgPayload
.ubxCfgGnss
.configblocks
[2].flags
& UBLOX_GNSS_ENABLE
)) { //disabled
2304 isM8NwithDefaultConfig
= true;
2307 const uint16_t messageSize
= 4 + (ubxRcvMsgPayload
.ubxCfgGnss
.numConfigBlocks
* sizeof(ubxConfigblock_t
));
2309 ubxMessage_t tx_buffer
;
2310 memcpy(&tx_buffer
.payload
, &ubxRcvMsgPayload
, messageSize
);
2312 if (isSBASenabled
&& (gpsConfig()->sbasMode
== SBAS_NONE
)) {
2313 tx_buffer
.payload
.cfg_gnss
.configblocks
[1].flags
&= ~UBLOX_GNSS_ENABLE
; //Disable SBAS
2316 if (isM8NwithDefaultConfig
&& gpsConfig()->gps_ublox_use_galileo
) {
2317 tx_buffer
.payload
.cfg_gnss
.configblocks
[2].flags
|= UBLOX_GNSS_ENABLE
; //Enable Galileo
2320 ubloxSendConfigMessage(&tx_buffer
, MSG_CFG_GNSS
, messageSize
, false);
2323 case CLSMSG(CLASS_ACK
, MSG_ACK_ACK
):
2324 if ((gpsData
.ackState
== UBLOX_ACK_WAITING
) && (ubxRcvMsgPayload
.ubxAck
.msgId
== gpsData
.ackWaitingMsgId
)) {
2325 gpsData
.ackState
= UBLOX_ACK_GOT_ACK
;
2328 case CLSMSG(CLASS_ACK
, MSG_ACK_NACK
):
2329 if ((gpsData
.ackState
== UBLOX_ACK_WAITING
) && (ubxRcvMsgPayload
.ubxAck
.msgId
== gpsData
.ackWaitingMsgId
)) {
2330 gpsData
.ackState
= UBLOX_ACK_GOT_NACK
;
2339 // we only return true when we get new position and speed data
2340 // this ensures we don't use stale data
2341 if (ubxHaveNewPosition
&& ubxHaveNewSpeed
) {
2342 ubxHaveNewSpeed
= ubxHaveNewPosition
= false;
2348 static bool gpsNewFrameUBLOX(uint8_t data
)
2350 bool newPositionDataReceived
= false;
2352 switch (ubxFrameParseState
) {
2353 case UBX_PARSE_PREAMBLE_SYNC_1
:
2354 if (PREAMBLE1
== data
) {
2355 // Might be a new UBX message, go on to look for next preamble byte.
2356 ubxFrameParseState
= UBX_PARSE_PREAMBLE_SYNC_2
;
2359 // Not a new UBX message, stay in this state for the next incoming byte.
2361 case UBX_PARSE_PREAMBLE_SYNC_2
:
2362 if (PREAMBLE2
== data
) {
2363 // Matches the two-byte preamble, seems to be a legit message, go on to process the rest of the message.
2364 ubxFrameParseState
= UBX_PARSE_MESSAGE_CLASS
;
2367 // False start, if this byte is not a preamble 1, restart new message parsing.
2368 // If this byte is a preamble 1, we might have gotten two in a row, so stay here and look for preamble 2 again.
2369 if (PREAMBLE1
!= data
) {
2370 ubxFrameParseState
= UBX_PARSE_PREAMBLE_SYNC_1
;
2373 case UBX_PARSE_MESSAGE_CLASS
:
2374 ubxRcvMsgChecksumB
= ubxRcvMsgChecksumA
= data
; // Reset & start the checksum A & B accumulators.
2375 ubxRcvMsgClass
= data
;
2376 ubxFrameParseState
= UBX_PARSE_MESSAGE_ID
;
2378 case UBX_PARSE_MESSAGE_ID
:
2379 ubxRcvMsgChecksumB
+= (ubxRcvMsgChecksumA
+= data
); // Accumulate both checksums.
2381 ubxFrameParseState
= UBX_PARSE_PAYLOAD_LENGTH_LSB
;
2383 case UBX_PARSE_PAYLOAD_LENGTH_LSB
:
2384 ubxRcvMsgChecksumB
+= (ubxRcvMsgChecksumA
+= data
);
2385 ubxRcvMsgPayloadLength
= data
; // Payload length LSB.
2386 ubxFrameParseState
= UBX_PARSE_PAYLOAD_LENGTH_MSB
;
2388 case UBX_PARSE_PAYLOAD_LENGTH_MSB
:
2389 ubxRcvMsgChecksumB
+= (ubxRcvMsgChecksumA
+= data
); // Accumulate both checksums.
2390 ubxRcvMsgPayloadLength
+= (uint16_t)(data
<< 8); //Payload length MSB.
2391 if (ubxRcvMsgPayloadLength
== 0) {
2392 // No payload for this message, skip to checksum checking.
2393 ubxFrameParseState
= UBX_PARSE_CHECKSUM_A
;
2396 if (ubxRcvMsgPayloadLength
> UBLOX_MAX_PAYLOAD_SANITY_SIZE
) {
2397 // Payload length is not reasonable, treat as a bad packet, restart new message parsing.
2398 // Note that we do not parse the rest of the message, better to leave it and look for a new message.
2399 #ifdef USE_DASHBOARD
2400 logErrorToPacketLog();
2402 if (PREAMBLE1
== data
) {
2403 // If this byte is a preamble 1 value, it might be a new message, so look for preamble 2 instead of starting over.
2404 ubxFrameParseState
= UBX_PARSE_PREAMBLE_SYNC_2
;
2406 ubxFrameParseState
= UBX_PARSE_PREAMBLE_SYNC_1
;
2410 // Payload length seems legit, go on to receive the payload content.
2411 ubxFrameParsePayloadCounter
= 0;
2412 ubxFrameParseState
= UBX_PARSE_PAYLOAD_CONTENT
;
2414 case UBX_PARSE_PAYLOAD_CONTENT
:
2415 ubxRcvMsgChecksumB
+= (ubxRcvMsgChecksumA
+= data
); // Accumulate both checksums.
2416 if (ubxFrameParsePayloadCounter
< UBLOX_PAYLOAD_SIZE
) {
2417 // Only add bytes to the buffer if we haven't reached the max supported payload size.
2418 // Note that we still read & checksum every byte so the checksum calculates correctly.
2419 ubxRcvMsgPayload
.rawBytes
[ubxFrameParsePayloadCounter
] = data
;
2421 if (++ubxFrameParsePayloadCounter
>= ubxRcvMsgPayloadLength
) {
2422 // All bytes for payload length processed.
2423 ubxFrameParseState
= UBX_PARSE_CHECKSUM_A
;
2426 // More payload content left, stay in this state.
2428 case UBX_PARSE_CHECKSUM_A
:
2429 if (ubxRcvMsgChecksumA
== data
) {
2430 // Checksum A matches, go on to checksum B.
2431 ubxFrameParseState
= UBX_PARSE_CHECKSUM_B
;
2434 // Bad checksum A, restart new message parsing.
2435 // Note that we do not parse checksum B, new message processing will handle skipping it if needed.
2436 #ifdef USE_DASHBOARD
2437 logErrorToPacketLog();
2439 if (PREAMBLE1
== data
) {
2440 // If this byte is a preamble 1 value, it might be a new message, so look for preamble 2 instead of starting over.
2441 ubxFrameParseState
= UBX_PARSE_PREAMBLE_SYNC_2
;
2443 ubxFrameParseState
= UBX_PARSE_PREAMBLE_SYNC_1
;
2446 case UBX_PARSE_CHECKSUM_B
:
2447 if (ubxRcvMsgChecksumB
== data
) {
2448 // Checksum B also matches, successfully received a new full packet!
2449 #ifdef USE_DASHBOARD
2450 dashboardGpsPacketCount
++; // Packet counter used by dashboard device.
2451 shiftPacketLog(); // Make space for message handling to add the message type char to the dashboard device packet log.
2453 // Handle the parsed message. Note this is a questionable inverted call dependency, but something for a later refactoring.
2454 newPositionDataReceived
= UBLOX_parse_gps(); // True only when we have new position data from the parsed message.
2455 ubxFrameParseState
= UBX_PARSE_PREAMBLE_SYNC_1
; // Restart new message parsing.
2458 // Bad checksum B, restart new message parsing.
2459 #ifdef USE_DASHBOARD
2460 logErrorToPacketLog();
2462 if (PREAMBLE1
== data
) {
2463 // If this byte is a preamble 1 value, it might be a new message, so look for preamble 2 instead of starting over.
2464 ubxFrameParseState
= UBX_PARSE_PREAMBLE_SYNC_2
;
2466 ubxFrameParseState
= UBX_PARSE_PREAMBLE_SYNC_1
;
2471 // Note this function returns if UBLOX_parse_gps() found new position data, NOT whether this function successfully parsed the frame or not.
2472 return newPositionDataReceived
;
2474 #endif // USE_GPS_UBLOX
2476 static void gpsHandlePassthrough(uint8_t data
)
2479 #ifdef USE_DASHBOARD
2480 if (featureIsEnabled(FEATURE_DASHBOARD
)) {
2481 // Should be handled via a generic callback hook, so the GPS module doesn't have to be coupled to the dashboard module.
2482 dashboardUpdate(micros());
2487 void gpsEnablePassthrough(serialPort_t
*gpsPassthroughPort
)
2489 waitForSerialPortToFinishTransmitting(gpsPort
);
2490 waitForSerialPortToFinishTransmitting(gpsPassthroughPort
);
2492 if (!(gpsPort
->mode
& MODE_TX
))
2493 serialSetMode(gpsPort
, gpsPort
->mode
| MODE_TX
);
2495 #ifdef USE_DASHBOARD
2496 if (featureIsEnabled(FEATURE_DASHBOARD
)) {
2497 // Should be handled via a generic callback hook, so the GPS module doesn't have to be coupled to the dashboard module.
2498 dashboardShowFixedPage(PAGE_GPS
);
2502 serialPassthrough(gpsPort
, gpsPassthroughPort
, &gpsHandlePassthrough
, NULL
);
2505 float GPS_scaleLonDown
= 1.0f
; // this is used to offset the shrinking longitude as we go towards the poles
2507 void GPS_calc_longitude_scaling(int32_t lat
)
2509 float rads
= (fabsf((float)lat
) / 10000000.0f
) * 0.0174532925f
;
2510 GPS_scaleLonDown
= cos_approx(rads
);
2513 ////////////////////////////////////////////////////////////////////////////////////
2514 // Calculate the distance flown from gps position data
2516 static void GPS_calculateDistanceFlown(bool initialize
)
2518 static int32_t lastCoord
[2] = { 0, 0 };
2519 static int32_t lastAlt
;
2522 GPS_distanceFlownInCm
= 0;
2524 if (STATE(GPS_FIX_HOME
) && ARMING_FLAG(ARMED
)) {
2525 uint16_t speed
= gpsConfig()->gps_use_3d_speed
? gpsSol
.speed3d
: gpsSol
.groundSpeed
;
2526 // Only add up movement when speed is faster than minimum threshold
2527 if (speed
> GPS_DISTANCE_FLOWN_MIN_SPEED_THRESHOLD_CM_S
) {
2530 GPS_distance_cm_bearing(&gpsSol
.llh
.lat
, &gpsSol
.llh
.lon
, &lastCoord
[GPS_LATITUDE
], &lastCoord
[GPS_LONGITUDE
], &dist
, &dir
);
2531 if (gpsConfig()->gps_use_3d_speed
) {
2532 dist
= sqrtf(sq(gpsSol
.llh
.altCm
- lastAlt
) + sq(dist
));
2534 GPS_distanceFlownInCm
+= dist
;
2538 lastCoord
[GPS_LONGITUDE
] = gpsSol
.llh
.lon
;
2539 lastCoord
[GPS_LATITUDE
] = gpsSol
.llh
.lat
;
2540 lastAlt
= gpsSol
.llh
.altCm
;
2543 void GPS_reset_home_position(void)
2544 // runs, if GPS is defined, on arming via tryArm() in core.c, and on gyro cal via processRcStickPositions() in rc_controls.c
2546 if (!STATE(GPS_FIX_HOME
) || !gpsConfig()->gps_set_home_point_once
) {
2547 if (STATE(GPS_FIX
) && gpsSol
.numSat
>= gpsRescueConfig()->minSats
) {
2548 // those checks are always true for tryArm, but may not be true for gyro cal
2549 GPS_home
[GPS_LATITUDE
] = gpsSol
.llh
.lat
;
2550 GPS_home
[GPS_LONGITUDE
] = gpsSol
.llh
.lon
;
2551 GPS_calc_longitude_scaling(gpsSol
.llh
.lat
);
2552 ENABLE_STATE(GPS_FIX_HOME
);
2553 // no point beeping success here since:
2554 // when triggered by tryArm, the arming beep is modified to indicate the GPS home fix status on arming, and
2555 // when triggered by gyro cal, the gyro cal beep takes priority over the GPS beep, so we won't hear the GPS beep
2556 // PS: to test for gyro cal, check for !ARMED, since we cannot be here while disarmed other than via gyro cal
2560 #ifdef USE_GPS_UBLOX
2561 // disable Sat Info requests on arming
2562 if (gpsConfig()->provider
== GPS_UBLOX
) {
2563 setSatInfoMessageRate(0);
2566 GPS_calculateDistanceFlown(true); // Initialize
2569 ////////////////////////////////////////////////////////////////////////////////////
2570 #define DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR_IN_HUNDREDS_OF_KILOMETERS 1.113195f
2571 #define TAN_89_99_DEGREES 5729.57795f
2572 // Get distance between two points in cm
2573 // Get bearing from pos1 to pos2, returns an 1deg = 100 precision
2574 void GPS_distance_cm_bearing(int32_t *currentLat1
, int32_t *currentLon1
, int32_t *destinationLat2
, int32_t *destinationLon2
, uint32_t *dist
, int32_t *bearing
)
2576 float dLat
= *destinationLat2
- *currentLat1
; // difference of latitude in 1/10 000 000 degrees
2577 float dLon
= (float)(*destinationLon2
- *currentLon1
) * GPS_scaleLonDown
;
2578 *dist
= sqrtf(sq(dLat
) + sq(dLon
)) * DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR_IN_HUNDREDS_OF_KILOMETERS
;
2580 *bearing
= 9000.0f
+ atan2_approx(-dLat
, dLon
) * TAN_89_99_DEGREES
; // Convert the output radians to 100xdeg
2585 void GPS_calculateDistanceAndDirectionToHome(void)
2587 if (STATE(GPS_FIX_HOME
)) {
2590 GPS_distance_cm_bearing(&gpsSol
.llh
.lat
, &gpsSol
.llh
.lon
, &GPS_home
[GPS_LATITUDE
], &GPS_home
[GPS_LONGITUDE
], &dist
, &dir
);
2591 GPS_distanceToHome
= dist
/ 100; // m
2592 GPS_distanceToHomeCm
= dist
; // cm
2593 GPS_directionToHome
= dir
/ 10; // degrees * 10 or decidegrees
2595 // If we don't have home set, do not display anything
2596 GPS_distanceToHome
= 0;
2597 GPS_distanceToHomeCm
= 0;
2598 GPS_directionToHome
= 0;
2602 void onGpsNewData(void)
2604 if (!STATE(GPS_FIX
)) {
2605 // if we don't have a 3D fix don't give data to GPS rescue
2609 gpsDataIntervalSeconds
= gpsSol
.navIntervalMs
/ 1000.0f
;
2611 GPS_calculateDistanceAndDirectionToHome();
2612 if (ARMING_FLAG(ARMED
)) {
2613 GPS_calculateDistanceFlown(false);
2616 #ifdef USE_GPS_RESCUE
2617 gpsRescueNewGpsData();
2619 #ifdef USE_GPS_LAP_TIMER
2620 gpsLapTimerNewGpsData();
2621 #endif // USE_GPS_LAP_TIMER
2624 void gpsSetFixState(bool state
)
2627 ENABLE_STATE(GPS_FIX
);
2628 ENABLE_STATE(GPS_FIX_EVER
);
2630 DISABLE_STATE(GPS_FIX
);
2634 float getGpsDataIntervalSeconds(void)
2636 return gpsDataIntervalSeconds
;
2639 baudRate_e
getGpsPortActualBaudRateIndex(void)
2641 return lookupBaudRateIndex(serialGetBaudRate(gpsPort
));