Skip to article frontmatterSkip to article content
Site not loading correctly?

This may be due to an incorrect BASE_URL configuration. See the MyST Documentation for reference.

GNSS Single Point Positioning with Factor Graphs

Open In Colab

Overview

Global Navigation Satellite Systems (GNSS) are space-based systems that provide precise positioning, navigation, and timing (PNT) information to users anywhere on or near the Earth. GPS (Global Positioning System), developed and operated by the United States, is the most widely used GNSS, but it is part of a broader family that also includes Russia’s GLONASS, Europe’s Galileo, and China’s BeiDou.

GNSS works by measuring the travel time of radio signals transmitted from multiple satellites to a receiver on the ground. By combining these measurements with accurate satellite orbit and clock information, a receiver can determine its position, velocity, and time with high accuracy. Modern GNSS applications range from everyday uses such as smartphone navigation and time synchronization to advanced scientific, aviation, maritime, and geodetic applications requiring centimeter-level precision.

GNSS positioning problems can be encoded as factor graphs in GTSAM; this notebook shows an example of identifying a GNSS receiver’s position using pseudoranges from a RINEX file.

Prerequisites

We’ll need to install a couple python packages to help with today’s example. We’ll be using python bindings for the RTKLIB library to parse RINEX files from an example receiver source. Numpy is also installed here for easy array manipulation.

Premise

Single-point positioning (SPP) is the most basic GNSS positioning technique, in which a receiver determines its position using pseudorange measurements from multiple satellites and broadcast satellite orbit and clock information. It requires only a single receiver and does not rely on external corrections or reference stations, making it simple and widely accessible. While SPP typically provides meter-level accuracy, its performance is limited by errors such as satellite clock and orbit uncertainties, ionospheric and tropospheric delays, and measurement noise.

We’ll be looking at a receiver mounted on top of an FAA air traffic control center; ZOA1 in Fremont, California. It records pseudorange measurements 24/7 as part of a nationwide NOAA Continuously Operating Reference Stations (CORS) network that provides high-accuracy positioning data for geodesy, surveying, and navigation applications. Data from the CORS network can be accessed through the NOAA CORS Network (NCN) data portal, where we’ll download ZOA1’s observation and navigation files for January 18th, 2026.

zoa1_data = gnss_utils.loadCORSRINEX([
    "https://noaa-cors-pds.s3.amazonaws.com/rinex/2026/018/brdc0180.26n.gz",
    "https://noaa-cors-pds.s3.amazonaws.com/rinex/2026/018/zoa1/zoa10180.26o.gz"
])
print(zoa1_data)

Compute Satellite Positions

Satellite positions must be computed first before receiver position can be solved. GNSS broadcast ephemerides are orbit and clock parameters transmitted directly by navigation satellites as part of their navigation message. They allow receivers to compute satellite positions and clock corrections in real time using a simplified orbital model. While readily available and sufficient for standard navigation, broadcast ephemerides are less accurate than precise ephemerides due to prediction errors and limited modeling of perturbations.

The brdc0180.26n RINEX file contains orbital parameters we need to compute satellite positions. We won’t cover how orbits are stored and modeled in the RINEX files, but you can check out the RTCM website for more information. For now, we’ll simply have RTKLIB’s satposs() function do it for us.

zoa1_sat_pos = zoa1_data.computeSatelliteOrbits(zoa1_data.obs.data[0].time)

Solve Receiver Position and Time

Finally! We’re ready for factor graphs. Using the PseudorangeFactor, we can build a simple system that estimates receiver clock bias and 3D ECEF position. The graph topology is fairly straight-forward: One node for clock bias, another node for 3D position, all connected to a series of psuedorange factors that encapsulates satellite positions.

# Prepare factor graph:
cb_key = B(0)  # Receiver clock bias variable key.
pos_key = X(0) # Receiver position variable key.
nm = gtsam.noiseModel.Diagonal.Sigmas(np.array([1.0]))
graph = gtsam.NonlinearFactorGraph()

# Add a PseudorangeFactor for each observation:
for obsd, sat_bias, sat_pos, pseudorange in gnss_utils.iterateObservations(zoa1_data, zoa1_sat_pos, n=4):
    graph.add(
        gtsam.PseudorangeFactor(pos_key, cb_key, pseudorange, sat_pos, sat_bias, nm)
    )
    
    print(f"=== Satellite {obsd.sat} ===")
    print(f"Receiver pseudorange: {pseudorange} meters")
    print(f"Observation time (unixtime): {rtklib.time_str(obsd.time, 3)} ({obsd.time.time})")
    print(f"Satellite position (ECEF): {1e-3*sat_pos} km")
    print(f"Satellite clock drift: bias {sat_bias} seconds")
    print()

We initialize receiver position at origin, and then use a LM solver to optimize the system.

# Solve the system:
initial_values = gtsam.Values()
initial_values.insert(cb_key, 0.0)
initial_values.insert(pos_key, np.zeros(3))
result = gtsam.LevenbergMarquardtOptimizer(graph, initial_values).optimize()

# Process the results:
clock_bias = result.atDouble(cb_key)
receiver_position = result.atVector(pos_key)
print(f"Final clock bias {clock_bias} seconds and receiver position {receiver_position} (ECEF meters)")

Nice! We see that the solver converged at a reasonable solution. ECEF is difficult to visualize, however. So we’ll convert the result to geodetic coordinates and plot it on a map:

# Convert coordinates coordinates (latitude, longitude)
lon, lat, alt = ecef2lla.transform(receiver_position[0], receiver_position[1], receiver_position[2])
print(f"Latitude: {lat} degrees")
print(f"Longitude: {lon} degrees")
print(f"Altitude: {alt} meters")

gnss_utils.plotMap(lat, lon)

Validate Results

Our results appear to be roughly in the right place, but CORS stations actually provide ground-truth coordinates we can use as a measure of accuracy in our solutions. ZOA1’s full precision-surveyed coordinates are published in their data portal, but we’ll examine a just a snippet copied here:

| ITRF2020 POSITION (EPOCH 2020.0)                                            |
| Computed in Apr 2025 using data through gpswk 2237.                         |
|     X =  -2684436.824 m     latitude    =  37 32 34.99617 N                 |
|     Y =  -4293336.957 m     longitude   = 122 00 57.42005 W                 |
|     Z =   3865351.638 m     ellipsoid height =   -3.960   m                 |

We can compute a simple error metric by subtracting the two coordinates as follows:

ground_truth = np.array([-2684436.824, -4293336.957, 3865351.638])
error = ground_truth - receiver_position
print(f"Total positioning error: {np.linalg.norm(error)} meters")

Conclusions

29 meters of error puts us in the same building as the receiver, which is a good starting point for simple positioning. As mentioned above, however, decades of advancements have vastly improved GNSS positioning accuracy down to sub-meter or even centimeter-scale precision and error. The simple PseudorangeFactor does not account for atmospheric effects, carrier-phase measurements, nor differential GNSS corrections. So there’s a lot more potential for improvement, but this introductory example provides a foundation for expanding GNSS measurements into the broader GTSAM ecosystem.