Skip to content

Commit bb7f3ba

Browse files
authored
Merge pull request #355 from sparkfun/KeyedPairs
Configure module using keys
2 parents bf8ac32 + 48ea1ee commit bb7f3ba

16 files changed

+464
-800
lines changed

Firmware/RTK_Surveyor/Base.ino

Lines changed: 87 additions & 80 deletions
Original file line numberDiff line numberDiff line change
@@ -3,9 +3,6 @@ bool configureUbloxModuleBase()
33
{
44
if (online.gnss == false) return (false);
55

6-
bool response = true;
7-
int maxWait = 2000;
8-
96
//If our settings haven't changed, and this is first config since power on, trust ZED's settings
107
if (settings.updateZEDSettings == false && firstPowerOn == true)
118
{
@@ -18,76 +15,73 @@ bool configureUbloxModuleBase()
1815

1916
i2cGNSS.checkUblox(); //Regularly poll to get latest data and any RTCM
2017

21-
const int baseNavigationFrequency = 1;
22-
23-
//In Base mode we force 1Hz
24-
if (i2cGNSS.getNavigationFrequency(maxWait) != baseNavigationFrequency)
25-
response &= i2cGNSS.setNavigationFrequency(baseNavigationFrequency, maxWait);
26-
if (response == false)
27-
Serial.println("setNavigationFrequency failed");
18+
i2cGNSS.setNMEAGPGGAcallbackPtr(NULL); // Disable GPGGA call back that may have been set during Rover NTRIP Client mode
2819

29-
i2cGNSS.checkUblox(); //Regularly poll to get latest data and any RTCM
20+
bool response = true;
3021

31-
i2cGNSS.setNMEAGPGGAcallbackPtr(NULL); // Disable GPGGA call back that may have been set during Rover NTRIP Client mode
32-
i2cGNSS.disableNMEAMessage(UBX_NMEA_GGA, COM_PORT_I2C); // Disable NMEA message that may have been set during Rover NTRIP Client mode
22+
//In Base mode we force 1Hz
23+
response &= i2cGNSS.newCfgValset16(UBLOX_CFG_RATE_MEAS, 1000);
24+
response &= i2cGNSS.addCfgValset16(UBLOX_CFG_RATE_NAV, 1);
3325

34-
response = i2cGNSS.setSurveyMode(0, 0, 0); //Disable Survey-In or Fixed Mode
35-
if (response == false)
36-
Serial.println("Disable TMODE3 failed");
26+
//Since we are at 1Hz, allow GSV NMEA to be reported at whatever the user has chosen
27+
response &= i2cGNSS.addCfgValset8(settings.ubxMessages[8].msgConfigKey, settings.ubxMessages[8].msgRate); //Update rate on module
3728

38-
// Set dynamic model
39-
if (i2cGNSS.getDynamicModel(maxWait) != DYN_MODEL_STATIONARY)
40-
{
41-
response &= i2cGNSS.setDynamicModel(DYN_MODEL_STATIONARY, maxWait);
42-
if (response == false)
43-
{
44-
Serial.println("setDynamicModel failed");
45-
return (false);
46-
}
47-
}
29+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_NMEA_ID_GGA_I2C, 0); // Disable NMEA message that may have been set during Rover NTRIP Client mode
4830

49-
#define OUTPUT_SETTING 14
31+
//Survey mode is only available on ZED-F9P modules
32+
if (zedModuleType == PLATFORM_F9P)
33+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_MODE, 0); //Disable survey-in mode
5034

51-
//Turn on RTCM so that we can harvest RTCM over I2C and send out over WiFi
52-
//This is easier than parsing over UART because the library handles the frame detection
53-
getPortSettings(COM_PORT_I2C); //Load the settingPayload with this port's settings
54-
if (settingPayload[OUTPUT_SETTING] != (COM_TYPE_UBX | COM_TYPE_NMEA | COM_TYPE_RTCM3))
55-
response &= i2cGNSS.setPortOutput(COM_PORT_I2C, COM_TYPE_UBX | COM_TYPE_NMEA | COM_TYPE_RTCM3); //Set the I2C port to output UBX (config), and RTCM3 (casting)
56-
//response &= i2cGNSS.setPortOutput(COM_PORT_I2C, COM_TYPE_UBX | COM_TYPE_RTCM3); //Not a valid state. Goes to UBX+NMEA+RTCM3
35+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_NAVSPG_DYNMODEL, (dynModel)settings.dynamicModel); // Set dynamic model
5736

58-
//In base mode the Surveyor should output RTCM over all ports:
37+
//In base mode the RTK device should output RTCM over all ports:
5938
//(Primary) UART2 in case the Surveyor is connected via radio to rover
6039
//(Optional) I2C in case user wants base to connect to WiFi and NTRIP Caster
6140
//(Seconday) USB in case the Surveyor is used as an NTRIP caster connected to SBC or other
6241
//(Tertiary) UART1 in case Surveyor is sending RTCM to phone that is then NTRIP Caster
63-
response &= enableRTCMSentences(COM_PORT_UART2);
64-
response &= enableRTCMSentences(COM_PORT_UART1);
65-
response &= enableRTCMSentences(COM_PORT_USB);
66-
response &= enableRTCMSentences(COM_PORT_I2C); //Enable for plain radio so we can count RTCM packets for display
67-
68-
//If enabled, adjust GSV NMEA to be reported at 1Hz
69-
if (settings.ubxMessages[8].msgRate > baseNavigationFrequency)
70-
setMessageRateByName("UBX_NMEA_GSV", baseNavigationFrequency); //Update GSV setting in file
71-
72-
response &= configureGNSSMessageRates(COM_PORT_UART1, settings.ubxMessages); //In the interest of logging, make sure the appropriate messages are enabled
42+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1005_I2C, 1);
43+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1074_I2C, 1);
44+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1084_I2C, 1);
45+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1094_I2C, 1);
46+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1124_I2C, 1);
47+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1230_I2C, 1);
48+
49+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1005_USB, 1);
50+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1074_USB, 1);
51+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1084_USB, 1);
52+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1094_USB, 1);
53+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1124_USB, 1);
54+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1230_USB, 1);
55+
56+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1005_UART1, 1);
57+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1074_UART1, 1);
58+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1084_UART1, 1);
59+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1094_UART1, 1);
60+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1124_UART1, 1);
61+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1230_UART1, 1);
62+
63+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1005_UART2, 1);
64+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1074_UART2, 1);
65+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1084_UART2, 1);
66+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1094_UART2, 1);
67+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1124_UART2, 1);
68+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1230_UART2, 1);
69+
70+
response &= i2cGNSS.sendCfgValset8(UBLOX_CFG_MSGOUT_NMEA_ID_VTG_SPI, 0); //Dummy closing value - #31
7371

7472
if (response == false)
75-
{
76-
Serial.println("RTCM settings failed to enable");
77-
return (false);
78-
}
79-
80-
response &= i2cGNSS.saveConfiguration(); //Save the current settings to flash and BBR
81-
if (response == false)
82-
Serial.println("Module failed to save.");
73+
Serial.println("Base config fail");
8374

8475
return (response);
8576
}
8677

8778
//Start survey
8879
//The ZED-F9P is slightly different than the NEO-M8P. See the Integration manual 3.5.8 for more info.
89-
bool beginSurveyIn()
80+
bool surveyInStart()
9081
{
82+
i2cGNSS.setVal8(UBLOX_CFG_TMODE_MODE, 0); //Disable survey-in mode
83+
delay(100);
84+
9185
bool needSurveyReset = false;
9286
if (i2cGNSS.getSurveyInActive(100) == true) needSurveyReset = true;
9387
if (i2cGNSS.getSurveyInValid(100) == true) needSurveyReset = true;
@@ -96,17 +90,19 @@ bool beginSurveyIn()
9690
{
9791
Serial.println("Resetting survey");
9892

99-
if (resetSurvey() == false)
93+
if (surveyInReset() == false)
10094
{
10195
Serial.println("Survey reset failed");
102-
if (resetSurvey() == false)
103-
{
96+
if (surveyInReset() == false)
10497
Serial.println("Survey reset failed - 2nd attempt");
105-
}
10698
}
10799
}
108100

109-
bool response = i2cGNSS.enableSurveyMode(settings.observationSeconds, settings.observationPositionAccuracy, 5000); //Enable Survey in, with user parameters. Wait up to 5s.
101+
bool response = true;
102+
response &= i2cGNSS.setVal8(UBLOX_CFG_TMODE_MODE, 1); //Survey-in enable
103+
response &= i2cGNSS.setVal32(UBLOX_CFG_TMODE_SVIN_ACC_LIMIT, settings.observationPositionAccuracy * 10000);
104+
response &= i2cGNSS.setVal32(UBLOX_CFG_TMODE_SVIN_MIN_DUR, settings.observationSeconds);
105+
110106
if (response == false)
111107
{
112108
Serial.println("Survey start failed");
@@ -130,16 +126,23 @@ bool beginSurveyIn()
130126
return (true);
131127
}
132128

133-
bool resetSurvey()
129+
//Slightly modified method for restarting survey-in from: https://portal.u-blox.com/s/question/0D52p00009IsVoMCAV/restarting-surveyin-on-an-f9p
130+
bool surveyInReset()
134131
{
135-
int maxWait = 2000;
132+
bool response = true;
136133

137-
//Slightly modified method for restarting survey-in from: https://portal.u-blox.com/s/question/0D52p00009IsVoMCAV/restarting-surveyin-on-an-f9p
138-
bool response = i2cGNSS.setSurveyMode(maxWait, 0, 0); //Disable Survey-In or Fixed Mode
134+
//Disable survey-in mode
135+
response &= i2cGNSS.setVal8(UBLOX_CFG_TMODE_MODE, 0);
139136
delay(1000);
140-
response &= i2cGNSS.enableSurveyMode(1000, 400.000, maxWait); //Enable Survey in with bogus values
137+
138+
//Enable Survey in with bogus values
139+
response &= i2cGNSS.newCfgValset8(UBLOX_CFG_TMODE_MODE, 1); //Survey-in enable
140+
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_SVIN_ACC_LIMIT, 40 * 10000); //40.0m
141+
response &= i2cGNSS.sendCfgValset32(UBLOX_CFG_TMODE_SVIN_MIN_DUR, 1000); //1000s
141142
delay(1000);
142-
response &= i2cGNSS.setSurveyMode(maxWait, 0, 0); //Disable Survey-In or Fixed Mode
143+
144+
//Disable survey-in mode
145+
response &= i2cGNSS.setVal8(UBLOX_CFG_TMODE_MODE, 0);
143146

144147
if (response == false)
145148
return (response);
@@ -159,8 +162,7 @@ bool resetSurvey()
159162
//Start the base using fixed coordinates
160163
bool startFixedBase()
161164
{
162-
bool response = false;
163-
int maxWait = 2000;
165+
bool response = true;
164166

165167
if (settings.fixedBaseCoordinateType == COORD_TYPE_ECEF)
166168
{
@@ -179,20 +181,23 @@ bool startFixedBase()
179181

180182
//Units are cm with a high precision extension so -1234.5678 should be called: (-123456, -78)
181183
//-1280208.308,-4716803.847,4086665.811 is SparkFun HQ so...
182-
response = i2cGNSS.setStaticPosition(majorEcefX, minorEcefX,
183-
majorEcefY, minorEcefY,
184-
majorEcefZ, minorEcefZ,
185-
false,
186-
maxWait
187-
); //With high precision 0.1mm parts
184+
185+
response &= i2cGNSS.newCfgValset8(UBLOX_CFG_TMODE_MODE, 2); //Fixed
186+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_POS_TYPE, 0); //Position in ECEF
187+
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_ECEF_X, majorEcefX);
188+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_ECEF_X_HP, minorEcefX);
189+
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_ECEF_Y, majorEcefY);
190+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_ECEF_Y_HP, minorEcefY);
191+
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_ECEF_Z, majorEcefZ);
192+
response &= i2cGNSS.sendCfgValset8(UBLOX_CFG_TMODE_ECEF_Z_HP, minorEcefZ);
188193
}
189194
else if (settings.fixedBaseCoordinateType == COORD_TYPE_GEODETIC)
190195
{
191196
//Add height of instrument (HI) to fixed altitude
192197
//https://www.e-education.psu.edu/geog862/node/1853
193198
//For example, if HAE is at 100.0m, + 2m stick + 73mm ARP = 102.073
194199
float totalFixedAltitude = settings.fixedAltitude + (settings.antennaHeight / 1000.0) + (settings.antennaReferencePoint / 1000.0);
195-
200+
196201
//Break coordinates into main and high precision parts
197202
//The type casting should not effect rounding of original double cast coordinate
198203
int64_t majorLat = settings.fixedLat * 10000000;
@@ -214,12 +219,14 @@ bool startFixedBase()
214219
// Serial.printf("major (should be 156022): %ld\r\n", majorAlt);
215220
// Serial.printf("minor (should be 84): %ld\r\n", minorAlt);
216221

217-
response = i2cGNSS.setStaticPosition(
218-
majorLat, minorLat,
219-
majorLong, minorLong,
220-
majorAlt, minorAlt,
221-
true, //Use lat/long as input
222-
maxWait);
222+
response &= i2cGNSS.newCfgValset8(UBLOX_CFG_TMODE_MODE, 2); //Fixed
223+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_POS_TYPE, 1); //Position in LLH
224+
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_LAT, majorLat);
225+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_LAT_HP, minorLat);
226+
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_LON, majorLong);
227+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_LON_HP, minorLong);
228+
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_HEIGHT, majorAlt);
229+
response &= i2cGNSS.sendCfgValset8(UBLOX_CFG_TMODE_HEIGHT_HP, minorAlt);
223230
}
224231

225232
return (response);
@@ -251,7 +258,7 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming)
251258
{
252259
rtcmLastReceived = millis();
253260
rtcmBytesSent++;
254-
261+
255262
ntripServerProcessRTCM(incoming);
256263

257264
espnowProcessRTCM(incoming);

Firmware/RTK_Surveyor/Begin.ino

Lines changed: 15 additions & 80 deletions
Original file line numberDiff line numberDiff line change
@@ -336,7 +336,7 @@ void beginUART2()
336336
//Allows more time between when the UART interrupt occurs and when the FIFO buffer overruns
337337
//serialGNSS.setRxFIFOFull(50); //Available in >v2.0.5
338338
uart_set_rx_full_threshold(2, 50); //uart_num, threshold
339-
339+
340340
// if (pinUART2TaskHandle == NULL) xTaskCreatePinnedToCore(
341341
// pinUART2Task,
342342
// "UARTStart", //Just for humans
@@ -367,65 +367,6 @@ void pinUART2Task( void *pvParameters )
367367
vTaskDelete( NULL ); //Delete task once it has run once
368368
}
369369

370-
//Serial Read/Write tasks for the F9P must be started after BT is up and running otherwise SerialBT->available will cause reboot
371-
void startUART2Tasks()
372-
{
373-
//Reads data from ZED and stores data into circular buffer
374-
if (F9PSerialReadTaskHandle == NULL)
375-
xTaskCreate(
376-
F9PSerialReadTask, //Function to call
377-
"F9Read", //Just for humans
378-
readTaskStackSize, //Stack Size
379-
NULL, //Task input parameter
380-
F9PSerialReadTaskPriority, //Priority
381-
&F9PSerialReadTaskHandle); //Task handle
382-
383-
//Reads data from circular buffer and sends data to SD, SPP, or TCP
384-
if (handleGNSSDataTaskHandle == NULL)
385-
xTaskCreate(
386-
handleGNSSDataTask, //Function to call
387-
"handleGNSSData", //Just for humans
388-
handleGNSSDataTaskStackSize, //Stack Size
389-
NULL, //Task input parameter
390-
handleGNSSDataTaskPriority, //Priority
391-
&handleGNSSDataTaskHandle); //Task handle
392-
393-
//Reads data from BT and sends to ZED
394-
if (F9PSerialWriteTaskHandle == NULL)
395-
xTaskCreate(
396-
F9PSerialWriteTask, //Function to call
397-
"F9Write", //Just for humans
398-
writeTaskStackSize, //Stack Size
399-
NULL, //Task input parameter
400-
F9PSerialWriteTaskPriority, //Priority
401-
&F9PSerialWriteTaskHandle); //Task handle
402-
}
403-
404-
//Stop tasks - useful when running firmware update or WiFi AP is running
405-
void stopUART2Tasks()
406-
{
407-
//Delete tasks if running
408-
if (F9PSerialReadTaskHandle != NULL)
409-
{
410-
vTaskDelete(F9PSerialReadTaskHandle);
411-
F9PSerialReadTaskHandle = NULL;
412-
}
413-
if (handleGNSSDataTaskHandle != NULL)
414-
{
415-
vTaskDelete(handleGNSSDataTaskHandle);
416-
handleGNSSDataTaskHandle = NULL;
417-
}
418-
if (F9PSerialWriteTaskHandle != NULL)
419-
{
420-
vTaskDelete(F9PSerialWriteTaskHandle);
421-
F9PSerialWriteTaskHandle = NULL;
422-
}
423-
424-
//Give the other CPU time to finish
425-
//Eliminates CPU bus hang condition
426-
delay(100);
427-
}
428-
429370
void beginFS()
430371
{
431372
if (online.fs == false)
@@ -712,39 +653,33 @@ bool beginExternalTriggers()
712653
return (true);
713654
}
714655

715-
UBX_CFG_TP5_data_t timePulseParameters;
656+
if (settings.dataPortChannel != MUX_PPS_EVENTTRIGGER)
657+
return (true); //No need to configure PPS if port is not selected
716658

717-
if (i2cGNSS.getTimePulseParameters(&timePulseParameters) == false)
718-
log_e("getTimePulseParameters failed!");
659+
bool response = true;
719660

720-
timePulseParameters.tpIdx = 0; // Select the TIMEPULSE pin
661+
response &= i2cGNSS.newCfgValset8(UBLOX_CFG_TP_USE_LOCKED_TP1, 1); //Use CFG-TP-PERIOD_LOCK_TP1 and CFG-TP-LEN_LOCK_TP1 as soon as GNSS time is valid
662+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TP_TP1_ENA, settings.enableExternalPulse); //Enable/disable timepulse
663+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TP_PULSE_DEF, 0); //Time pulse definition is a period (in us)
664+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TP_PULSE_LENGTH_DEF, 1); //Define timepulse by length (not ratio)
665+
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TP_POL_TP1, settings.externalPulsePolarity); //0 = falling, 1 = raising edge
721666

722667
// While the module is _locking_ to GNSS time, turn off pulse
723-
timePulseParameters.freqPeriod = 1000000; //Set the period between pulses in us
724-
timePulseParameters.pulseLenRatio = 0; //Set the pulse length in us
668+
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TP_PERIOD_TP1, 1000000); //Set the period between pulses in us
669+
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TP_LEN_TP1, 0); //Set the pulse length in us
725670

726671
// When the module is _locked_ to GNSS time, make it generate 1kHz
727-
timePulseParameters.freqPeriodLock = settings.externalPulseTimeBetweenPulse_us; //Set the period between pulses is us
728-
timePulseParameters.pulseLenRatioLock = settings.externalPulseLength_us; //Set the pulse length in us
729-
730-
timePulseParameters.flags.bits.active = settings.enableExternalPulse; //Make sure the active flag is set to enable the time pulse. (Set to 0 to disable.)
731-
timePulseParameters.flags.bits.lockedOtherSet = 1; //Tell the module to use freqPeriod while locking and freqPeriodLock when locked to GNSS time
732-
timePulseParameters.flags.bits.isFreq = 0; //Tell the module that we want to set the period
733-
timePulseParameters.flags.bits.isLength = 1; //Tell the module that pulseLenRatio is a length (in us)
734-
timePulseParameters.flags.bits.polarity = (uint8_t)settings.externalPulsePolarity; //Rising or failling edge type pulse
672+
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TP_PERIOD_LOCK_TP1, settings.externalPulseTimeBetweenPulse_us); //Set the period between pulses is us
673+
response &= i2cGNSS.sendCfgValset32(UBLOX_CFG_TP_LEN_LOCK_TP1, settings.externalPulseLength_us); //Set the pulse length in us
735674

736-
if (i2cGNSS.setTimePulseParameters(&timePulseParameters, 1000) == false)
737-
log_e("setTimePulseParameters failed!");
675+
if (response == false)
676+
Serial.println("beginExternalTriggers config failed");
738677

739678
if (settings.enableExternalHardwareEventLogging == true)
740679
i2cGNSS.setAutoTIMTM2callback(&eventTriggerReceived); //Enable automatic TIM TM2 messages with callback to eventTriggerReceived
741680
else
742681
i2cGNSS.setAutoTIMTM2callback(NULL);
743682

744-
bool response = i2cGNSS.saveConfiguration(); //Save the current settings to flash and BBR
745-
if (response == false)
746-
Serial.println("Module failed to save.");
747-
748683
return (response);
749684
}
750685

0 commit comments

Comments
 (0)