diff --git a/python/gtsam/examples/README.md b/python/gtsam/examples/README.md index d3c5a36733..c70283664c 100644 --- a/python/gtsam/examples/README.md +++ b/python/gtsam/examples/README.md @@ -49,7 +49,7 @@ | SimpleRotation | :heavy_check_mark: | | SolverComparer | | | StereoVOExample | :heavy_check_mark: | -| StereoVOExample_large | | +| StereoVOExample_large | :heavy_check_mark: | | TimeTBB | | | UGM_chain | discrete functionality not yet exposed | | UGM_small | discrete functionality not yet exposed | diff --git a/python/gtsam/examples/StereoVOExample.ipynb b/python/gtsam/examples/StereoVOExample.ipynb index 2589cf23d9..d37da72417 100644 --- a/python/gtsam/examples/StereoVOExample.ipynb +++ b/python/gtsam/examples/StereoVOExample.ipynb @@ -7,23 +7,31 @@ "source": [ "# Stereo Visual Odometry with GTSAM\n", "\n", + "\"Open\n", + "\n", "This notebook demonstrates a simple 3D stereo visual odometry problem using the GTSAM Python wrapper. The scenario is as follows:\n", "\n", "1. A robot starts at the origin (Pose 1: `X(1)`).\n", - "2. The robot moves approximately 1 meter forward (Pose 2: `X(2)`).\n", + "2. The robot moves approximately one meter forward (Pose 2: `X(2)`).\n", "3. From both poses, the robot observes three landmarks (`L(1)`, `L(2)`, `L(3)`) with a stereo camera.\n", "\n", "We will:\n", - "* Define camera calibration and noise models.\n", - "* Create a factor graph representing the problem.\n", - "* Provide initial estimates for poses and landmark positions.\n", - "* Optimize the graph using Levenberg-Marquardt to find the most probable configuration.\n" + "- Define camera calibration and noise models.\n", + "- Create a factor graph representing the problem.\n", + "- Provide initial estimates for poses and landmark positions.\n", + "- Optimize the graph using Levenberg-Marquardt to find the most probable configuration.\n", + "\n", + "**Note:** This example is also available in C++. If you're interested in the C++ implementation, refer to `StereoVOExample.cpp` in the [GTSAM examples directory](https://github.com/borglab/gtsam/tree/develop/examples)." ] }, { "cell_type": "markdown", "id": "e33e553a", - "metadata": {}, + "metadata": { + "tags": [ + "remove-cell" + ] + }, "source": [ "GTSAM Copyright 2010-2025, Georgia Tech Research Corporation,\n", "Atlanta, Georgia 30332-0415\n", @@ -35,25 +43,49 @@ ] }, { - "cell_type": "markdown", - "id": "6af0f339", - "metadata": {}, + "cell_type": "code", + "execution_count": 1, + "id": "43bbbfe4", + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Not running in Google Colab. Please install necessary libraries as needed.\n" + ] + } + ], "source": [ - "\"Open" + "try:\n", + " import google.colab\n", + " print(\"Running in Google Colab, installing necessary libraries...\")\n", + " %pip install --quiet gtsam-develop\n", + " print(\"Done!\")\n", + "except ImportError:\n", + " print(\"Not running in Google Colab. Please install necessary libraries as needed.\")\n", + " pass" ] }, { "cell_type": "code", - "execution_count": 19, - "id": "ac25f0ee", - "metadata": {}, + "execution_count": 2, + "id": "778ceb66", + "metadata": { + "tags": [ + "hide-cell" + ] + }, "outputs": [], "source": [ "import gtsam\n", - "import numpy as np\n", "\n", "# For shorthand for common GTSAM types (like X for poses, L for landmarks)\n", - "from gtsam.symbol_shorthand import X, L\n" + "from gtsam.symbol_shorthand import X, L" ] }, { @@ -63,14 +95,12 @@ "source": [ "## 1. Setup Factor Graph and Priors\n", "\n", - "We start by creating an empty `NonlinearFactorGraph`.\n", - "\n", - "The first pose `X(1)` is assumed to be at the origin. We'll add a hard constraint (prior) for this using `NonlinearEqualityPose3`. In GTSAM, factor keys are typically integers. We use `X(1)` as a symbolic key for the first pose.\n" + "We start by creating an empty `NonlinearFactorGraph`. The first pose `X(1)` is assumed to be at the world origin. To reflect this, we add a hard constraint using `NonlinearEqualityPose3`, which fixes `X(1)` to the identity pose. This ensures that the optimization has a known reference point for the rest of the variables. In GTSAM, factor keys are typically integers, and `X(1)` is a symbolic shorthand for such a key.\n" ] }, { "cell_type": "code", - "execution_count": 20, + "execution_count": 3, "id": "342a585f", "metadata": {}, "outputs": [ @@ -89,9 +119,7 @@ "# Define the first pose at the origin\n", "first_pose = gtsam.Pose3() # Default constructor is identity\n", "\n", - "# Add a prior on the first pose (X1). This constraint implies X1 is fixed at the origin.\n", - "# NonlinearEqualityPose3 is a factor that enforces X(1) == first_pose.\n", - "# It effectively acts as a prior with infinite precision (zero noise).\n", + "# Add a prior constraint on X(1)\n", "graph.add(gtsam.NonlinearEqualityPose3(X(1), first_pose))\n", "\n", "print(\"Graph size after adding prior:\", graph.size())\n" @@ -104,26 +132,42 @@ "source": [ "## 2. Define Camera Calibration and Measurement Noise\n", "\n", - "- **Noise Model:** We define an isotropic noise model for the stereo measurements. `Isotropic.Sigma(3, 1.0)` means a 3-dimensional noise (for $u_L, u_R, v$) with a standard deviation of 1 pixel for each dimension.\n", + "To accurately model the stereo observations, we must define both the measurement noise model and the intrinsic calibration of the stereo camera system.\n", + "- **Measurement Noise:** We assume an isotropic Gaussian noise model for the stereo measurements. Since each observation consists of three pixel values $(u_L, u_R, v)$, we use `Isotropic.Sigma(3, 1.0)` to define a noise model with unit standard deviation in each of the three dimensions.\n", "- **Camera Calibration ([`Cal3_S2Stereo`](/gtsam/geometry/doc/Cal3_S2Stereo.ipynb)):** We define a stereo calibration model with the following properties:\n", - " - $f_x=f_y=1000$\n", - " - $s=0$\n", - " - $(u,v)=(320,\\,240)$\n", - " - $b=0.2$" + " - Focal lengths: $f_x=f_y=1000$\n", + " - Skew: $s=0$\n", + " - Principal point: $(u,v)=(320,\\,240)$\n", + " - Baseline: $b=0.2$\n", + " \n", + "These parameters represent a synthetic stereo camera setup for this minimal example." ] }, { "cell_type": "code", - "execution_count": 21, + "execution_count": 4, "id": "e04b26c7", "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "K: 1000 0 320\n", + " 0 1000 240\n", + " 0 0 1\n", + "Baseline: 0.2\n", + "\n" + ] + } + ], "source": [ - "# Define the stereo measurement noise model (isotropic, 1 pixel standard deviation)\n", - "measurement_noise = gtsam.noiseModel.Isotropic.Sigma(3, 1.0)\n", - "\n", "# Create stereo camera calibration object\n", - "K = gtsam.Cal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2)" + "K = gtsam.Cal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2)\n", + "print(K)\n", + "\n", + "# Define the stereo measurement noise model (isotropic, 1 pixel standard deviation)\n", + "measurement_noise = gtsam.noiseModel.Isotropic.Sigma(3, 1.0)" ] }, { @@ -136,19 +180,17 @@ "We now add stereo factors to the graph. Each factor connects a camera pose to a landmark.\n", "The `GenericStereoFactor3D` takes:\n", "* `measured`: The `StereoPoint2` measurement $(u_L, u_R, v)$.\n", - "* `model`: The noise model for the measurement.\n", + "* `model`: The noise model for the pixel measurement.\n", "* `poseKey`: Key for the camera pose.\n", "* `landmarkKey`: Key for the landmark.\n", "* `K`: The stereo camera calibration.\n", "\n", - "Landmark keys in the C++ example are 3, 4, 5. We'll use `L(1)`, `L(2)`, `L(3)` to map to these.\n", - "\n", - "**Measurements from Pose 1 (`X(1)`)**\n" + "We'll use `L(1)`, `L(2)`, `L(3)` to represent our three landmarks." ] }, { "cell_type": "code", - "execution_count": 22, + "execution_count": 5, "id": "e9778bec", "metadata": {}, "outputs": [ @@ -162,28 +204,22 @@ ], "source": [ "# Factors from X(1) to landmarks\n", - "# StereoPoint2(uL, uR, v)\n", "graph.add(gtsam.GenericStereoFactor3D(\n", - " gtsam.StereoPoint2(520, 480, 440), measurement_noise, X(1), L(1), K))\n", + " gtsam.StereoPoint2(520, 480, 440), measurement_noise, X(1), L(1), K\n", + "))\n", "graph.add(gtsam.GenericStereoFactor3D(\n", - " gtsam.StereoPoint2(120, 80, 440), measurement_noise, X(1), L(2), K))\n", + " gtsam.StereoPoint2(120, 80, 440), measurement_noise, X(1), L(2), K\n", + "))\n", "graph.add(gtsam.GenericStereoFactor3D(\n", - " gtsam.StereoPoint2(320, 280, 140), measurement_noise, X(1), L(3), K))\n", + " gtsam.StereoPoint2(320, 280, 140), measurement_noise, X(1), L(3), K\n", + "))\n", "\n", "print(\"Graph size after adding X(1) factors:\", graph.size())\n" ] }, - { - "cell_type": "markdown", - "id": "d0160cf1", - "metadata": {}, - "source": [ - "**Measurements from Pose 2 (`X(2)`)**\n" - ] - }, { "cell_type": "code", - "execution_count": 23, + "execution_count": 6, "id": "495fc44f", "metadata": {}, "outputs": [ @@ -198,11 +234,14 @@ "source": [ "# Factors from X(2) to landmarks\n", "graph.add(gtsam.GenericStereoFactor3D(\n", - " gtsam.StereoPoint2(570, 520, 490), measurement_noise, X(2), L(1), K))\n", + " gtsam.StereoPoint2(570, 520, 490), measurement_noise, X(2), L(1), K\n", + "))\n", "graph.add(gtsam.GenericStereoFactor3D(\n", - " gtsam.StereoPoint2(70, 20, 490), measurement_noise, X(2), L(2), K))\n", + " gtsam.StereoPoint2(70, 20, 490), measurement_noise, X(2), L(2), K\n", + "))\n", "graph.add(gtsam.GenericStereoFactor3D(\n", - " gtsam.StereoPoint2(320, 270, 115), measurement_noise, X(2), L(3), K))\n", + " gtsam.StereoPoint2(320, 270, 115), measurement_noise, X(2), L(3), K\n", + "))\n", "\n", "print(\"Graph size after adding all factors:\", graph.size())" ] @@ -214,17 +253,15 @@ "source": [ "## 4. Create Initial Estimates\n", "\n", - "Nonlinear optimization requires initial estimates for all variables (poses and landmarks).\n", - "We create a `Values` object to store these.\n", - "\n", - "* `X(1)`: At origin (matches the prior).\n", - "* `X(2)`: Robot moves forward, slightly off-axis: `Pose3(Rot3(), Point3(0.1, -0.1, 1.1))`.\n", - "* Landmarks (`L(1)`, `L(2)`, `L(3)` or `3,4,5`): Placed at estimated 3D positions.\n" + "Nonlinear optimization requires initial estimates for all variables (poses and landmarks). We create a `Values` object named `initial_estimate` to store these. To see the effects of optimization in the later sections, we introduce a small error when inserting the initial estimate of pose `X(2)`. In summary, this is what we insert into `initial_estimate`:\n", + "* Pose `X(1)`: Identity pose at the origin.\n", + "* Pose `X(2)`: Camera pose after the robot moves forward by one meter, slightly off-axis and with a small overshoot.\n", + "* Landmarks (`L(1)`, `L(2)`, `L(3)`): Placed at estimated 3D positions.\n" ] }, { "cell_type": "code", - "execution_count": 24, + "execution_count": 7, "id": "b4be6ab2", "metadata": {}, "outputs": [], @@ -258,7 +295,7 @@ }, { "cell_type": "code", - "execution_count": 25, + "execution_count": 8, "id": "d0c3a87b", "metadata": {}, "outputs": [], @@ -277,18 +314,21 @@ "source": [ "## 6. Analyze Results\n", "\n", - "We can extract the optimized poses and landmark positions from the `result` Values object.\n", + "After optimization, we extract the refined poses and landmark positions from the `result` returned by the optimizer.\n", + "\n", + "Recall that in this example, the robot begins at the origin, and we expect the second pose `X(2)` to be apprixmately one meter forward along the Z-axis, so `X(2)` should ideally be near `Pose3(Rot3(), Point3(0, 0, 1.0))`.\n", "\n", - "For example, the true second pose (if the robot moved exactly 1m forward along Z from origin) would be `Pose3(Rot3(), Point3(0, 0, 1.0))`.\n", - "The true landmark positions can be triangulated from the perfect measurements and true poses.\n", - "The example's measurements and initial estimates are designed to be somewhat noisy/imperfect, so the optimizer refines them.\n", + "GTSAM minimizes the total reprojection error (i.e. the discrepancy between observed and predicted stereo image coordinates) across all factors. We can evaluate this using `graph.error()` to compute the total error before and after optimization. A significant drop in this error indicates that the optimizer successfully refined the estimates.\n", "\n", - "Let's check the error before and after optimization.\n" + "To better understand the outcome of this example, we print the error, both prior- and post-optimization, along with the optimized poses and landmark positions. This helps verify:\n", + "- That the optimizer is successful in refining the estimates.\n", + "- That the second pose `X(2)` aligns with the expected forward motion.\n", + "- That the landmark locations are consistent and reasonable." ] }, { "cell_type": "code", - "execution_count": 26, + "execution_count": 9, "id": "093fe3dc", "metadata": {}, "outputs": [ diff --git a/python/gtsam/examples/StereoVOExample_large.ipynb b/python/gtsam/examples/StereoVOExample_large.ipynb new file mode 100644 index 0000000000..c34b812c7d --- /dev/null +++ b/python/gtsam/examples/StereoVOExample_large.ipynb @@ -0,0 +1,2292 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Stereo Visual Odometry Example (Large Dataset)\n", + "\n", + "\"Open\n", + "\n", + "In this notebook we build on `StereoVOExample.ipynb` to tackle a more realistic stereo visual-odometry problem. A robot carries a stereo camera, moves forward over a longer trajectory, and observes a large sample of landmarks. Our goals are:\n", + "\n", + "1. Define a noise model and stereo calibration. \n", + "2. Assemble a factor graph of stereo-measurement factors. \n", + "3. Provide initial estimates for both camera poses and landmark positions. \n", + "4. Run Levenberg–Marquardt optimization to recover the most likely trajectory and map. \n", + "5. Analyze and visualize final poses and landmarks.\n", + "\n", + "\n", + "If any section may seem unclear, we recommend looking at `StereoVOExample.ipynb` first and coming back to this example afterwards. \n", + "\n", + "**Note:** This example is also available in C++. If you're interested in the C++ implementation, refer to `StereoVOExample_large.cpp` in the [GTSAM examples directory](https://github.com/borglab/gtsam/tree/develop/examples)." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "source": [ + "GTSAM Copyright 2010-2025, Georgia Tech Research Corporation,\n", + "Atlanta, Georgia 30332-0415\n", + "All Rights Reserved\n", + "\n", + "Authors: Frank Dellaert, et al. (see THANKS for the full author list)\n", + "\n", + "See LICENSE for the license information" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Not running in Google Colab. Please install necessary libraries as needed.\n" + ] + } + ], + "source": [ + "try:\n", + " import google.colab\n", + " print(\"Running in Google Colab, installing necessary libraries...\")\n", + " %pip install --quiet gtsam-develop\n", + " print(\"Done!\")\n", + "except ImportError:\n", + " print(\"Not running in Google Colab. Please install necessary libraries as needed.\")\n", + " pass # Not in Colab" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": { + "tags": [ + "hide-cell" + ] + }, + "outputs": [], + "source": [ + "import gtsam\n", + "import gtsam.utils.plot as gtsam_plot\n", + "import numpy as np\n", + "import plotly.graph_objects as go\n", + "\n", + "# For shorthand for common GTSAM types (like X for poses, L for landmarks)\n", + "from gtsam.symbol_shorthand import X, L" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 1. Setup Factor Graph\n", + "\n", + "We start by creating an empty `NonlinearFactorGraph`." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "# Create an empty nonlinear factor graph\n", + "graph = gtsam.NonlinearFactorGraph()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 2. Define Camera Calibration and Measurement \n", + "\n", + "To accurately model the stereo observations, we must define both the measurement noise model and the intrinsic calibration of the stereo camera system.\n", + "- **Measurement Noise:** We assume an isotropic Gaussian noise model for the stereo measurements. Since each observation consists of three pixel values $(u_L, u_R, v)$, we use `Isotropic.Sigma(3, 1.0)` to define a noise model with unit standard deviation in each of the three dimensions.\n", + "- **Camera Calibration ([`Cal3_S2Stereo`](/gtsam/geometry/doc/Cal3_S2Stereo.ipynb)):** We load precomputed intrinsic parameters and baseline values to construct a stereo calibration model. These values are as follows:\n", + " - Focal lengths: $f_x=f_y=721.5377$\n", + " - Skew: $s=0$\n", + " - Principal point: $(u,v)=(609.5593,\\,172.854)$\n", + " - Baseline: $b=0.537150588$\n", + " \n", + "These parameters define how 3D world points are projected into pixel coordinates in the left and right stereo images, and are essential for constructing `GeneraicStereoFactor3D` measurements in Section 5." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "K: 721.538 0 609.559\n", + " 0 721.538 172.854\n", + " 0 0 1\n", + "Baseline: 0.537151\n", + "\n" + ] + } + ], + "source": [ + "# Retrieve Calibration file\n", + "cal_params_file = gtsam.findExampleDataFile(\"VO_calibration.txt\")\n", + "\n", + "# Read calibration parameters\n", + "cal_params = np.loadtxt(cal_params_file)\n", + "\n", + "# Create a Cal3_S2Stereo calibration object\n", + "K = gtsam.Cal3_S2Stereo(cal_params)\n", + "print(K)\n", + "\n", + "# Define the stereo measurement noise model (isotropic, 1 pixel standard deviation)\n", + "measurement_noise_model = gtsam.noiseModel.Isotropic.Sigma(3, 1.0)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 3. Construct Initial Pose Estimates from Odometry Measurements" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The next step in our visual odometry pipeline is to provide an initial guess for the robot's trajectory. GTSAM relies on good initial values for its nonlinear optimization process to converge accurately and efficiently. These initial pose estimates serve as a prior that guides the optimizer toward a globally consistent solution.\n", + "\n", + "In this example, the pose data is stored in a text file, where each row corresponds to a unique camera pose. Each row contains 17 values:\n", + "- The first value is an integer index/ID that identifies the camera pose.\n", + "- The remaining 16 values encode the camera's 3D pose as a flattened $4\\times 4$ transformation matrix, stored in row-major order. This matrix represents a rigid body transformation in $SE(3)$, combining both rotation and translation.\n", + "\n", + "The file contains pose data for 26 time steps along the robot's trajectory. We load these poses and insert them into a `gtsam.Values` object named `initial_estimates`. This object functions like a dictionary, mapping symbolic keys (e.g. `X(1)`, `X(2)`,...) to corresponding `Pose3` objects. These estimates will later be refined during optimization, but they must be reasonably close to the true trajectory to ensure successful convergence." + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "# Odometry data file with camera poses\n", + "odometry_data_file = gtsam.findExampleDataFile(\"VO_camera_poses_large.txt\")\n", + "\n", + "# Read poses\n", + "camera_poses = np.loadtxt(odometry_data_file)\n", + "\n", + "# Create a gtsam.Values object to hold the pose data\n", + "initial_estimates = gtsam.Values()\n", + "\n", + "# Parse the raw camera pose data\n", + "for pose in camera_poses:\n", + "\tpose_id = int(pose[0])\n", + "\tm = pose[1:].copy().reshape(4, 4)\n", + "\tinitial_estimates.insert(X(pose_id), gtsam.Pose3(m))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 4. Load and Inspect Stereo Measurement Data\n", + "In this section, we load the raw stereo measurement data that encodes the pixel observations and 3D landmark positions captured by the robot's stereo camera. This data provides the core geometric constraints that link camera poses to landmarks in our factor graph.\n", + "\n", + "Each row in the data file represents a single stereo observation, consisting of eight values:\n", + "- The first two values are integer indices/IDs: one for the camera pose and one for the landmark.\n", + "- The next three values are the rectified stereo pixel coordinates $(u_L, u_R, v)$. These represent horizontal pixel positions in the left and right images and the sharted vertical coordinate.\n", + "- The last three values are the 3D coordinates $(X, Y, Z)$ of the observed landmark, expressed in the camera frame using stereo triangulation.\n", + "\n", + "This data will be used in the next steps to build measurement factors and initialize landmark positions in the world frame." + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Loaded 8189 stereo observations.\n", + "First row (for reference):\n", + "[ 1. 3. 209.979 185.87 61.5418 -8.90263 -2.48003\n", + " 16.0758 ]\n" + ] + } + ], + "source": [ + "# Factor data file with pixel coordinates and landmark coordinates\n", + "factor_data_file = gtsam.findExampleDataFile(\"VO_stereo_factors_large.txt\")\n", + "\n", + "# Each row has 8 columns corresponding to [pose_id, landmark_id, uL, uR, v, X, Y, Z]\n", + "data_matrix = np.loadtxt(factor_data_file)\n", + "\n", + "print(f\"Loaded {data_matrix.shape[0]} stereo observations.\")\n", + "print(f\"First row (for reference):\\n{data_matrix[0]}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 5. Add Stereo Factors to the Factor Graph\n", + "With the measurement data loaded, we now translate each stereo observation into a factor that constrains the relative position of a camera pose and a landmark. These constraints form the backbone of our factor graph and are essential for computing an optimized trajectory and map.\n", + "\n", + "For every observation entry (or row) in the measurement matrix:\n", + "- We create a `GenericStereoFactor3D` using the pixel coordinates $(u_L, u_R, v)$, the stereo calibration object `K`, and the noise model defined earlier.\n", + "- Each factor connects a camera pose variable `X(i)` and a landmark variable `L(j)` with the associated stereo observation.\n", + "- The stereo measurement provides enough geometric information to triangulate depth and establish spatial relationships in 3D.\n", + "\n", + "This step builds up the graph structure that the optimizer will later use to refine both the robot's trajectory and the map of landmarks." + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [], + "source": [ + "# Add a stereo measurement factor for each observation\n", + "for entry in data_matrix:\n", + "\tpose_id = int(entry[0])\n", + "\tlandmark_id = int(entry[1])\n", + "\tuL, uR, v = entry[2:5]\n", + "\n", + "\tgraph.add(gtsam.GenericStereoFactor3D(\n", + "\t\tgtsam.StereoPoint2(uL, uR, v),\t# Stereo measurement\n", + "\t\tmeasurement_noise_model, \t\t# Assumed pixel measurement noise\n", + "\t\tX(pose_id), \t\t\t\t\t# Camera pose key\n", + "\t\tL(landmark_id), \t\t\t\t# Landmark key\n", + "\t\tK\t\t\t\t\t\t\t\t# Stereo calibration\n", + "\t))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 6. Initialize Landmark Positions from Triangulated Observations\n", + "Now that we have added measurement factors to the graph, we need to provide an initial guess for the location of each landmark. These guesses are essential for nonlinear optimization; without them, the optimizer would have no starting point from which to refine the 3D landmark positions.\n", + "\n", + "As mentioned before, each observation row includes a 3D point $(X, Y, Z)$ representing the landmark's position in the camera frame at the time of observation. However, GTSAM operates in a global coordinate frame, so we must convert each point from the camera's local frame to the world frame.\n", + "\n", + "To do this:\n", + "- We check whether a landmark has already been initialized in `initial_estimates`.\n", + "- If it hasn't, we retrieve the pose of the observing camera and apply a transformation from the camera frame to the world frame using `transformFrom()`.\n", + "- We then insert the transformed landmark point into the initial estimate under its corresponding symbolic key.\n", + "\n", + "Each landmark is initialized only once, using the pose from its first observation." + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [], + "source": [ + "# Provide an initial guess for each unique landmark in world coordinates\n", + "for entry in data_matrix:\n", + "\tlandmark_id = int(entry[1])\n", + "\tif initial_estimates.exists(L(landmark_id)):\n", + "\t\tcontinue\t# Skip this landmark if already initialized\n", + "\n", + "\tpose_id = int(entry[0])\n", + "\tland_X, land_Y, land_Z\t= entry[5:8]\n", + "\n", + "\tcam_pose = initial_estimates.atPose3(X(pose_id))\t# Get pose of observing camera\n", + "\tworld_point = cam_pose.transformFrom(\t\t\t\t# Convert from camera frame to world frame\n", + "\t\tgtsam.Point3(land_X, land_Y, land_Z)\n", + "\t)\n", + "\tinitial_estimates.insert(L(landmark_id), world_point)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 7. Fix the First Pose to Anchor the World Frame\n", + "Before running optimization, we fix the very first camera pose to anchor the entire system in space. Without this constraint, the entire solution would be underdetermined up to a rigid-body transformation, meaning the optimizer could slide or rotate all poses and landmarks arbitrarily while still minimizing the objective function. \n", + "\n", + "Intuitively, this step establishes a reference origin for the map of the environment we're trying to build, pinning it down so that all subsequent positions are expressed relative to that origin. As an analogy, this is much like specifying an initial condition when solving a differential equation as we need to fix a starting point in order to recover a particular solution.\n", + "\n", + "To enforce this constraint, we add a `NonlinearEqualityPose3` factor to the graph. It ensures that the first pose, `X(1)`, remains exactly equal to its initial estimate and does not change during optimization. This convention is common in SLAM and structure-form-motion systems to eliminate gauge freedom and define a fixed global frame." + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [], + "source": [ + "# Fix the first pose to serve as the world frame origin\n", + "first_pose = initial_estimates.atPose3(X(1))\n", + "graph.add(gtsam.NonlinearEqualityPose3(X(1), first_pose))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 8. Optimize the Factor Graph with Levenberg-Marquardt\n", + "\n", + "With the factor graph fully constructed and initial values provided for all variables, we now run nonlinear optimization to compute the most probable configuration of camera poses and landmarks. GTSAM uses the Levenberg-Marquardt algorithm, a robust and widely used solver that blends the Gauss-Newton method with gradient descent to handle nonlinearity and poor initial guesses.\n", + "\n", + "We configure the optimizer using a `LevenbergMarquardtParams` object. One optional parameter we set here is the variable elimination ordering strategy, which influences how the underlying linear system is solved during optimization. We use `\"METIS\"`, a graph partitioning strategy from the METIS software package that often improves performance by reducing fill-in during matrix factorization. While this step is not strictly necessary for small problems, it becomes valuable in larger graphs.\n", + "\n", + "Once the optimizer runs, it returns a new `Values` object containing the optimized pose and landmark estimates. This step may take several seconds depending on the size of the graph." + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [], + "source": [ + "# Set up optimizer with optional METIS ordering strategy\n", + "params = gtsam.LevenbergMarquardtParams()\n", + "params.setOrderingType(\"METIS\")\n", + "\n", + "# Optimize the factor graph to compute maximum posterior estimates\n", + "optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial_estimates, params)\n", + "result = optimizer.optimize()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 9. Analyze the Results\n", + "\n", + "With optimization complete, we now examine the quality of the resulting map and trajectory. A key benefit of using factor graphs and nonlinear optimization is that we can recover a globally consistent trajectory and landmark map even when the initial estimates are noisy or imprecise.\n", + "\n", + "In this last section, we extract and visualize both:\n", + "- The initial estimates of poses and landmarks prior to optimization.\n", + "- The optimized result returned by the Levenberg-Marquardt optimizer.\n", + "\n", + "To highlight the improvement, we plot both sets side-by-side in a single interactive 3D view. The viewer can rotate, zoom, and pan to inspect the geometry from different perspectives." + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": { + "tags": [ + "hide-input" + ] + }, + "outputs": [ + { + "data": { + "application/vnd.plotly.v1+json": { + "config": { + "plotlyServerURL": "https://plot.ly" + }, + "data": [ + { + "line": { + "color": "lightgray", + "dash": "dash", + "width": 2 + }, + "marker": { + "color": "black", + "size": 2 + }, + "mode": "lines+markers", + "name": "Initial Trajectory", + "type": "scatter3d", + "x": { + "bdata": "AAAAAAAAAAAhFVLAbr9pP+UTiXQF/GY/NeZ9NWoycT8nVl/AP2N+P9GIgOB9l3o/nJAx0uaTYD8FPz/Gu6drv11NAd1VF4G/uNOM+0W/jL8PhpVl4xygv+qKY24In6O/Cty6m6c6qL+NNRJXhFGvv1mv2BXpNLO/0SbiCK3itr+Osn4zMV28v9zz/GmjOsG/3c8pyM9GxL/l8EknEkzHv27gDtQpj8q/btxifm5ozr8fLjnulA7RvxsRjINLx9K/l4xjJHuE1L9DIJc48kDWvw==", + "dtype": "f8" + }, + "y": { + "bdata": "AAAAAAAAAAD7tMSpWvtwP1+xyKeuGYQ/v/lozH+jiD90FNZ8S++RPye+2lGco5Y/oRVzay0nnD/nsFZIVAOgPyF3EaYol6I/6qy7HvHQpD+qFzINebqpPzI476QqErA/mILaFDTSsT9LdmwE4nWzPwm+DkF6L7U/p9vIK8avtj/VzjC1pQ64P3fBO1SuS7g/KsGHt3MGuT8prir7rgi6P2DpfHiWILs/G7luSnmtvD/QCgxZ3eq9P9QrZRniWL8/Vb5nJEIjwD9cIazGEtbAPw==", + "dtype": "f8" + }, + "z": { + "bdata": "AAAAAAAAAADyDBr6J7juPxDM0eP3tv4/zzEge737BkBJnYAmwoYOQH2R0JZzCRNALA5nfjXHFkD5MeauJYQaQMIv9fOmQh5AGyrG+ZsAIUAaNPRPcOEiQDqSy39IvyRAEFg5tMiWJkC0WfW52mooQLPqc7UVOypACRueXikLLECzDHGsi9stQEHxY8xdqy9Asi5uowG8MEBRa5p3nKIxQNlfdk8ehjJAnMQgsHJoM0BfmEwVjEo0QF5LyAc9KzVACmgibHgKNkAsZRniWOc2QA==", + "dtype": "f8" + } + }, + { + "line": { + "color": "blue", + "width": 2 + }, + "marker": { + "color": "blue", + "size": 2 + }, + "mode": "lines+markers", + "name": "Optimized Trajectory", + "type": "scatter3d", + "x": { + "bdata": "AAAAAAAAAAB5IWUIYOJkP7fsvDu7Y1I/VSp9BjDoVD++hn3FMrtpPzW9wEfsY1Q/iIvk3mJwcr9MAzrBRqWJv0SmP/IV45O/XWzr2er3mr+CbC4k1kWmv8yfPLM4lKm/PgyClHyWrb+SkpeoXPWxv2eibCuj8bS/1RPEGB88uL+6ctcKsyK9v6EbK1P/jcG/Pgtlib1/xL+PWAaRZlTHvzSgkI/XTsq/JWKC8TXSzb9mwSkAOpDQv0eo8U8MJ9K/Zy25bEHH07/edrPl7mbVvw==", + "dtype": "f8" + }, + "y": { + "bdata": "AAAAAAAAAACVcGj0IJ5xPwnu15aYQoQ/Rsjvb/MDiD8DRx+LHBeRPyupk9dkg5U/nQ1NWpuRmj9idIoee7SdP3a3UhJDAqE/oI8XWqotoz/uPYPb8/6nPwtgTd8+Za4/CrLzknb6sD9BB426iUiyP+qAINTA0bM/0zzHDAFitT9MNZIe35e2P+eUO5/OprY/rSGLdGOutz8H8zgYuA+5P9GMG9N7+bk/cTll3TJruz8eGdBW7rK8P7RlggzI5b0//BI3W1aKvj8JL/qhBfa/Pw==", + "dtype": "f8" + }, + "z": { + "bdata": "AAAAAAAAAADezpNKkbHuP4wrJrC2r/4/GGFPcp/5BkDtAx03b4IOQGRS7cPxBRNAzcokr/PDFkAcFYQt04EaQKLQBCQ1Ph5A/fkLx4H8IEB0+wn/B9oiQI7ugLwWtSRAZ0/W8MKLJkD2EBbmMF8oQHjUCenKLypAo5nQrVYALEAvwmvha9EtQJNTy6A3ny9AXIaHVhS2MEDDfWUfOZwxQOYNACwGgDJA3fvYI05iM0DH9akZQ0Q0QOJLoIKgJDVA7rYKZhoDNkDKmVl+wN82QA==", + "dtype": "f8" + } + }, + { + "marker": { + "color": "black", + "opacity": 0.5, + "size": 2 + }, + "mode": "markers", + "name": "Initial Landmarks", + "type": "scatter3d", + "x": { + "bdata": "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", + "dtype": "f8" + }, + "y": { + "bdata": "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", + "dtype": "f8" + }, + "z": { + "bdata": "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", + "dtype": "f8" + } + }, + { + "marker": { + "color": "orange", + "size": 2 + }, + "mode": "markers", + "name": "Optimized Landmarks", + "type": "scatter3d", + "x": { + "bdata": "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", + "dtype": "f8" + }, + "y": { + "bdata": "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", + "dtype": "f8" + }, + "z": { + "bdata": "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", + "dtype": "f8" + } + } + ], + "layout": { + "legend": { + "x": 0, + "y": 1 + }, + "margin": { + "b": 0, + "l": 0, + "r": 0, + "t": 30 + }, + "scene": { + "aspectmode": "data", + "camera": { + "center": { + "x": 0, + "y": 0.1, + "z": 0 + }, + "eye": { + "x": -1, + "y": -1, + "z": -1 + }, + "up": { + "x": 0, + "y": -1, + "z": 0 + } + }, + "xaxis": { + "title": { + "text": "X" + } + }, + "yaxis": { + "title": { + "text": "Y" + } + }, + "zaxis": { + "title": { + "text": "Z" + } + } + }, + "template": { + "data": { + "bar": [ + { + "error_x": { + "color": "#2a3f5f" + }, + "error_y": { + "color": "#2a3f5f" + }, + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "baxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "type": "carpet" + } + ], + "choropleth": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "choropleth" + } + ], + "contour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "contour" + } + ], + "contourcarpet": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "contourcarpet" + } + ], + "heatmap": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "heatmap" + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "histogram2d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2d" + } + ], + "histogram2dcontour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2dcontour" + } + ], + "mesh3d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "mesh3d" + } + ], + "parcoords": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "parcoords" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ], + "scatter": [ + { + "fillpattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + }, + "type": "scatter" + } + ], + "scatter3d": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatter3d" + } + ], + "scattercarpet": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattercarpet" + } + ], + "scattergeo": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergeo" + } + ], + "scattergl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergl" + } + ], + "scattermap": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattermap" + } + ], + "scattermapbox": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattermapbox" + } + ], + "scatterpolar": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolar" + } + ], + "scatterpolargl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolargl" + } + ], + "scatterternary": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterternary" + } + ], + "surface": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "surface" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#EBF0F8" + }, + "line": { + "color": "white" + } + }, + "header": { + "fill": { + "color": "#C8D4E3" + }, + "line": { + "color": "white" + } + }, + "type": "table" + } + ] + }, + "layout": { + "annotationdefaults": { + "arrowcolor": "#2a3f5f", + "arrowhead": 0, + "arrowwidth": 1 + }, + "autotypenumbers": "strict", + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ], + "sequential": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ] + }, + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#2a3f5f" + }, + "geo": { + "bgcolor": "white", + "lakecolor": "white", + "landcolor": "#E5ECF6", + "showlakes": true, + "showland": true, + "subunitcolor": "white" + }, + "hoverlabel": { + "align": "left" + }, + "hovermode": "closest", + "mapbox": { + "style": "light" + }, + "paper_bgcolor": "white", + "plot_bgcolor": "#E5ECF6", + "polar": { + "angularaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "radialaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "scene": { + "xaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "yaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "zaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + } + }, + "shapedefaults": { + "line": { + "color": "#2a3f5f" + } + }, + "ternary": { + "aaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "baxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "caxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "title": { + "x": 0.05 + }, + "xaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + }, + "yaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + } + } + }, + "title": { + "text": "SLAM Result: Initial vs Optimized Estimates" + } + } + } + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Function to extract camera coordinates and put them in an N x 3 matrix\n", + "def extract_camera_xyz(values: gtsam.Values, prefix='x'):\n", + " coords = []\n", + " for key in values.keys():\n", + " symbol = gtsam.Symbol(key)\n", + " if symbol.chr() == ord(prefix):\n", + " coords.append(values.atPose3(key).translation())\n", + " return np.array([p for p in coords])\n", + "\n", + "# Function to extract landmark coordinates and put them in an N x 3 matrix\n", + "def extract_landmark_xyz(values: gtsam.Values, prefix='l'):\n", + " coords = []\n", + " for key in values.keys():\n", + " symbol = gtsam.Symbol(key)\n", + " if symbol.chr() == ord(prefix):\n", + " coords.append(values.atPoint3(key))\n", + " return np.array([p for p in coords])\n", + "\n", + "# Extract both initial and optimized estimates\n", + "init_cam = extract_camera_xyz(initial_estimates)\n", + "opt_cam = extract_camera_xyz(result)\n", + "init_land = extract_landmark_xyz(initial_estimates)\n", + "opt_land = extract_landmark_xyz(result)\n", + "\n", + "# Define traces\n", + "trace_init_cam = go.Scatter3d(\n", + " x=init_cam[:, 0], y=init_cam[:, 1], z=init_cam[:, 2],\n", + " mode=\"lines+markers\",\n", + " name=\"Initial Trajectory\",\n", + " line=dict(color=\"lightgray\", width=2, dash=\"dash\"),\n", + " marker=dict(size=2, color=\"black\")\n", + ")\n", + "\n", + "trace_opt_cam = go.Scatter3d(\n", + " x=opt_cam[:, 0], y=opt_cam[:, 1], z=opt_cam[:, 2],\n", + " mode=\"lines+markers\",\n", + " name=\"Optimized Trajectory\",\n", + " line=dict(color=\"blue\", width=2),\n", + " marker=dict(size=2, color=\"blue\")\n", + ")\n", + "\n", + "scatter_init_land = go.Scatter3d(\n", + " x=init_land[:, 0], y=init_land[:, 1], z=init_land[:, 2],\n", + " mode=\"markers\",\n", + " name=\"Initial Landmarks\",\n", + " marker=dict(size=2, color=\"black\", opacity=0.5)\n", + ")\n", + "\n", + "scatter_opt_land = go.Scatter3d(\n", + " x=opt_land[:, 0], y=opt_land[:, 1], z=opt_land[:, 2],\n", + " mode=\"markers\",\n", + " name=\"Optimized Landmarks\",\n", + " marker=dict(size=2, color=\"orange\")\n", + ")\n", + "\n", + "# Assemble the figure\n", + "fig = go.Figure(data=[trace_init_cam, trace_opt_cam, scatter_init_land, scatter_opt_land])\n", + "\n", + "fig.update_layout(\n", + " title=\"SLAM Result: Initial vs Optimized Estimates\",\n", + " scene=dict(\n", + " xaxis_title='X',\n", + " yaxis_title='Y',\n", + " zaxis_title='Z',\n", + " aspectmode='data',\n", + " camera=dict(\n", + " up=dict(x=0, y=-1, z=0),\n", + " center=dict(x=0, y=0.1, z=0),\n", + " eye=dict(x=-1, y=-1, z=-1)\n", + "\t\t)\n", + "\t),\n", + " legend=dict(x=0, y=1),\n", + " margin=dict(l=0, r=0, b=0, t=30)\n", + ")\n", + "\n", + "fig.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "While the visual difference between the initial and optimized trajectory may be subtle, especially in a controlled, hallway-like environment in the case of this example, we can still measure the effectiveness of optimization quantitatively.\n", + "\n", + "GTSAM provides a convenient method to evaluate the total error of the factor graph under any estimate. This cost represents the sum of squared Mahalanobis distances between the predicted and actual measurements over all factors in the graph. By computing this cost both before and after optimization, we gain a numerical understanding of how well the optimizer has improved the estimate, even in cases where the visual improvement is minor." + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": { + "tags": [ + "hide-input" + ] + }, + "outputs": [ + { + "data": { + "application/vnd.plotly.v1+json": { + "config": { + "plotlyServerURL": "https://plot.ly" + }, + "data": [ + { + "marker": { + "color": "gray" + }, + "name": "Initial Estimate", + "type": "bar", + "x": [ + "Initial" + ], + "y": [ + 14538.70640735373 + ] + }, + { + "marker": { + "color": "blue" + }, + "name": "Optimized Result", + "type": "bar", + "x": [ + "Optimized" + ], + "y": [ + 1577.0301094720978 + ] + } + ], + "layout": { + "bargap": 0.4, + "showlegend": true, + "template": { + "data": { + "bar": [ + { + "error_x": { + "color": "#2a3f5f" + }, + "error_y": { + "color": "#2a3f5f" + }, + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "baxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "type": "carpet" + } + ], + "choropleth": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "choropleth" + } + ], + "contour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "contour" + } + ], + "contourcarpet": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "contourcarpet" + } + ], + "heatmap": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "heatmap" + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "histogram2d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2d" + } + ], + "histogram2dcontour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2dcontour" + } + ], + "mesh3d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "mesh3d" + } + ], + "parcoords": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "parcoords" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ], + "scatter": [ + { + "fillpattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + }, + "type": "scatter" + } + ], + "scatter3d": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatter3d" + } + ], + "scattercarpet": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattercarpet" + } + ], + "scattergeo": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergeo" + } + ], + "scattergl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergl" + } + ], + "scattermap": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattermap" + } + ], + "scattermapbox": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattermapbox" + } + ], + "scatterpolar": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolar" + } + ], + "scatterpolargl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolargl" + } + ], + "scatterternary": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterternary" + } + ], + "surface": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "surface" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#EBF0F8" + }, + "line": { + "color": "white" + } + }, + "header": { + "fill": { + "color": "#C8D4E3" + }, + "line": { + "color": "white" + } + }, + "type": "table" + } + ] + }, + "layout": { + "annotationdefaults": { + "arrowcolor": "#2a3f5f", + "arrowhead": 0, + "arrowwidth": 1 + }, + "autotypenumbers": "strict", + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ], + "sequential": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ] + }, + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#2a3f5f" + }, + "geo": { + "bgcolor": "white", + "lakecolor": "white", + "landcolor": "#E5ECF6", + "showlakes": true, + "showland": true, + "subunitcolor": "white" + }, + "hoverlabel": { + "align": "left" + }, + "hovermode": "closest", + "mapbox": { + "style": "light" + }, + "paper_bgcolor": "white", + "plot_bgcolor": "#E5ECF6", + "polar": { + "angularaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "radialaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "scene": { + "xaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "yaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "zaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + } + }, + "shapedefaults": { + "line": { + "color": "#2a3f5f" + } + }, + "ternary": { + "aaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "baxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "caxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "title": { + "x": 0.05 + }, + "xaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + }, + "yaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + } + } + }, + "title": { + "text": "Total Graph Error: Initial vs. Optimized" + }, + "yaxis": { + "title": { + "text": "Total Error (sum of squared residuals)" + } + } + } + } + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Compute total error (cost) before and after optimization\n", + "init_cost = graph.error(initial_estimates)\n", + "opt_cost = graph.error(result)\n", + "\n", + "fig_cost = go.Figure(data=[\n", + " go.Bar(name=\"Initial Estimate\", x=[\"Initial\"], y=[init_cost], marker_color=\"gray\"),\n", + " go.Bar(name=\"Optimized Result\", x=[\"Optimized\"], y=[opt_cost], marker_color=\"blue\")\n", + "])\n", + "\n", + "fig_cost.update_layout(\n", + " title=\"Total Graph Error: Initial vs. Optimized\",\n", + " yaxis_title=\"Total Error (sum of squared residuals)\",\n", + " bargap=0.4,\n", + " showlegend=True\n", + ")\n", + "\n", + "fig_cost.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "base", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.10" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +}