Skip to content

Configure module using keys #355

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 3 commits into from
Oct 28, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
167 changes: 87 additions & 80 deletions Firmware/RTK_Surveyor/Base.ino
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,6 @@ bool configureUbloxModuleBase()
{
if (online.gnss == false) return (false);

bool response = true;
int maxWait = 2000;

//If our settings haven't changed, and this is first config since power on, trust ZED's settings
if (settings.updateZEDSettings == false && firstPowerOn == true)
{
Expand All @@ -18,76 +15,73 @@ bool configureUbloxModuleBase()

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

const int baseNavigationFrequency = 1;

//In Base mode we force 1Hz
if (i2cGNSS.getNavigationFrequency(maxWait) != baseNavigationFrequency)
response &= i2cGNSS.setNavigationFrequency(baseNavigationFrequency, maxWait);
if (response == false)
Serial.println("setNavigationFrequency failed");
i2cGNSS.setNMEAGPGGAcallbackPtr(NULL); // Disable GPGGA call back that may have been set during Rover NTRIP Client mode

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

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

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

// Set dynamic model
if (i2cGNSS.getDynamicModel(maxWait) != DYN_MODEL_STATIONARY)
{
response &= i2cGNSS.setDynamicModel(DYN_MODEL_STATIONARY, maxWait);
if (response == false)
{
Serial.println("setDynamicModel failed");
return (false);
}
}
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_NMEA_ID_GGA_I2C, 0); // Disable NMEA message that may have been set during Rover NTRIP Client mode

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

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

//In base mode the Surveyor should output RTCM over all ports:
//In base mode the RTK device should output RTCM over all ports:
//(Primary) UART2 in case the Surveyor is connected via radio to rover
//(Optional) I2C in case user wants base to connect to WiFi and NTRIP Caster
//(Seconday) USB in case the Surveyor is used as an NTRIP caster connected to SBC or other
//(Tertiary) UART1 in case Surveyor is sending RTCM to phone that is then NTRIP Caster
response &= enableRTCMSentences(COM_PORT_UART2);
response &= enableRTCMSentences(COM_PORT_UART1);
response &= enableRTCMSentences(COM_PORT_USB);
response &= enableRTCMSentences(COM_PORT_I2C); //Enable for plain radio so we can count RTCM packets for display

//If enabled, adjust GSV NMEA to be reported at 1Hz
if (settings.ubxMessages[8].msgRate > baseNavigationFrequency)
setMessageRateByName("UBX_NMEA_GSV", baseNavigationFrequency); //Update GSV setting in file

response &= configureGNSSMessageRates(COM_PORT_UART1, settings.ubxMessages); //In the interest of logging, make sure the appropriate messages are enabled
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1005_I2C, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1074_I2C, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1084_I2C, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1094_I2C, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1124_I2C, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1230_I2C, 1);

response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1005_USB, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1074_USB, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1084_USB, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1094_USB, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1124_USB, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1230_USB, 1);

response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1005_UART1, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1074_UART1, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1084_UART1, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1094_UART1, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1124_UART1, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1230_UART1, 1);

response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1005_UART2, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1074_UART2, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1084_UART2, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1094_UART2, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1124_UART2, 1);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1230_UART2, 1);

response &= i2cGNSS.sendCfgValset8(UBLOX_CFG_MSGOUT_NMEA_ID_VTG_SPI, 0); //Dummy closing value - #31

if (response == false)
{
Serial.println("RTCM settings failed to enable");
return (false);
}

response &= i2cGNSS.saveConfiguration(); //Save the current settings to flash and BBR
if (response == false)
Serial.println("Module failed to save.");
Serial.println("Base config fail");

return (response);
}

//Start survey
//The ZED-F9P is slightly different than the NEO-M8P. See the Integration manual 3.5.8 for more info.
bool beginSurveyIn()
bool surveyInStart()
{
i2cGNSS.setVal8(UBLOX_CFG_TMODE_MODE, 0); //Disable survey-in mode
delay(100);

bool needSurveyReset = false;
if (i2cGNSS.getSurveyInActive(100) == true) needSurveyReset = true;
if (i2cGNSS.getSurveyInValid(100) == true) needSurveyReset = true;
Expand All @@ -96,17 +90,19 @@ bool beginSurveyIn()
{
Serial.println("Resetting survey");

if (resetSurvey() == false)
if (surveyInReset() == false)
{
Serial.println("Survey reset failed");
if (resetSurvey() == false)
{
if (surveyInReset() == false)
Serial.println("Survey reset failed - 2nd attempt");
}
}
}

bool response = i2cGNSS.enableSurveyMode(settings.observationSeconds, settings.observationPositionAccuracy, 5000); //Enable Survey in, with user parameters. Wait up to 5s.
bool response = true;
response &= i2cGNSS.setVal8(UBLOX_CFG_TMODE_MODE, 1); //Survey-in enable
response &= i2cGNSS.setVal32(UBLOX_CFG_TMODE_SVIN_ACC_LIMIT, settings.observationPositionAccuracy * 10000);
response &= i2cGNSS.setVal32(UBLOX_CFG_TMODE_SVIN_MIN_DUR, settings.observationSeconds);

if (response == false)
{
Serial.println("Survey start failed");
Expand All @@ -130,16 +126,23 @@ bool beginSurveyIn()
return (true);
}

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

//Slightly modified method for restarting survey-in from: https://portal.u-blox.com/s/question/0D52p00009IsVoMCAV/restarting-surveyin-on-an-f9p
bool response = i2cGNSS.setSurveyMode(maxWait, 0, 0); //Disable Survey-In or Fixed Mode
//Disable survey-in mode
response &= i2cGNSS.setVal8(UBLOX_CFG_TMODE_MODE, 0);
delay(1000);
response &= i2cGNSS.enableSurveyMode(1000, 400.000, maxWait); //Enable Survey in with bogus values

//Enable Survey in with bogus values
response &= i2cGNSS.newCfgValset8(UBLOX_CFG_TMODE_MODE, 1); //Survey-in enable
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_SVIN_ACC_LIMIT, 40 * 10000); //40.0m
response &= i2cGNSS.sendCfgValset32(UBLOX_CFG_TMODE_SVIN_MIN_DUR, 1000); //1000s
delay(1000);
response &= i2cGNSS.setSurveyMode(maxWait, 0, 0); //Disable Survey-In or Fixed Mode

//Disable survey-in mode
response &= i2cGNSS.setVal8(UBLOX_CFG_TMODE_MODE, 0);

if (response == false)
return (response);
Expand All @@ -159,8 +162,7 @@ bool resetSurvey()
//Start the base using fixed coordinates
bool startFixedBase()
{
bool response = false;
int maxWait = 2000;
bool response = true;

if (settings.fixedBaseCoordinateType == COORD_TYPE_ECEF)
{
Expand All @@ -179,20 +181,23 @@ bool startFixedBase()

//Units are cm with a high precision extension so -1234.5678 should be called: (-123456, -78)
//-1280208.308,-4716803.847,4086665.811 is SparkFun HQ so...
response = i2cGNSS.setStaticPosition(majorEcefX, minorEcefX,
majorEcefY, minorEcefY,
majorEcefZ, minorEcefZ,
false,
maxWait
); //With high precision 0.1mm parts

response &= i2cGNSS.newCfgValset8(UBLOX_CFG_TMODE_MODE, 2); //Fixed
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_POS_TYPE, 0); //Position in ECEF
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_ECEF_X, majorEcefX);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_ECEF_X_HP, minorEcefX);
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_ECEF_Y, majorEcefY);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_ECEF_Y_HP, minorEcefY);
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_ECEF_Z, majorEcefZ);
response &= i2cGNSS.sendCfgValset8(UBLOX_CFG_TMODE_ECEF_Z_HP, minorEcefZ);
}
else if (settings.fixedBaseCoordinateType == COORD_TYPE_GEODETIC)
{
//Add height of instrument (HI) to fixed altitude
//https://www.e-education.psu.edu/geog862/node/1853
//For example, if HAE is at 100.0m, + 2m stick + 73mm ARP = 102.073
float totalFixedAltitude = settings.fixedAltitude + (settings.antennaHeight / 1000.0) + (settings.antennaReferencePoint / 1000.0);

//Break coordinates into main and high precision parts
//The type casting should not effect rounding of original double cast coordinate
int64_t majorLat = settings.fixedLat * 10000000;
Expand All @@ -214,12 +219,14 @@ bool startFixedBase()
// Serial.printf("major (should be 156022): %ld\r\n", majorAlt);
// Serial.printf("minor (should be 84): %ld\r\n", minorAlt);

response = i2cGNSS.setStaticPosition(
majorLat, minorLat,
majorLong, minorLong,
majorAlt, minorAlt,
true, //Use lat/long as input
maxWait);
response &= i2cGNSS.newCfgValset8(UBLOX_CFG_TMODE_MODE, 2); //Fixed
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_POS_TYPE, 1); //Position in LLH
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_LAT, majorLat);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_LAT_HP, minorLat);
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_LON, majorLong);
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TMODE_LON_HP, minorLong);
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TMODE_HEIGHT, majorAlt);
response &= i2cGNSS.sendCfgValset8(UBLOX_CFG_TMODE_HEIGHT_HP, minorAlt);
}

return (response);
Expand Down Expand Up @@ -251,7 +258,7 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming)
{
rtcmLastReceived = millis();
rtcmBytesSent++;

ntripServerProcessRTCM(incoming);

espnowProcessRTCM(incoming);
Expand Down
95 changes: 15 additions & 80 deletions Firmware/RTK_Surveyor/Begin.ino
Original file line number Diff line number Diff line change
Expand Up @@ -336,7 +336,7 @@ void beginUART2()
//Allows more time between when the UART interrupt occurs and when the FIFO buffer overruns
//serialGNSS.setRxFIFOFull(50); //Available in >v2.0.5
uart_set_rx_full_threshold(2, 50); //uart_num, threshold

// if (pinUART2TaskHandle == NULL) xTaskCreatePinnedToCore(
// pinUART2Task,
// "UARTStart", //Just for humans
Expand Down Expand Up @@ -367,65 +367,6 @@ void pinUART2Task( void *pvParameters )
vTaskDelete( NULL ); //Delete task once it has run once
}

//Serial Read/Write tasks for the F9P must be started after BT is up and running otherwise SerialBT->available will cause reboot
void startUART2Tasks()
{
//Reads data from ZED and stores data into circular buffer
if (F9PSerialReadTaskHandle == NULL)
xTaskCreate(
F9PSerialReadTask, //Function to call
"F9Read", //Just for humans
readTaskStackSize, //Stack Size
NULL, //Task input parameter
F9PSerialReadTaskPriority, //Priority
&F9PSerialReadTaskHandle); //Task handle

//Reads data from circular buffer and sends data to SD, SPP, or TCP
if (handleGNSSDataTaskHandle == NULL)
xTaskCreate(
handleGNSSDataTask, //Function to call
"handleGNSSData", //Just for humans
handleGNSSDataTaskStackSize, //Stack Size
NULL, //Task input parameter
handleGNSSDataTaskPriority, //Priority
&handleGNSSDataTaskHandle); //Task handle

//Reads data from BT and sends to ZED
if (F9PSerialWriteTaskHandle == NULL)
xTaskCreate(
F9PSerialWriteTask, //Function to call
"F9Write", //Just for humans
writeTaskStackSize, //Stack Size
NULL, //Task input parameter
F9PSerialWriteTaskPriority, //Priority
&F9PSerialWriteTaskHandle); //Task handle
}

//Stop tasks - useful when running firmware update or WiFi AP is running
void stopUART2Tasks()
{
//Delete tasks if running
if (F9PSerialReadTaskHandle != NULL)
{
vTaskDelete(F9PSerialReadTaskHandle);
F9PSerialReadTaskHandle = NULL;
}
if (handleGNSSDataTaskHandle != NULL)
{
vTaskDelete(handleGNSSDataTaskHandle);
handleGNSSDataTaskHandle = NULL;
}
if (F9PSerialWriteTaskHandle != NULL)
{
vTaskDelete(F9PSerialWriteTaskHandle);
F9PSerialWriteTaskHandle = NULL;
}

//Give the other CPU time to finish
//Eliminates CPU bus hang condition
delay(100);
}

void beginFS()
{
if (online.fs == false)
Expand Down Expand Up @@ -712,39 +653,33 @@ bool beginExternalTriggers()
return (true);
}

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

if (i2cGNSS.getTimePulseParameters(&timePulseParameters) == false)
log_e("getTimePulseParameters failed!");
bool response = true;

timePulseParameters.tpIdx = 0; // Select the TIMEPULSE pin
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
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TP_TP1_ENA, settings.enableExternalPulse); //Enable/disable timepulse
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TP_PULSE_DEF, 0); //Time pulse definition is a period (in us)
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TP_PULSE_LENGTH_DEF, 1); //Define timepulse by length (not ratio)
response &= i2cGNSS.addCfgValset8(UBLOX_CFG_TP_POL_TP1, settings.externalPulsePolarity); //0 = falling, 1 = raising edge

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

// When the module is _locked_ to GNSS time, make it generate 1kHz
timePulseParameters.freqPeriodLock = settings.externalPulseTimeBetweenPulse_us; //Set the period between pulses is us
timePulseParameters.pulseLenRatioLock = settings.externalPulseLength_us; //Set the pulse length in us

timePulseParameters.flags.bits.active = settings.enableExternalPulse; //Make sure the active flag is set to enable the time pulse. (Set to 0 to disable.)
timePulseParameters.flags.bits.lockedOtherSet = 1; //Tell the module to use freqPeriod while locking and freqPeriodLock when locked to GNSS time
timePulseParameters.flags.bits.isFreq = 0; //Tell the module that we want to set the period
timePulseParameters.flags.bits.isLength = 1; //Tell the module that pulseLenRatio is a length (in us)
timePulseParameters.flags.bits.polarity = (uint8_t)settings.externalPulsePolarity; //Rising or failling edge type pulse
response &= i2cGNSS.addCfgValset32(UBLOX_CFG_TP_PERIOD_LOCK_TP1, settings.externalPulseTimeBetweenPulse_us); //Set the period between pulses is us
response &= i2cGNSS.sendCfgValset32(UBLOX_CFG_TP_LEN_LOCK_TP1, settings.externalPulseLength_us); //Set the pulse length in us

if (i2cGNSS.setTimePulseParameters(&timePulseParameters, 1000) == false)
log_e("setTimePulseParameters failed!");
if (response == false)
Serial.println("beginExternalTriggers config failed");

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

bool response = i2cGNSS.saveConfiguration(); //Save the current settings to flash and BBR
if (response == false)
Serial.println("Module failed to save.");

return (response);
}

Expand Down
Loading