Skip to article frontmatterSkip to article content

Dataset Utilities

The gtsam/slam/dataset.h header provides utility functions for loading and saving factor graph data, particularly in formats commonly used in the SLAM community like TORO (‘.graph’) and g2o (‘.g2o’).

Key functions include:

  • findExampleDataFile(name): Locates example dataset files distributed with GTSAM.
  • load2D(filename, ...): Loads a 2D pose graph (Poses and BetweenFactors) from TORO or g2o format.
  • load3D(filename): Loads a 3D pose graph (currently simpler than load2D, assumes specific format).
  • readG2o(filename, is3D): A more general function to read g2o files containing various factor and variable types (2D/3D poses, landmarks, measurements).
  • writeG2o(graph, initialEstimate, filename): Saves a factor graph and values to the g2o format.
  • parseVariables<T>/parseMeasurements<T>/parseFactors<T>: Lower-level parsing functions (less commonly used directly).

Open In Colab

import gtsam
import gtsam.utils.plot as gtsam_plot
import matplotlib.pyplot as plt
import numpy as np
import os

# Ensure the example datasets are available
# In Colab/pip install, they are usually included.
# If running locally from build, findExampleDataFile works.
# If running locally from install without examples, this might fail.
try:
    # Check for a common example file
    gtsam.findExampleDataFile("w100.graph")
    HAVE_EXAMPLES = True
except RuntimeError:
    print("Warning: Example datasets not found.")
    print("Try running from build directory or installing examples.")
    HAVE_EXAMPLES = False

# Create dummy files for writing examples if needed
if not os.path.exists("output"):
    os.makedirs("output")

Finding Example Datasets

if HAVE_EXAMPLES:
    try:
        w100_path = gtsam.findExampleDataFile("w100.graph")
        print(f"Found w100.graph at: {w100_path}")
        dlr_path = gtsam.findExampleDataFile("dlr.g2o")
        print(f"Found dlr.g2o at: {dlr_path}")
    except RuntimeError as e:
        print(f"Error finding example file: {e}")
else:
    print("Skipping findExampleDataFile test as examples are not available.")
Found w100.graph at: c:\Users\porte\miniconda3\envs\gtsam\Lib\site-packages\gtsam\Data\w100.graph
Found dlr.g2o at: None

Loading 2D Datasets (load2D)

if HAVE_EXAMPLES:
    # Load TORO 2D file
    graph_2d, initial_2d = gtsam.load2D(w100_path)
    print(f"\nLoaded {w100_path}:")
    print(f"  Graph size: {graph_2d.size()}")
    print(f"  Initial estimate keys: {len(initial_2d.keys())}")

    # Plot initial estimate (optional)
    for key in initial_2d.keys():
         gtsam_plot.plot_pose2(0, initial_2d.atPose2(key))
    plt.title("Initial Estimate from w100.graph")
    plt.axis('equal')
    # plt.show() # Uncomment to display plot
    plt.close() # Close plot to prevent display in output
else:
    print("\nSkipping load2D test.")

Loaded c:\Users\porte\miniconda3\envs\gtsam\Lib\site-packages\gtsam\Data\w100.graph:
  Graph size: 300
  Initial estimate keys: 100

Loading/Saving G2O Files (readG2o, writeG2o)

readG2o can handle both 2D and 3D datasets and various factor types defined in the g2o format. writeG2o saves a NonlinearFactorGraph and Values into a g2o file.

if HAVE_EXAMPLES:
   # Load a 3D g2o file
   try:
      graph_3d, initial_3d = gtsam.readG2o(dlr_path, is3D=True)
      print(f"\nLoaded {dlr_path} (3D):")
      print(f"  Graph size: {graph_3d.size()}")
      print(f"  Initial estimate keys: {len(initial_3d.keys())}")
      # You could optimize graph_3d with initial_3d here...
      print("Optimization skipped for brevity.")
      optimized_values = initial_3d # Use initial for demo write

      # Save the graph and values back to a g2o file
      output_g2o_file = os.path.join("output", "dlr_rewrite.g2o")
      gtsam.writeG2o(graph_3d, optimized_values, output_g2o_file)
      print(f"  Saved graph and values to {output_g2o_file}")
      # Clean up dummy file
      # os.remove(output_g2o_file)
      # os.rmdir("output")
   except (RuntimeError, TypeError) as e:
      print(f"Error processing {dlr_path}: {e}")
else:
    print("\nSkipping readG2o/writeG2o test.")
Error processing None: readG2o(): incompatible function arguments. The following argument types are supported:
    1. (filename: str, is3D: bool = False, kernelFunctionType: gtsam.gtsam.KernelFunctionType = <KernelFunctionType.KernelFunctionTypeNONE: 0>) -> tuple[gtsam.gtsam.NonlinearFactorGraph, gtsam.gtsam.Values]

Invoked with: None; kwargs: is3D=True