I want to know code configuration of rover arduino. (using SparkFun GPS-RTK2 -ZED-F9P)

I organized the communication of base and rover as shown in the picture

thanks to sample code, i make base arduino code.

/*
  Send UBX binary commands to enable RTCM sentences on Ublox ZED-F9P module
  By: Nathan Seidle
  SparkFun Electronics
  Date: January 9th, 2019
  License: MIT. See license file for more information but you can
  basically do whatever you want with this code.

  This example does all steps to configure and enable a ZED-F9P as a base station:
    Begin Survey-In
    Once we've achieved 2m accuracy and 300s have passed, survey is complete
    Enable six RTCM messages
    Begin outputting RTCM bytes

  Feel like supporting open source hardware?
  Buy a board from SparkFun!
  ZED-F9P RTK2: https://www.sparkfun.com/products/15136
  NEO-M8P RTK: https://www.sparkfun.com/products/15005
  SAM-M8Q: https://www.sparkfun.com/products/15106

  Hardware Connections:
  Plug a Qwiic cable into the GPS and a BlackBoard
  If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
  Open the serial monitor at 115200 baud to see the output
*/

#include <Wire.h> //Needed for I2C to GPS
#include <SoftwareSerial.h>

#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_Ublox_GPS
SoftwareSerial S2(2,3);    // 2:RX 3:TX  // added to send RTCM3 format data packet to rover arduino by using HC-11 ( wireless uart communication)
SFE_UBLOX_GPS myGPS;

int cnt = 0;
uint8_t test[200]={0,};    // RTCM3 format data packet
void setup()
{
  Serial.begin(9600);       // 115200 -> 9600
  S2.begin(9600);           // wireless uart communication baud rate
  S2.flush(); 
  while (!Serial); //Wait for user to open terminal
  Serial.println("Ublox Base station example");

  Wire.begin();
  Wire.setClock(400000); //Increase I2C clock speed to 400kHz

  if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
  {
    Serial.println(F("Freezing."));
    while (1);
  }

  myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
  myGPS.saveConfiguration(); //Save the current settings to flash and BBR

  while (Serial.available()) Serial.read(); //Clear any latent chars in serial buffer
  Serial.println("Press any key");
  while (Serial.available() == 0) ; //Wait for user to press a key

  boolean response = true;
  response &= myGPS.enableRTCMmessage(UBX_RTCM_1005, COM_PORT_I2C, 1); //Enable message 1005 to output through I2C port, message every second
  response &= myGPS.enableRTCMmessage(UBX_RTCM_1074, COM_PORT_I2C, 1);
  response &= myGPS.enableRTCMmessage(UBX_RTCM_1084, COM_PORT_I2C, 1);
  response &= myGPS.enableRTCMmessage(UBX_RTCM_1094, COM_PORT_I2C, 1);
  response &= myGPS.enableRTCMmessage(UBX_RTCM_1124, COM_PORT_I2C, 1);
  response &= myGPS.enableRTCMmessage(UBX_RTCM_1230, COM_PORT_I2C, 10); //Enable message every 10 seconds

  //Use COM_PORT_UART1 for the above six messages to direct RTCM messages out UART1
  //COM_PORT_UART2, COM_PORT_USB, COM_PORT_SPI are also available
  //For example: response &= myGPS.enableRTCMmessage(UBX_RTCM_1005, COM_PORT_UART1, 10);

  if (response == true)
  {
    Serial.println("RTCM messages enabled");
  }
  else
  {
    Serial.println("RTCM failed to enable. Are you sure you have an ZED-F9P?"); // 
    while (1); //Freeze
  }

  //Check if Survey is in Progress before initiating one
  response = myGPS.getSurveyStatus(2000); //Query module for SVIN status with 2000ms timeout (request can take a long time)
  if (response == false)
  {
    Serial.println("b?"); //Failed to get Survey In status
    while (1); //Freeze
  }

  if (myGPS.svin.active == true)
  {
    Serial.print("in"); //Survey already in progress.
  }
  else
  {
    //Start survey
    //The ZED-F9P is slightly different than the NEO-M8P. See the Integration manual 3.5.8 for more info.
    //response = myGPS.enableSurveyMode(300, 2.000); //Enable Survey in on NEO-M8P, 300 seconds, 2.0m
    response = myGPS.enableSurveyMode(60, 5.000); //Enable Survey in, 60 seconds, 5.0m
    if (response == false)
    {
      Serial.println("fai"); // Survey start failed
      while (1);
    }
    Serial.println("Survey started."); // This will run until 60s has passed and less than 5m accuracy is achieved.
  }

  while(Serial.available()) Serial.read(); //Clear buffer
  
  //Begin waiting for survey to complete
  while (myGPS.svin.valid == false)
  {
    if(Serial.available())
    {
      byte incoming = Serial.read();
      if(incoming == 'x')
      {
        //Stop survey mode
        response = myGPS.disableSurveyMode(); //Disable survey
        Serial.println("Survey stopped");
        break;
      }
    }
    
    response = myGPS.getSurveyStatus(2000); //Query module for SVIN status with 2000ms timeout (req can take a long time)
    if (response == true)
    {
      Serial.print("Press x to end survey - ");
      Serial.print("Time elapsed: ");
      Serial.print((String)myGPS.svin.observationTime);

      Serial.print(" Accuracy: ");
      Serial.print((String)myGPS.svin.meanAccuracy);
      Serial.println();
    }
    else
    {
      Serial.println("SVIN request failed");
    }

    delay(1000);
  }
  Serial.println("Survey valid!");
  myGPS.setI2COutput(COM_TYPE_UBX | COM_TYPE_RTCM3); //Set the I2C port to output UBX and RTCM sentences (not really an option, turns on NMEA as well)
}

void loop()
{
  myGPS.checkUblox(); //See if new data is available. Process bytes as they come in.

  delay(250); //Don't pound too hard on the I2C bus
}

//This function gets called from the SparkFun Ublox Arduino Library.
//As each RTCM byte comes in you can specify what to do with it
//Useful for passing the RTCM correction data to a radio, Ntrip broadcaster, etc.
void SFE_UBLOX_GPS::processRTCM(uint8_t incoming)
{
  //Let's just pretty-print the HEX values for now
  
  if(cnt==0) S2.write("ba"); //hex - b (62), a(61) // added to inform start of packet to rover arduino
  cnt ++;
  S2.write(incoming);         // Send data to rover arduino
  // sencond byte + 6 = length of data packet
  /* reference
  //RTCM 3.2 bytes look like this:
  //Byte 0: Always 0xD3
  //Byte 1: 6-bits of zero
  //Byte 2: 10-bits of length of this packet including the first two-ish header bytes, + 6.
  //byte 3 + 4 bits: Msg type 12 bits
  //Example: D3 00 7C 43 F0 ... / 0x7C = 124+6 = 130 bytes in this packet, 0x43F = Msg type 1087
   */
  if(cnt ==3) num = incoming;  

  Serial.print(incoming, HEX);
  Serial.print(" ");

  
  // exception handling
  // in mormal case, length of one message type data packet don't reach 198. 
  if(cnt > 198)             
  {
    cnt = 0;
    Serial.println();
  }

  
  if (cnt == (num+6))     // 
  {
    S2.write("gh");       //hex - g (67), h(68) // added to inform end of packet to rover arduino
    cnt = 0;
    Serial.println();
  }
}

after that, I make rover arudino by using sample code.

/*
  Send UBX binary commands to enable RTCM sentences on Ublox ZED-F9P module
  By: Nathan Seidle
  SparkFun Electronics
  Date: January 9th, 2019
  License: MIT. See license file for more information but you can
  basically do whatever you want with this code.

  This example shows how to query the module for RELPOS information in the NED frame.
  It assumes you already have RTCM correction data being fed to the receiver.

  Feel like supporting open source hardware?
  Buy a board from SparkFun!
  ZED-F9P RTK2: https://www.sparkfun.com/products/15136
  NEO-M8P RTK: https://www.sparkfun.com/products/15005
  SAM-M8Q: https://www.sparkfun.com/products/15106

  Hardware Connections:
  Plug a Qwiic cable into the GPS and a RedBoard Qwiic or BlackBoard
  If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
  Open the serial monitor at 115200 baud to see the output
*/

#include <Wire.h> //Needed for I2C to GPS
// ㅡㅡㅡㅡㅡㅡadded ㅡㅡㅡㅡㅡㅡㅡㅡㅡㅡ
#include <SoftwareSerial.h>
uint8_t ch;
uint8_t cnt = 0;
int flag = 1;
uint8_t test[200] = {0,};
int num;
int lastTime = 0;
// ㅡㅡㅡㅡㅡㅡㅡㅡㅡㅡㅡㅡㅡㅡㅡㅡㅡㅡ
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_Ublox_GPS
SFE_UBLOX_GPS myGPS;
SoftwareSerial S2(2,3);    // 2:RX 3:TX       // added

void setup()
{
  Serial.begin(9600);                         // modified (115200 -> 9600)
  S2.begin(9600);                             // added
  S2.flush();                                 // added
  while (!Serial); //Wait for user to open terminal
  Serial.println("Ublox Base station example");

  Wire.begin();
  Wire.setClock(400000); //Increase I2C clock speed to 400kHz

  if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
  {
    Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
    while (1);
  }
  
  myGPS.setI2COutput(COM_TYPE_NMEA|COM_TYPE_UBX);   // get NMEA, UBX format data from gps module
  myGPS.setPortInput(0, 0x20);                      // send rtcm3 data to gps module
  
}

void loop()
{
for(int i=0;i<8;i++)
{
  // in base arduino code, i send "ba" to inform start of data packet.
  if(S2.available()) 
  {
    ch = S2.read();
    Serial.print(ch,HEX);  
    if (ch == 98)
    {
      if(S2.available())
      {
        ch = S2.read();
        Serial.print(ch,HEX);
        if (ch == 97) flag = 1; 
      }
    }
  }

  // make data packet as msg type.
  while(flag == 1)
  {
    Serial.print(" ");
    if(S2.available())
    {
      ch = S2.read();
      cnt++;
      test[cnt-1] = ch;
      Serial.print(test[cnt-1], HEX);
      Serial.print(" ");
     //exception handling
      if(cnt> 180)
      {
        flag = 0;
        Serial.println("");
      }
     // I sended "gh" from base- arduino to inform end of data packet.
      if(test[cnt-1] == 104)
      {
         Serial.print(test[cnt-1]);
         if(test[cnt-2] == 103)
         {
           Serial.print(test[cnt-2]);
           Serial.println("");
           flag = 0;

           // send data packet to gps module
           // in this I2C communication, rover-arudino is master,
           // and rover - gps module is slave( I2C address : 66) 
           Wire.beginTransmission(66); 
           Wire.write(test,cnt-2);
           Wire.endTransmission();
         }
      }
    }
  }
  cnt = 0;
}
  
  if (millis() - lastTime > 5000)             // modified 1000 -> 5000
  {
    lastTime = millis(); //Update the timer
  if (myGPS.getRELPOSNED() == true)
  {
    Serial.print("relPosN: ");
    Serial.println(myGPS.relPosInfo.relPosN, 4);
    Serial.print("relPosE: ");
    Serial.println(myGPS.relPosInfo.relPosE, 4);
    Serial.print("relPosD: ");
    Serial.println(myGPS.relPosInfo.relPosD, 4);
  }
  else
    Serial.println("RELPOS request failed");
  }
  
  
}

in GPS-RTK2 Hookup Guide, says

‘What about configuring the rover? Ublox designed the ZED-F9P to automatically go into RTK mode once RTCM data is detected on any of the ports. Simply push the RTCM bytes from your back channel into one of the ports (UART, SPI, I2C) on the rover’s ZED-F9P and the location accuracy will go from meters to centimeters. The rover’s NMEA messages will contain the improved Lat/Long data and you’ll know where you are with mind-bending accuracy. It’s a lot of fun to watch’

So , I directly send every rtcm3 format data (that come from base arduino code) from rover-arduino to gps module of rover.

I added below codes in rover-arudino code to make rover configuration,

  myGPS.setI2COutput(COM_TYPE_NMEA|COM_TYPE_UBX);   // get NMEA, UBX format data from gps module
  myGPS.setPortInput(0, 0x20);                                                              // send rtcm3 data to gps module

when i make this code,

I use setPortInput function in ublox library,

//Configure a given port to input UBX, NMEA, RTCM3 or a combination thereof
//Port 0=I2c, 1=UART1, 2=UART2, 3=USB, 4=SPI
//Bit:0 = UBX, :1=NMEA, :5=RTCM3
boolean SFE_UBLOX_GPS::setPortInput(uint8_t portID, uint8_t inStreamSettings, uint16_t maxWait)
{
  //Get the current config values for this port ID
  //This will load the payloadCfg array with current port settings
  if (getPortSettings(portID, maxWait) == false)
    return (false); //Something went wrong. Bail.

  packetCfg.cls = UBX_CLASS_CFG;
  packetCfg.id = UBX_CFG_PRT;
  packetCfg.len = 20;
  packetCfg.startingSpot = 0;

  //payloadCfg is now loaded with current bytes. Change only the ones we need to
  payloadCfg[12] = inStreamSettings; //InProtocolMask LSB - Set inStream bits

  return ((sendCommand(&packetCfg, maxWait)) == SFE_UBLOX_STATUS_DATA_SENT); // We are only expecting an ACK
}

and to send RTCM3 message from rover-arudino to gps module I added below code,

           // send data packet to gps module
           // in this I2C communication, rover-arudino is master,
           // and rover - gps module is slave( I2C address : 66) 
           Wire.beginTransmission(66); 
           Wire.write(test,cnt-2);
           Wire.endTransmission();

but, only one sentences that i can see on serial monitor is " RELPOS request failed "

It was confirmed that the rtcm3 format data from base-arduino appeared well in the rover - arduino.

To get relpos data, how i modify source code?

Which source code are you referring to?

TS-Brandon:
Which source code are you referring to?

I use code in this library.

https://github.com/sparkfun/SparkFun_Ub … no_Library

make base : libraries\SparkFun_Ublox_Arduino_Library\examples\ZED-F9P\Example3_StartRTCMBase

make rover : libraries\SparkFun_Ublox_Arduino_Library\examples\ZED-F9P\Example5_RelativePositioningInformation

Did you success to make the rover working? i’m in the same case as you…

Try looking at page 15 of the integration manual. Section 3.5: Configuration of the base and rover for RTK operation