diff --git a/gtsam/basis/basis.md b/gtsam/basis/basis.md
new file mode 100644
index 0000000000..7a22ad2b4f
--- /dev/null
+++ b/gtsam/basis/basis.md
@@ -0,0 +1,66 @@
+# Basis
+
+The `basis` module provides tools for representing continuous functions as
+linear combinations of basis functions or as values at interpolation points.
+It is useful for smooth function approximation, trajectory modeling, and
+building factors that constrain functions (or their derivatives) at specific
+points.
+
+At a high level, you choose a basis (Fourier or Chebyshev), decide whether you
+want a coefficient-based representation or a pseudo-spectral one (values at
+Chebyshev points), and then use the provided factors or fitting utilities to
+solve for parameters in GTSAM.
+
+## Getting Oriented
+
+- **Coefficient-based bases**: `Chebyshev1Basis`, `Chebyshev2Basis`, and
+ `FourierBasis` treat the parameters as coefficients on basis functions.
+- **Pseudo-spectral basis**: `Chebyshev2` treats the parameters as values at
+ Chebyshev points and uses barycentric interpolation.
+- **Factors**: A family of unary factors enforce function values or derivatives
+ at specific points, including vector- and manifold-valued variants.
+- **Fitting**: `FitBasis` performs least-squares regression from samples.
+
+## Core Concepts
+
+- [Basis](doc/Basis.ipynb): CRTP base class providing evaluation and derivative
+ functors, Jacobians, and common helpers.
+
+## Polynomial Bases
+
+- [Chebyshev1Basis](doc/Chebyshev1Basis.ipynb): First-kind Chebyshev basis
+ $T_n(x)$ on $[-1,1]$ (coefficient-based).
+- [Chebyshev2Basis](doc/Chebyshev2Basis.ipynb): Second-kind Chebyshev basis
+ $U_n(x)$ on $[-1,1]$ (coefficient-based).
+- [FourierBasis](doc/FourierBasis.ipynb): Real Fourier series basis for
+ periodic functions.
+
+## Pseudo-Spectral Basis
+
+- [Chebyshev2](doc/Chebyshev2.ipynb): Chebyshev points, barycentric
+ interpolation, differentiation/integration matrices, and quadrature weights.
+
+## Factors for Basis Evaluation
+
+These factors connect basis parameters to measurements of values or derivatives.
+
+- [EvaluationFactor](doc/EvaluationFactor.ipynb): Scalar value at a point.
+- [VectorEvaluationFactor](doc/VectorEvaluationFactor.ipynb): Vector value at a
+ point.
+- [VectorComponentFactor](doc/VectorComponentFactor.ipynb): Single component of
+ a vector value.
+- [ManifoldEvaluationFactor](doc/ManifoldEvaluationFactor.ipynb): Manifold-valued
+ measurement (e.g., `Rot3`, `Pose3`).
+
+## Factors for Derivative Constraints
+
+- [DerivativeFactor](doc/DerivativeFactor.ipynb): Scalar derivative at a point.
+- [VectorDerivativeFactor](doc/VectorDerivativeFactor.ipynb): Vector derivative
+ at a point.
+- [ComponentDerivativeFactor](doc/ComponentDerivativeFactor.ipynb): Single
+ component of a vector derivative.
+
+## Fitting from Data
+
+- [FitBasis](doc/FitBasis.ipynb): Build a least-squares problem from samples and
+ solve for basis parameters.
diff --git a/gtsam/basis/doc/Basis.ipynb b/gtsam/basis/doc/Basis.ipynb
new file mode 100644
index 0000000000..368906f157
--- /dev/null
+++ b/gtsam/basis/doc/Basis.ipynb
@@ -0,0 +1,155 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# Basis\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "The `Basis` class is a CRTP base class that defines common utilities for representing functions as linear combinations of basis functions. Derived classes provide `CalculateWeights` and `DerivativeWeights`, while `Basis` supplies functors and helpers for evaluation, vector-valued evaluation, and derivative computation with Jacobians with respect to parameters.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 4,
+ "id": "6775be6c",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "ce1fbbd5",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `WeightMatrix(N, X)` and `WeightMatrix(N, X, a, b)` build stacked weight matrices.\n",
+ "- `EvaluationFunctor` evaluates a scalar function at `x`.\n",
+ "- `VectorEvaluationFunctor` evaluates vector-valued functions from a parameter matrix.\n",
+ "- `VectorComponentFunctor` evaluates a single component of a vector-valued function.\n",
+ "- `ManifoldEvaluationFunctor` evaluates manifold-valued functions via local coordinates.\n",
+ "- `DerivativeFunctor`, `VectorDerivativeFunctor`, and `ComponentDerivativeFunctor` compute derivatives.\n",
+ "- `kroneckerProductIdentity` builds efficient block Jacobians for vector-valued cases.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "46f84e69",
+ "metadata": {},
+ "source": [
+ "## Derived Classes\n",
+ "\n",
+ "- `Chebyshev1Basis` (first-kind Chebyshev polynomials)\n",
+ "- `Chebyshev2Basis` (second-kind Chebyshev polynomials)\n",
+ "- `FourierBasis` (real Fourier series)\n",
+ "- `Chebyshev2` (pseudo-spectral Chebyshev points)\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "c8e177a8",
+ "metadata": {},
+ "source": [
+ "## Usage Example\n",
+ "\n",
+ "This example builds a weight matrix for a Chebyshev basis and evaluates\n",
+ "Fourier weights at a point.\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 5,
+ "id": "905a64a4",
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ "Chebyshev2 WeightMatrix shape: (5, 5)\n",
+ "First row: [1. 0. 0. 0. 0.]\n",
+ "FourierBasis weights at x=0.3: [1. 0.955 0.296 0.825 0.565]\n"
+ ]
+ }
+ ],
+ "source": [
+ "import numpy as np\n",
+ "import gtsam\n",
+ "\n",
+ "np.set_printoptions(precision=3, suppress=True)\n",
+ "\n",
+ "N = 5\n",
+ "X = np.linspace(-1.0, 1.0, 5)\n",
+ "W = gtsam.Chebyshev2.WeightMatrix(N, X)\n",
+ "print(\"Chebyshev2 WeightMatrix shape:\", np.asarray(W).shape)\n",
+ "print(\"First row:\", np.asarray(W)[0])\n",
+ "\n",
+ "x = 0.3\n",
+ "weights = gtsam.FourierBasis.CalculateWeights(N, x)\n",
+ "print(\"FourierBasis weights at x=0.3:\", np.asarray(weights).ravel())\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [Basis.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/Basis.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/Chebyshev1Basis.ipynb b/gtsam/basis/doc/Chebyshev1Basis.ipynb
new file mode 100644
index 0000000000..f117d10d2b
--- /dev/null
+++ b/gtsam/basis/doc/Chebyshev1Basis.ipynb
@@ -0,0 +1,136 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# Chebyshev1Basis\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`Chebyshev1Basis` provides the first-kind Chebyshev polynomial basis $T_n(x)$ on the interval $[-1, 1]$. Parameters are coefficients of the basis functions, making this a classic orthogonal polynomial expansion for smooth function approximation.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `CalculateWeights(N, x, a=-1, b=1)` returns the $1 \t\\times N$ basis weights.\n",
+ "- `DerivativeWeights(N, x, a=-1, b=1)` returns weights for the derivative.\n",
+ "- `WeightMatrix(N, X)` stacks weights for a vector of sample points.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "922e3685",
+ "metadata": {},
+ "source": [
+ "## Usage Example\n",
+ "\n",
+ "Evaluate first-kind Chebyshev weights at a point and build a weight\n",
+ "matrix for multiple sample points.\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 2,
+ "id": "30b37cbb",
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ "Weights at x=0.25: [ 1. 0.25 -0.875 -0.688 0.531 0.953]\n",
+ "WeightMatrix shape: (5, 6)\n",
+ "Row for x=0: [ 1. 0. -1. -0. 1. 0.]\n"
+ ]
+ }
+ ],
+ "source": [
+ "import numpy as np\n",
+ "import gtsam\n",
+ "\n",
+ "np.set_printoptions(precision=3, suppress=True)\n",
+ "\n",
+ "N = 6\n",
+ "x = 0.25\n",
+ "weights = gtsam.Chebyshev1Basis.CalculateWeights(N, x)\n",
+ "print(\"Weights at x=0.25:\", np.asarray(weights).ravel())\n",
+ "\n",
+ "X = np.linspace(-1.0, 1.0, 5)\n",
+ "W = gtsam.Chebyshev1Basis.WeightMatrix(N, X)\n",
+ "print(\"WeightMatrix shape:\", np.asarray(W).shape)\n",
+ "print(\"Row for x=0:\", np.asarray(W)[2])\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [Chebyshev.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/Chebyshev.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/Chebyshev2.ipynb b/gtsam/basis/doc/Chebyshev2.ipynb
new file mode 100644
index 0000000000..b5265faf23
--- /dev/null
+++ b/gtsam/basis/doc/Chebyshev2.ipynb
@@ -0,0 +1,139 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# Chebyshev2\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`Chebyshev2` implements a pseudo-spectral parameterization on Chebyshev points of the second kind. Instead of coefficients, the parameters are function values at Chebyshev points, and evaluation uses barycentric interpolation. The class also provides differentiation and integration matrices for spectral calculus.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `Point(N, j[, a, b])` and `Points(N[, a, b])` return Chebyshev points.\n",
+ "- `CalculateWeights(N, x[, a, b])` returns barycentric interpolation weights.\n",
+ "- `DerivativeWeights(N, x[, a, b])` returns derivative weights.\n",
+ "- `DifferentiationMatrix(N[, a, b])` and `IntegrationMatrix(N[, a, b])` provide spectral operators.\n",
+ "- `IntegrationWeights(N[, a, b])` and `DoubleIntegrationWeights(N[, a, b])` provide quadrature weights.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Usage Example\n",
+ "\n",
+ "This example inspects the Chebyshev points, interpolation weights, and\n",
+ "the differentiation matrix.\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 2,
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ "Chebyshev points: [-1. -0.901 -0.623 -0.223 0.223 0.623 0.901 1. ]\n",
+ "Interpolation weights at x=0.2: [-0.009 0.02 -0.027 0.053 0.998 -0.053 0.032 -0.014]\n",
+ "D shape: (8, 8)\n",
+ "First row of D: [-16.5 20.196 -5.312 2.572 -1.636 1.232 -1.052 0.5 ]\n"
+ ]
+ }
+ ],
+ "source": [
+ "import numpy as np\n",
+ "import gtsam\n",
+ "\n",
+ "np.set_printoptions(precision=3, suppress=True)\n",
+ "\n",
+ "N = 8\n",
+ "points = gtsam.Chebyshev2.Points(N)\n",
+ "print(\"Chebyshev points:\", np.asarray(points).ravel())\n",
+ "\n",
+ "x = 0.2\n",
+ "weights = gtsam.Chebyshev2.CalculateWeights(N, x)\n",
+ "print(\"Interpolation weights at x=0.2:\", np.asarray(weights).ravel())\n",
+ "\n",
+ "D = gtsam.Chebyshev2.DifferentiationMatrix(N)\n",
+ "print(\"D shape:\", np.asarray(D).shape)\n",
+ "print(\"First row of D:\", np.asarray(D)[0])\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [Chebyshev2.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/Chebyshev2.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/Chebyshev2Basis.ipynb b/gtsam/basis/doc/Chebyshev2Basis.ipynb
new file mode 100644
index 0000000000..fc13e57a19
--- /dev/null
+++ b/gtsam/basis/doc/Chebyshev2Basis.ipynb
@@ -0,0 +1,134 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# Chebyshev2Basis\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`Chebyshev2Basis` provides the second-kind Chebyshev polynomial basis $U_n(x)$ on $[-1, 1]$. It is related to derivatives of first-kind polynomials and is useful when expressing functions directly in a basis of $U_n(x)$ polynomials.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `CalculateWeights(N, x, a=-1, b=1)` returns basis weights.\n",
+ "- `DerivativeWeights(N, x, a=-1, b=1)` returns derivative weights.\n",
+ "- `WeightMatrix(N, X)` stacks weights for a vector of sample points.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Usage Example\n",
+ "\n",
+ "Evaluate second-kind Chebyshev weights and build a weight matrix for\n",
+ "multiple sample points.\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 2,
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ "Weights at x=-0.3: [ 1. -0.6 -0.64 0.984 0.05 -1.014]\n",
+ "WeightMatrix shape: (5, 6)\n",
+ "Row for x=0: [ 1. 0. -1. -0. 1. 0.]\n"
+ ]
+ }
+ ],
+ "source": [
+ "import numpy as np\n",
+ "import gtsam\n",
+ "\n",
+ "np.set_printoptions(precision=3, suppress=True)\n",
+ "\n",
+ "N = 6\n",
+ "x = -0.3\n",
+ "weights = gtsam.Chebyshev2Basis.CalculateWeights(N, x)\n",
+ "print(\"Weights at x=-0.3:\", np.asarray(weights).ravel())\n",
+ "\n",
+ "X = np.linspace(-1.0, 1.0, 5)\n",
+ "W = gtsam.Chebyshev2Basis.WeightMatrix(N, X)\n",
+ "print(\"WeightMatrix shape:\", np.asarray(W).shape)\n",
+ "print(\"Row for x=0:\", np.asarray(W)[2])\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [Chebyshev.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/Chebyshev.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/ComponentDerivativeFactor.ipynb b/gtsam/basis/doc/ComponentDerivativeFactor.ipynb
new file mode 100644
index 0000000000..537823b62b
--- /dev/null
+++ b/gtsam/basis/doc/ComponentDerivativeFactor.ipynb
@@ -0,0 +1,134 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# ComponentDerivativeFactor\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`ComponentDerivativeFactor` is a unary factor that constrains the derivative of a single component of a vector-valued basis function at a given point.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `ComponentDerivativeFactor(key, z, model, P, N, i, x)` constrains component `i` of $\\mathbf{f}'(x)$.\n",
+ "- Optional interval parameters `a, b` scale the basis domain.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## C++ Usage Example\n",
+ "```cpp\n",
+ "auto model = gtsam::noiseModel::Isotropic::Sigma(1, 0.05);\n",
+ "size_t P = 3, N = 6, i = 2;\n",
+ "double x = 0.2;\n",
+ "double z = 0.0;\n",
+ "gtsam::ComponentDerivativeFactor factor(key, z, model, P, N, i, x);\n",
+ "```\n",
+ "\n",
+ "## Python Usage Example"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ " keys = { c0 }\n",
+ "isotropic dim=1 sigma=0.05\n",
+ "FunctorizedFactor(c0)\n",
+ " measurement: 0\n",
+ " noise model sigmas: 0.05\n",
+ "\n"
+ ]
+ }
+ ],
+ "source": [
+ "import gtsam\n",
+ "\n",
+ "model = gtsam.noiseModel.Isotropic.Sigma(1, 0.05)\n",
+ "key = gtsam.symbol(\"c\", 0)\n",
+ "factor = gtsam.ComponentDerivativeFactorChebyshev2(key, 0.0, model, 3, 6, 2, 0.2)\n",
+ "print(factor)"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [BasisFactors.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/BasisFactors.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/DerivativeFactor.ipynb b/gtsam/basis/doc/DerivativeFactor.ipynb
new file mode 100644
index 0000000000..35f2b4644a
--- /dev/null
+++ b/gtsam/basis/doc/DerivativeFactor.ipynb
@@ -0,0 +1,136 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# DerivativeFactor\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`DerivativeFactor` is a unary factor that enforces a scalar measurement of the derivative of a basis function at a given point.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `DerivativeFactor(key, z, model, N, x)` constrains $f'(x)$ to measurement `z`.\n",
+ "- Optional interval parameters `a, b` scale the basis domain.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## C++ Usage Example\n",
+ "\n",
+ "```cpp\n",
+ "auto model = gtsam::noiseModel::Isotropic::Sigma(1, 0.05);\n",
+ "size_t N = 8;\n",
+ "double x = -0.3;\n",
+ "double z = 0.0;\n",
+ "gtsam::DerivativeFactor factor(key, z, model, N, x);\n",
+ "\n",
+ "```\n",
+ "\n",
+ "## Python Usage Example"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 3,
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ " keys = { c0 }\n",
+ "isotropic dim=1 sigma=0.05\n",
+ "FunctorizedFactor(c0)\n",
+ " measurement: 0\n",
+ " noise model sigmas: 0.05\n",
+ "\n"
+ ]
+ }
+ ],
+ "source": [
+ "import gtsam\n",
+ "\n",
+ "model = gtsam.noiseModel.Isotropic.Sigma(1, 0.05)\n",
+ "key = gtsam.symbol('c', 0)\n",
+ "factor = gtsam.DerivativeFactorChebyshev2(key, 0.0, model, 8, -0.3)\n",
+ "print(factor)\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [BasisFactors.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/BasisFactors.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/EvaluationFactor.ipynb b/gtsam/basis/doc/EvaluationFactor.ipynb
new file mode 100644
index 0000000000..2e49b1e54c
--- /dev/null
+++ b/gtsam/basis/doc/EvaluationFactor.ipynb
@@ -0,0 +1,135 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# EvaluationFactor\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`EvaluationFactor` is a unary factor that enforces a scalar measurement of a basis function at a given point. It is commonly used with pseudo-spectral bases to constrain function values directly.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `EvaluationFactor(key, z, model, N, x)` constrains $f(x)$ to measurement `z`.\n",
+ "- Optional interval parameters `a, b` scale the basis domain.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## C++ Usage Example\n",
+ "\n",
+ "```cpp\n",
+ "auto model = gtsam::noiseModel::Isotropic::Sigma(1, 0.05);\n",
+ "size_t N = 8;\n",
+ "double x = 0.25;\n",
+ "double z = 1.2;\n",
+ "gtsam::EvaluationFactor factor(key, z, model, N, x);\n",
+ "```\n",
+ "\n",
+ "## Python Usage Example"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ " keys = { c0 }\n",
+ "isotropic dim=1 sigma=0.05\n",
+ "FunctorizedFactor(c0)\n",
+ " measurement: 1.2\n",
+ " noise model sigmas: 0.05\n",
+ "\n"
+ ]
+ }
+ ],
+ "source": [
+ "import gtsam\n",
+ "\n",
+ "key = gtsam.symbol('c', 0)\n",
+ "model = gtsam.noiseModel.Isotropic.Sigma(1, 0.05)\n",
+ "factor = gtsam.EvaluationFactorChebyshev2(key, 1.2, model, 8, 0.25)\n",
+ "print(factor)"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [BasisFactors.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/BasisFactors.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/FitBasis.ipynb b/gtsam/basis/doc/FitBasis.ipynb
new file mode 100644
index 0000000000..a6a14f7371
--- /dev/null
+++ b/gtsam/basis/doc/FitBasis.ipynb
@@ -0,0 +1,136 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# FitBasis\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`FitBasis` performs least-squares regression to fit a basis function to sample data. It builds a factor graph from samples and solves for basis parameters that best explain the data under a Gaussian noise model.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `FitBasis(sequence, model, N)` constructs and solves the least-squares problem.\n",
+ "- `parameters()` returns the fitted parameter vector.\n",
+ "- `NonlinearGraph(...)` and `LinearGraph(...)` expose intermediate graphs.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## C++ Usage Example\n",
+ "\n",
+ "```cpp\n",
+ "std::map samples = {{0.0, 1.0}, {0.5, 0.2}, {1.0, -0.1}};\n",
+ "auto model = gtsam::noiseModel::Isotropic::Sigma(1, 0.1);\n",
+ "size_t N = 5;\n",
+ "gtsam::FitBasis fit(samples, model, N);\n",
+ "gtsam::Vector params = fit.parameters();\n",
+ "\n",
+ "```\n",
+ "\n",
+ "## Python Example"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 4,
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ "FitBasisFourierBasis parameters: [ 2.242 -1.242 -1.986]\n"
+ ]
+ }
+ ],
+ "source": [
+ "import numpy as np\n",
+ "import gtsam\n",
+ "\n",
+ "np.set_printoptions(precision=3, suppress=True)\n",
+ "\n",
+ "sequence = {0.0: 1.0, 0.5: 0.2, 1.0: -0.1}\n",
+ "model = gtsam.noiseModel.Isotropic.Sigma(1, 0.1)\n",
+ "fit = gtsam.FitBasisFourierBasis(sequence, model, 3)\n",
+ "params = fit.parameters()\n",
+ "print(\"FitBasisFourierBasis parameters:\", params)"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [FitBasis.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/FitBasis.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/FourierBasis.ipynb b/gtsam/basis/doc/FourierBasis.ipynb
new file mode 100644
index 0000000000..e4acd181a2
--- /dev/null
+++ b/gtsam/basis/doc/FourierBasis.ipynb
@@ -0,0 +1,135 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# FourierBasis\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`FourierBasis` provides a real Fourier series basis for periodic functions. The basis is ordered as $[1, \\cos(x), \\sin(x), \\cos(2x), \\sin(2x), \\ldots]$, making it convenient for truncated Fourier expansions and their derivatives.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `CalculateWeights(N, x)` returns the real Fourier basis weights.\n",
+ "- `DifferentiationMatrix(N)` returns the linear operator for derivatives.\n",
+ "- `DerivativeWeights(N, x)` returns weights that evaluate the derivative at `x`.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Usage Example\n",
+ "\n",
+ "Evaluate a real Fourier basis, its derivative weights, and a slice of\n",
+ "the differentiation matrix.\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 3,
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ "Weights: [ 1. 0.362 0.932 -0.737 0.675 -0.897 -0.443]\n",
+ "Derivative weights: [ 0. -0.932 0.362 -1.351 -1.475 1.328 -2.69 ]\n",
+ "D[1:3, 1:3]: [[ 0. 1.]\n",
+ " [-1. 0.]]\n"
+ ]
+ }
+ ],
+ "source": [
+ "import numpy as np\n",
+ "import gtsam\n",
+ "\n",
+ "np.set_printoptions(precision=3, suppress=True)\n",
+ "\n",
+ "N = 7\n",
+ "x = 1.2\n",
+ "weights = gtsam.FourierBasis.CalculateWeights(N, x)\n",
+ "dweights = gtsam.FourierBasis.DerivativeWeights(N, x)\n",
+ "D = gtsam.FourierBasis.DifferentiationMatrix(N)\n",
+ "\n",
+ "print(\"Weights:\", np.asarray(weights).ravel())\n",
+ "print(\"Derivative weights:\", np.asarray(dweights).ravel())\n",
+ "print(\"D[1:3, 1:3]:\", np.asarray(D)[1:3, 1:3])"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [Fourier.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/Fourier.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/ManifoldEvaluationFactor.ipynb b/gtsam/basis/doc/ManifoldEvaluationFactor.ipynb
new file mode 100644
index 0000000000..e4762a7179
--- /dev/null
+++ b/gtsam/basis/doc/ManifoldEvaluationFactor.ipynb
@@ -0,0 +1,181 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# ManifoldEvaluationFactor\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`ManifoldEvaluationFactor` is a unary factor for manifold-valued measurements such as `Rot2`, `Rot3`, `Pose2`, or `Pose3`. It evaluates a vector-valued basis and compares the result in local coordinates on the manifold.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `ManifoldEvaluationFactor(key, z, model, N, x)` constrains the manifold value at `x`.\n",
+ "- Optional interval parameters `a, b` scale the basis domain.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## C++ example\n",
+ "\n",
+ "```cpp\n",
+ "auto model = gtsam::noiseModel::Isotropic::Sigma(3, 0.05);\n",
+ "size_t N = 6;\n",
+ "double x = 0.1;\n",
+ "gtsam::Rot3 z = gtsam::Rot3::RzRyRx(0.1, 0.2, 0.3);\n",
+ "gtsam::ManifoldEvaluationFactor factor(key, z, model, N, x);\n",
+ "```\n",
+ "\n",
+ "## Python Example"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 2,
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ "Available ManifoldEvaluationFactor wrappers:\n",
+ " ManifoldEvaluationFactorChebyshev1BasisPose2\n",
+ " ManifoldEvaluationFactorChebyshev1BasisPose3\n",
+ " ManifoldEvaluationFactorChebyshev1BasisRot2\n",
+ " ManifoldEvaluationFactorChebyshev1BasisRot3\n",
+ " ManifoldEvaluationFactorChebyshev2BasisPose2\n",
+ " ManifoldEvaluationFactorChebyshev2BasisPose3\n",
+ " ManifoldEvaluationFactorChebyshev2BasisRot2\n",
+ " ManifoldEvaluationFactorChebyshev2BasisRot3\n",
+ " ManifoldEvaluationFactorChebyshev2Pose2\n",
+ " ManifoldEvaluationFactorChebyshev2Pose3\n",
+ " ManifoldEvaluationFactorChebyshev2Rot2\n",
+ " ManifoldEvaluationFactorChebyshev2Rot3\n",
+ " ManifoldEvaluationFactorFourierBasisPose2\n",
+ " ManifoldEvaluationFactorFourierBasisPose3\n",
+ " ManifoldEvaluationFactorFourierBasisRot2\n",
+ " ManifoldEvaluationFactorFourierBasisRot3\n",
+ "Created ManifoldEvaluationFactorChebyshev1BasisRot2 with dim 1\n",
+ "Created ManifoldEvaluationFactorChebyshev1BasisPose2 with dim 3\n",
+ "Created ManifoldEvaluationFactorChebyshev1BasisRot3 with dim 3\n",
+ "Created ManifoldEvaluationFactorChebyshev1BasisPose3 with dim 6\n"
+ ]
+ }
+ ],
+ "source": [
+ "import numpy as np\n",
+ "import gtsam\n",
+ "\n",
+ "names = [n for n in dir(gtsam) if n.startswith(\"ManifoldEvaluationFactor\")]\n",
+ "print(\"Available ManifoldEvaluationFactor wrappers:\")\n",
+ "for name in names:\n",
+ " print(\" \", name)\n",
+ "\n",
+ "selected = None\n",
+ "kind = None\n",
+ "for preferred in [\"Rot2\", \"Pose2\", \"Rot3\", \"Pose3\"]:\n",
+ " for name in names:\n",
+ " if preferred in name:\n",
+ " selected = name\n",
+ " kind = preferred\n",
+ " break\n",
+ " if selected is None:\n",
+ " print(\"No ManifoldEvaluationFactor wrapper found; skipping execution.\")\n",
+ " else:\n",
+ " cls = getattr(gtsam, selected)\n",
+ " if kind == \"Rot2\":\n",
+ " z = gtsam.Rot2(0.3)\n",
+ " dim = 1\n",
+ " elif kind == \"Rot3\":\n",
+ " z = gtsam.Rot3.RzRyRx(0.1, 0.2, 0.3)\n",
+ " dim = 3\n",
+ " elif kind == \"Pose2\":\n",
+ " z = gtsam.Pose2(1.0, 0.0, 0.1)\n",
+ " dim = 3\n",
+ " else:\n",
+ " z = gtsam.Pose3(gtsam.Rot3.RzRyRx(0.1, 0.2, 0.3), np.array([1.0, 0.0, 0.0]))\n",
+ " dim = 6\n",
+ "\n",
+ " model = gtsam.noiseModel.Isotropic.Sigma(dim, 0.1)\n",
+ " key = gtsam.symbol('x', 0)\n",
+ " factor = cls(key, z, model, 6, 0.1)\n",
+ " print(f\"Created {selected} with dim {factor.dim()}\")\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [BasisFactors.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/BasisFactors.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/VectorComponentFactor.ipynb b/gtsam/basis/doc/VectorComponentFactor.ipynb
new file mode 100644
index 0000000000..91d678d64a
--- /dev/null
+++ b/gtsam/basis/doc/VectorComponentFactor.ipynb
@@ -0,0 +1,153 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# VectorComponentFactor\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`VectorComponentFactor` is a unary factor that constrains a single component of a vector-valued basis function at a given point. It is useful when only one component is observed.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `VectorComponentFactor(key, z, model, P, N, i, x)` constrains component `i`.\n",
+ "- Optional interval parameters `a, b` scale the basis domain.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## C++ Usage Example\n",
+ "\n",
+ "```cpp\n",
+ "auto model = gtsam::noiseModel::Isotropic::Sigma(1, 0.1);\n",
+ "size_t P = 3, N = 6, i = 1;\n",
+ "double x = 0.5;\n",
+ "double z = -0.2;\n",
+ "gtsam::VectorComponentFactor factor(key, z, model, P, N, i, x);\n",
+ "```\n",
+ "\n",
+ "## Python Example"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 4,
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ "VectorComponentFactor wrappers:\n",
+ " VectorComponentFactorChebyshev1Basis\n",
+ " VectorComponentFactorChebyshev2\n",
+ " VectorComponentFactorChebyshev2Basis\n",
+ " VectorComponentFactorFourierBasis\n",
+ "Created VectorComponentFactorChebyshev1Basis with dim 1\n",
+ "Created VectorComponentFactorChebyshev2 with dim 1\n",
+ "Created VectorComponentFactorChebyshev2Basis with dim 1\n",
+ "Created VectorComponentFactorFourierBasis with dim 1\n"
+ ]
+ }
+ ],
+ "source": [
+ "import gtsam\n",
+ "\n",
+ "candidates = [n for n in dir(gtsam) if n.startswith(\"VectorComponentFactor\")]\n",
+ "print(\"VectorComponentFactor wrappers:\")\n",
+ "for name in candidates:\n",
+ " print(\" \", name)\n",
+ "\n",
+ "cls = None\n",
+ "selected = None\n",
+ "for name in candidates:\n",
+ " if hasattr(gtsam, name):\n",
+ " cls = getattr(gtsam, name)\n",
+ " selected = name\n",
+ "\n",
+ " if cls is None:\n",
+ " print(\"No VectorComponentFactor wrapper found; skipping execution.\")\n",
+ " else:\n",
+ " model = gtsam.noiseModel.Isotropic.Sigma(1, 0.1)\n",
+ " key = gtsam.symbol('c', 0)\n",
+ " factor = cls(key, -0.2, model, 3, 6, 1, 0.5)\n",
+ " print(f\"Created {selected} with dim {factor.dim()}\")\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [BasisFactors.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/BasisFactors.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/VectorDerivativeFactor.ipynb b/gtsam/basis/doc/VectorDerivativeFactor.ipynb
new file mode 100644
index 0000000000..286031cbf8
--- /dev/null
+++ b/gtsam/basis/doc/VectorDerivativeFactor.ipynb
@@ -0,0 +1,151 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# VectorDerivativeFactor\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`VectorDerivativeFactor` is a unary factor that enforces a vector measurement of the derivative of a vector-valued basis function at a given point.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 5,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `VectorDerivativeFactor(key, z, model, M, N, x)` constrains $\\mathbf{f}'(x)$.\n",
+ "- Optional interval parameters `a, b` scale the basis domain.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## C++ Usage Example\n",
+ "\n",
+ "```cpp\n",
+ "gtsam::Vector z = (gtsam::Vector(2) << 0.1, -0.1).finished();\n",
+ "auto model = gtsam::noiseModel::Isotropic::Sigma(2, 0.05);\n",
+ "size_t M = 2, N = 6;\n",
+ "double x = 0.0;\n",
+ "gtsam::VectorDerivativeFactor factor(key, z, model, M, N, x);\n",
+ "```\n",
+ "\n",
+ "## Python Example"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 6,
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ "VectorDerivativeFactor wrappers:\n",
+ " VectorDerivativeFactorChebyshev1Basis\n",
+ " VectorDerivativeFactorChebyshev2\n",
+ " VectorDerivativeFactorChebyshev2Basis\n",
+ " VectorDerivativeFactorFourierBasis\n",
+ "factor:\n",
+ " keys = { c0 }\n",
+ "isotropic dim=2 sigma=0.05\n",
+ "FunctorizedFactor(c0)\n",
+ " measurement: [\n",
+ "\t0.1;\n",
+ "\t-0.1\n",
+ "]\n",
+ " noise model sigmas: 0.05 0.05\n",
+ "\n"
+ ]
+ }
+ ],
+ "source": [
+ "import numpy as np\n",
+ "import gtsam\n",
+ "\n",
+ "candidates = [n for n in dir(gtsam) if n.startswith(\"VectorDerivativeFactor\")]\n",
+ "print(\"VectorDerivativeFactor wrappers:\")\n",
+ "for name in candidates:\n",
+ " print(\" \", name)\n",
+ "\n",
+ "z = np.array([0.1, -0.1])\n",
+ "model = gtsam.noiseModel.Isotropic.Sigma(2, 0.05)\n",
+ "key = gtsam.symbol('c', 0)\n",
+ "factor = gtsam.VectorDerivativeFactorChebyshev2(key, z, model, 2, 6, 0.0)\n",
+ "print(\"factor:\\n\", factor)"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [BasisFactors.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/BasisFactors.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/gtsam/basis/doc/VectorEvaluationFactor.ipynb b/gtsam/basis/doc/VectorEvaluationFactor.ipynb
new file mode 100644
index 0000000000..8d14268e0a
--- /dev/null
+++ b/gtsam/basis/doc/VectorEvaluationFactor.ipynb
@@ -0,0 +1,162 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "# VectorEvaluationFactor\n",
+ "\n",
+ "
\n",
+ "\n",
+ "## Overview\n",
+ "\n",
+ "`VectorEvaluationFactor` is a unary factor for vector-valued measurements evaluated from a basis parameter matrix. It enforces $\\mathbf{f}(x)$ to match a measurement vector at a given point.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Key Functionality / API\n",
+ "\n",
+ "- `VectorEvaluationFactor(key, z, model, M, N, x)` constrains the full vector.\n",
+ "- Optional interval parameters `a, b` scale the basis domain.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "c2c42d05",
+ "metadata": {},
+ "source": [
+ "## C++ Usage Example\n",
+ "\n",
+ "```cpp\n",
+ "gtsam::Vector z = (gtsam::Vector(3) << 1.0, 0.0, -0.5).finished();\n",
+ "auto model = gtsam::noiseModel::Isotropic::Sigma(3, 0.1);\n",
+ "size_t M = 3, N = 6;\n",
+ "double x = 0.0;\n",
+ "gtsam::VectorEvaluationFactor factor(key, z, model, M, N, x);\n",
+ "```\n",
+ "\n",
+ "## Python Example"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "id": "c8e2e7c5",
+ "metadata": {},
+ "outputs": [
+ {
+ "name": "stdout",
+ "output_type": "stream",
+ "text": [
+ "VectorEvaluationFactor wrappers:\n",
+ " VectorEvaluationFactorChebyshev1Basis\n",
+ " VectorEvaluationFactorChebyshev2\n",
+ " VectorEvaluationFactorChebyshev2Basis\n",
+ " VectorEvaluationFactorFourierBasis\n",
+ "Created VectorEvaluationFactorChebyshev2 with dim 3\n",
+ "Created VectorEvaluationFactorChebyshev2Basis with dim 3\n",
+ "Created VectorEvaluationFactorChebyshev1Basis with dim 3\n",
+ "Created VectorEvaluationFactorFourierBasis with dim 3\n"
+ ]
+ }
+ ],
+ "source": [
+ "import numpy as np\n",
+ "import gtsam\n",
+ "\n",
+ "candidates = [n for n in dir(gtsam) if n.startswith(\"VectorEvaluationFactor\")]\n",
+ "print(\"VectorEvaluationFactor wrappers:\")\n",
+ "for name in candidates:\n",
+ " print(\" \", name)\n",
+ "\n",
+ "cls = None\n",
+ "selected = None\n",
+ "for name in [\n",
+ " \"VectorEvaluationFactorChebyshev2\",\n",
+ " \"VectorEvaluationFactorChebyshev2Basis\",\n",
+ " \"VectorEvaluationFactorChebyshev1Basis\",\n",
+ " \"VectorEvaluationFactorFourierBasis\",\n",
+ "]:\n",
+ " if hasattr(gtsam, name):\n",
+ " cls = getattr(gtsam, name)\n",
+ " selected = name\n",
+ "\n",
+ " if cls is None:\n",
+ " print(\"No VectorEvaluationFactor wrapper found; skipping execution.\")\n",
+ " else:\n",
+ " z = np.array([1.0, 0.0, -0.5])\n",
+ " model = gtsam.noiseModel.Isotropic.Sigma(3, 0.1)\n",
+ " key = gtsam.symbol('c', 0)\n",
+ " factor = cls(key, z, model, 3, 6, 0.0)\n",
+ " print(f\"Created {selected} with dim {factor.dim()}\")\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Source\n",
+ "- [BasisFactors.h](https://github.com/borglab/gtsam/blob/develop/gtsam/basis/BasisFactors.h)\n"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/myst.yml b/myst.yml
index 85d1f26bf4..a49cd607dc 100644
--- a/myst.yml
+++ b/myst.yml
@@ -17,6 +17,9 @@ project:
- file: ./gtsam/geometry/geometry.md
children:
- pattern: ./gtsam/geometry/doc/*
+ - file: ./gtsam/basis/basis.md
+ children:
+ - pattern: ./gtsam/basis/doc/*
- file: ./gtsam/inference/inference.md
children:
- pattern: ./gtsam/inference/doc/*
diff --git a/python/gtsam/examples/FitBasisExample.ipynb b/python/gtsam/examples/FitBasisExample.ipynb
new file mode 100644
index 0000000000..6d54e57df5
--- /dev/null
+++ b/python/gtsam/examples/FitBasisExample.ipynb
@@ -0,0 +1,3681 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "\n",
+ "# FitBasis Example (Fourier + Chebyshev)\n",
+ "\n",
+ "
\n",
+ "\n",
+ "This notebook demonstrates how to fit a set of scalar measurements using\n",
+ "`FitBasis` for all four basis options exposed in the Python wrapper:\n",
+ "\n",
+ "- `FourierBasis`\n",
+ "- `Chebyshev1Basis`\n",
+ "- `Chebyshev2Basis`\n",
+ "- `Chebyshev2` (pseudo-spectral, parameters are values at Chebyshev points)\n",
+ "\n",
+ "We use a time domain from **t = 0 to 1** and fit each basis with **fewer\n",
+ "parameters than points**. For Chebyshev bases, we map time into the\n",
+ "Chebyshev interval `x = 2t - 1` to match the default `[-1, 1]` domain.\n",
+ "For the Fourier basis we use `x = 2pi t` to model periodic behavior.\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "source": [
+ "GTSAM Copyright 2010-2022, 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\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 12,
+ "id": "50e0e944",
+ "metadata": {
+ "tags": [
+ "remove-cell"
+ ]
+ },
+ "outputs": [],
+ "source": [
+ "# Install GTSAM from pip if running in Google Colab\n",
+ "try:\n",
+ " import google.colab\n",
+ " %pip install --quiet gtsam-develop\n",
+ "except ImportError:\n",
+ " pass # Not in Colab\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 13,
+ "id": "b8cf1aff",
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "\n",
+ "import numpy as np\n",
+ "import gtsam\n",
+ "import plotly.graph_objects as go\n",
+ "\n",
+ "np.set_printoptions(precision=3, suppress=True)\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 14,
+ "id": "a040dcaf",
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "\n",
+ "# Sample data\n",
+ "rng = np.random.default_rng(42)\n",
+ "num_points = 30\n",
+ "t = np.linspace(0.0, 1.0, num_points)\n",
+ "\n",
+ "# A smooth, mildly periodic signal with a trend\n",
+ "y_clean = 0.7 * np.sin(2 * np.pi * t) + 0.3 * np.cos(4 * np.pi * t) + 0.2 * t\n",
+ "y = y_clean + 0.05 * rng.standard_normal(size=t.size)\n",
+ "\n",
+ "# Parameter count must be smaller or equal than number of points\n",
+ "N = 10"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 15,
+ "id": "dab48fee",
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "\n",
+ "def plot_fit(t_samples, y_samples, t_dense, y_fit, title, extra=None):\n",
+ " fig = go.Figure()\n",
+ " fig.add_trace(go.Scatter(x=t_samples, y=y_samples, mode=\"markers\", name=\"Samples\", marker=dict(color=\"blue\", symbol=\"diamond\")))\n",
+ " fig.add_trace(go.Scatter(x=t_dense, y=y_fit, mode=\"lines\", name=\"Fit\"))\n",
+ " if extra is not None:\n",
+ " fig.add_trace(extra)\n",
+ " fig.update_layout(\n",
+ " title=title,\n",
+ " xaxis_title=\"time t\",\n",
+ " yaxis_title=\"value\",\n",
+ " template=\"plotly_white\",\n",
+ " width=900,\n",
+ " height=450,\n",
+ " )\n",
+ " fig.show()\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "62f6a786",
+ "metadata": {},
+ "source": [
+ "\n",
+ "## FourierBasis Fit\n",
+ "\n",
+ "This cell:\n",
+ "1. Builds a `{x: y}` sample map using the periodic domain `x = 2pi t`.\n",
+ "2. Fits Fourier coefficients with `FitBasisFourierBasis`.\n",
+ "3. Evaluates the fit on a dense grid via `FourierBasis.WeightMatrix`.\n",
+ "\n",
+ "Copy the core fit + evaluation parts if you want to integrate this into\n",
+ "your own pipeline (plotting is in a helper function).\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 16,
+ "id": "c05c36fa",
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "application/vnd.plotly.v1+json": {
+ "config": {
+ "plotlyServerURL": "https://plot.ly"
+ },
+ "data": [
+ {
+ "marker": {
+ "color": "blue",
+ "symbol": "diamond"
+ },
+ "mode": "markers",
+ "name": "Samples",
+ "type": "scatter",
+ "x": {
+ "bdata": "AAAAAAAAAACWexphuaehP5Z7GmG5p7E/YbmnEZZ7uj+WexphuafBP3waYbmnEcY/YbmnEZZ7yj9GWO5phOXOP5Z7GmG5p9E/Ccs9jbDc0z98GmG5pxHWP+5phOWeRtg/YbmnEZZ72j/UCMs9jbDcP0ZY7mmE5d4/3dMIyz2N4D+WexphuafhP08jLPc0wuI/Ccs9jbDc4z/Cck8jLPfkP3waYbmnEeY/NcJyTyMs5z/uaYTlnkboP6gRlnsaYek/YbmnEZZ76j8aYbmnEZbrP9QIyz2NsOw/jbDc0wjL7T9GWO5phOXuPwAAAAAAAPA/",
+ "dtype": "f8"
+ },
+ "y": {
+ "bdata": "bNnZANMs1D87DzzjZyvYP1/q4t00Q+E/W93Nm4hK4j/9htzjk4/aPwJ3IkOy2No/ouTpv9LF3T8nN6aaernbPzkayBL+fd0/sExPovXr3D+auSyw0JniP34j9yWkmOM/zzzfso7M4j/2gpF4p3fjPxDkkfgqRd8/RmY1DkHH0T/om8bU13HCPz0e0IwxVsO/cHLYTHsD078FowRs9/rhvwUauYQeqee/KYBEpkqo67/AIDqigRnpv6quPF8R++i/Cu+DUhyR5L82oNlO6lfbv4w4MoeOl8G/lPMgx2DSuj+vwUkRYXnVP6dbPdt2sOA/",
+ "dtype": "f8"
+ }
+ },
+ {
+ "mode": "lines",
+ "name": "Fit",
+ "type": "scatter",
+ "x": {
+ "bdata": "AAAAAAAA4L/wSWWlS8nfv+CTykqXkt+/z90v8OJb37+/J5WVLiXfv69x+jp67t6/n7tf4MW33r+OBcWFEYHev35PKitdSt6/bpmP0KgT3r9e4/R19Nzdv00tWhtApt2/PXe/wItv3b8twSRm1zjdvx0LigsjAt2/DFXvsG7L3L/8nlRWupTcv+zoufsFXty/3DIfoVEn3L/MfIRGnfDbv7vG6evoudu/qxBPkTSD27+bWrQ2gEzbv4qkGdzLFdu/eu5+gRff2r9qOOQmY6jav1qCScyucdq/Ssyucfo62r85FhQXRgTavylgebyRzdm/GareYd2W2b8I9EMHKWDZv/g9qax0Kdm/6IcOUsDy2L/Y0XP3C7zYv8gb2ZxXhdi/t2U+QqNO2L+nr6Pn7hfYv5f5CI064de/hkNuMoaq1792jdPX0XPXv2bXOH0dPde/ViGeImkG179GawPItM/Wvza1aG0Amda/Jf/NEkxi1r8VSTO4lyvWvwSTmF3j9NW/9Nz9Ai++1b/kJmOoeofVv9RwyE3GUNW/xLot8xEa1b+0BJOYXePUv6NO+D2prNS/k5hd4/R11L+C4sKIQD/Uv3IsKC6MCNS/YnaN09fR079SwPJ4I5vTv0IKWB5vZNO/MlS9w7ot078hniJpBvfSvxHohw5SwNK/ADLts52J0r/we1JZ6VLSv+DFt/40HNK/0A8dpIDl0b/AWYJJzK7Rv7Cj5+4XeNG/oO1MlGNB0b+PN7I5rwrRv3+BF9/609C/bst8hEad0L9eFeIpkmbQv05fR8/dL9C/fFJZ6VLyz79c5iM06oTPvzp67n6BF8+/Gg65yRiqzr/6oYMUsDzOv9o1Tl9Hz82/uMkYqt5hzb+YXeP0dfTMv3jxrT8Nh8y/WIV4iqQZzL82GUPVO6zLvxatDSDTPsu/9kDYamrRyr/W1KK1AWTKv7RobQCZ9sm/lPw3SzCJyb90kAKWxxvJv1QkzeBersi/MriXK/ZAyL8STGJ2jdPHv/LfLMEkZse/0nP3C7z4xr+yB8JWU4vGv5CbjKHqHca/cC9X7IGwxb9QwyE3GUPFvzBX7IGw1cS/Duu2zEdoxL/ufoEX3/rDv84STGJ2jcO/rqYWrQ0gw7+MOuH3pLLCv2zOq0I8RcK/TGJ2jdPXwb8s9kDYamrBvwqKCyMC/cC/6h3WbZmPwL/KsaC4MCLAv1SL1gaQab+/ELNrnL6Ovr/Q2gAy7bO9v5AClscb2by/UCorXUr+u78MUsDyeCO7v8x5VYinSLq/jKHqHdZtub9MyX+zBJO4vwjxFEkzuLe/yBiq3mHdtr+IQD90kAK2v0ho1Am/J7W/BJBpn+1MtL/Et/40HHKzv4Tfk8pKl7K/RAcpYHm8sb8EL771p+Gwv8BWU4vWBrC/AP3QQQpYrr+ATPtsZ6KsvwCcJZjE7Kq/eOtPwyE3qb/4OnrufoGnv3iKpBncy6W/+NnORDkWpL9wKflvlmCiv/B4I5vzqqC/4JCbjKHqnb/gL/DiW3+av9DORDkWFJe/0G2Zj9Cok7/QDO7lij2Qv6BXhXiKpIm/gJUuJf/Ngr8Ap6+j5+53vwBGBPqhg2S/AAhbTS1aSz8A5VhQXBhxPwBpBvdyxX4/wPbZzkQ5hj/AuDAi0A+NP2C9w7ot85E/YB5vZHNelT9gfxoOucmYP2Dgxbf+NJw/YEFxYUSgnz8wUY4FxYWhP7ABZNpnO6M/QLI5rwrxpD/AYg+EraamP0AT5VhQXKg/wMO6LfMRqj9AdJAClserP8AkZtc4fa0/QNU7rNsyrz/gwohAP3SwPyib86oQT7E/aHNeFeIpsj+oS8l/swSzP+gjNOqE37M/KPyeVFa6tD9o1Am/J5W1P6isdCn5b7Y/6ITfk8pKtz8wXUr+myW4P3A1tWhtALk/sA0g0z7buT/w5Yo9ELa6PzC+9afhkLs/cJZgErNrvD+wbst8hEa9P/BGNudVIb4/OB+hUSf8vj949wu8+Na/P9xnOxPlWMA//NNwyE3GwD8cQKZ9tjPBPzys2zIfocE/XBgR6IcOwj98hEad8HvCP5zwe1JZ6cI/wFyxB8JWwz/gyOa8KsTDPwA1HHKTMcQ/IKFRJ/yexD9ADYfcZAzFP2B5vJHNecU/gOXxRjbnxT+gUSf8nlTGP8S9XLEHwsY/5CmSZnAvxz8Elscb2ZzHPyQC/dBBCsg/RG4yhqp3yD9k2mc7E+XIP4RGnfB7Usk/pLLSpeS/yT/IHghbTS3KP+iKPRC2mso/CPdyxR4Iyz8oY6h6h3XLP0jP3S/w4ss/aDsT5VhQzD+Ip0iawb3MP6gTfk8qK80/zH+zBJOYzT/s6+i5+wXOPwxYHm9kc84/LMRTJM3gzj9MMInZNU7PP2ycvo6eu88/RgT6oYMU0D9WupT8N0vQP2ZwL1fsgdA/eCbKsaC40D+I3GQMVe/QP5iS/2YJJtE/qEiawb1c0T+4/jQccpPRP8i0z3YmytE/2Gpq0doA0j/oIAUsjzfSP/rWn4ZDbtI/Co064fek0j8aQ9U7rNvSPyr5b5ZgEtM/Oq8K8RRJ0z9KZaVLyX/TP1obQKZ9ttM/atHaADLt0z98h3Vb5iPUP4w9ELaaWtQ/nPOqEE+R1D+sqUVrA8jUP7xf4MW3/tQ/zBV7IGw11T/cyxV7IGzVP+yBsNXUotU//jdLMInZ1T8O7uWKPRDWPx6kgOXxRtY/LlobQKZ91j8+ELaaWrTWP07GUPUO69Y/XnzrT8Mh1z9uMoaqd1jXP37oIAUsj9c/kJ67X+DF1z+gVFa6lPzXP7AK8RRJM9g/wMCLb/1p2D/QdibKsaDYP+AswSRm19g/8OJbfxoO2T8AmfbZzkTZPxJPkTSDe9k/IgUsjzey2T8yu8bp6+jZP0JxYUSgH9o/Uif8nlRW2j9i3Zb5CI3aP3KTMVS9w9o/gknMrnH62j+U/2YJJjHbP6S1AWTaZ9s/tGucvo6e2z/EITcZQ9XbP9TX0XP3C9w/5I1szqtC3D/0QwcpYHncPwT6oYMUsNw/FrA83sjm3D8mZtc4fR3dPzYccpMxVN0/RtIM7uWK3T9WiKdImsHdP2Y+QqNO+N0/dvTc/QIv3j+GqndYt2XeP5ZgErNrnN4/qBatDSDT3j+4zEdo1AnfP8iC4sKIQN8/2Dh9HT133z/o7hd48a3fP/ikstKl5N8/hK2mFq0N4D+MCPRDByngP5RjQXFhROA/nL6Onrtf4D+kGdzLFXvgP6x0KflvluA/ts92Jsqx4D++KsRTJM3gP8aFEYF+6OA/zuBertgD4T/WO6zbMh/hP96W+QiNOuE/5vFGNudV4T/uTJRjQXHhP/an4ZCbjOE//gIvvvWn4T8GXnzrT8PhPw65yRiq3uE/FhQXRgT64T8eb2RzXhXiPybKsaC4MOI/LiX/zRJM4j82gEz7bGfiP0DbmSjHguI/SDbnVSGe4j9QkTSDe7niP1jsgbDV1OI/YEfP3S/w4j9oohwLigvjP3D9aTjkJuM/eFi3ZT5C4z+AswSTmF3jP4gOUsDyeOM/kGmf7UyU4z+YxOwap6/jP6AfOkgBy+M/qHqHdVvm4z+w1dSitQHkP7gwItAPHeQ/wotv/Wk45D/K5rwqxFPkP9JBClgeb+Q/2pxXhXiK5D/i96Sy0qXkP+pS8t8sweQ/8q0/DYfc5D/6CI064ffkPwJk2mc7E+U/Cr8nlZUu5T8SGnXC70nlPxp1wu9JZeU/ItAPHaSA5T8qK11K/pvlPzKGqndYt+U/OuH3pLLS5T9CPEXSDO7lP0yXkv9mCeY/VPLfLMEk5j9cTS1aG0DmP2Soeod1W+Y/bAPItM925j90XhXiKZLmP3y5Yg+EreY/hBSwPN7I5j+Mb/1pOOTmP5TKSpeS/+Y/nCWYxOwa5z+kgOXxRjbnP6zbMh+hUec/tDaATPts5z+8kc15VYjnP8TsGqevo+c/zkdo1Am/5z/WorUBZNrnP979Ai++9ec/5lhQXBgR6D/us52JcizoP/YO67bMR+g//mk45CZj6D8GxYURgX7oPw4g0z7bmeg/FnsgbDW16D8e1m2Zj9DoPyYxu8bp6+g/LowI9EMH6T8251UhniLpPz5Co074Pek/Rp3we1JZ6T9O+D2prHTpP1hTi9YGkOk/YK7YA2Gr6T9oCSYxu8bpP3Bkc14V4uk/eL/Ai2/96T+AGg65yRjqP4h1W+YjNOo/kNCoE35P6j+YK/ZA2GrqP6CGQ24yhuo/qOGQm4yh6j+wPN7I5rzqP7iXK/ZA2Oo/wPJ4I5vz6j/ITcZQ9Q7rP9CoE35PKus/2gNhq6lF6z/iXq7YA2HrP+q5+wVefOs/8hRJM7iX6z/6b5ZgErPrPwLL441szus/CiYxu8bp6z8SgX7oIAXsPxrcyxV7IOw/IjcZQ9U77D8qkmZwL1fsPzLts52Jcuw/OkgBy+ON7D9Co074PansP0r+myWYxOw/UlnpUvLf7D9atDaATPvsP2QPhK2mFu0/bGrR2gAy7T90xR4IW03tP3wgbDW1aO0/hHu5Yg+E7T+M1gaQaZ/tP5QxVL3Duu0/nIyh6h3W7T+k5+4XePHtP6xCPEXSDO4/tJ2Jciwo7j+8+NafhkPuP8RTJM3gXu4/zK5x+jp67j/UCb8nlZXuP9xkDFXvsO4/5r9ZgknM7j/uGqevo+fuP/Z19Nz9Au8//tBBClge7z8GLI83sjnvPw6H3GQMVe8/FuIpkmZw7z8ePXe/wIvvPyaYxOwap+8/LvMRGnXC7z82Tl9Hz93vPz6prHQp+e8/IwL90EEK8D+nr6Pn7hfwPytdSv6bJfA/rwrxFEkz8D8zuJcr9kDwP7hlPkKjTvA/PBPlWFBc8D/AwItv/WnwP0RuMoaqd/A/yBvZnFeF8D9MyX+zBJPwP9B2JsqxoPA/VCTN4F6u8D/Y0XP3C7zwP1x/Gg65yfA/4CzBJGbX8D9k2mc7E+XwP+iHDlLA8vA/bDW1aG0A8T/w4lt/Gg7xP3SQApbHG/E/+T2prHQp8T9960/DITfxPwGZ9tnORPE/hUad8HtS8T8J9EMHKWDxP42h6h3WbfE/EU+RNIN78T+V/DdLMInxPxmq3mHdlvE/nVeFeIqk8T8hBSyPN7LxP6Wy0qXkv/E/KWB5vJHN8T+tDSDTPtvxPzG7xunr6PE/tWhtAJn28T85FhQXRgTyP77Dui3zEfI/QnFhRKAf8j/GHghbTS3yP0rMrnH6OvI/znlViKdI8j9SJ/yeVFbyP9bUorUBZPI/WoJJzK5x8j/eL/DiW3/yP2LdlvkIjfI/5oo9ELaa8j9qOOQmY6jyP+7lij0QtvI/cpMxVL3D8j/2QNhqatHyP3rufoEX3/I//5slmMTs8j+DScyucfryPwf3csUeCPM/i6QZ3MsV8z8PUsDyeCPzP5P/ZgkmMfM/F60NINM+8z+bWrQ2gEzzPx8IW00tWvM/o7UBZNpn8z8nY6h6h3XzP6sQT5E0g/M/L771p+GQ8z+za5y+jp7zPzcZQ9U7rPM/u8bp6+i58z8/dJAClsfzP8QhNxlD1fM/SM/dL/Di8z/MfIRGnfDzP1AqK11K/vM/1NfRc/cL9D9YhXiKpBn0P9wyH6FRJ/Q/YODFt/409D/kjWzOq0L0P2g7E+VYUPQ/7Oi5+wVe9D9wlmASs2v0P/RDBylgefQ/ePGtPw2H9D/8nlRWupT0P4BM+2xnovQ/BfqhgxSw9D+Jp0iawb30Pw1V77Buy/Q/kQKWxxvZ9D8VsDzeyOb0P5ld4/R19PQ/HQuKCyMC9T+huDAi0A/1PyVm1zh9HfU/qRN+Tyor9T8twSRm1zj1P7Fuy3yERvU/NRxykzFU9T+5yRiq3mH1Pz13v8CLb/U/wSRm1zh99T9F0gzu5Yr1P8p/swSTmPU/Ti1aG0Cm9T/S2gAy7bP1P1aIp0iawfU/2jVOX0fP9T9e4/R19Nz1P+KQm4yh6vU/Zj5Co0749T/q6+i5+wX2P26Zj9CoE/Y/8kY251Uh9j929Nz9Ai/2P/qhgxSwPPY/fk8qK11K9j8C/dBBClj2P4aqd1i3ZfY/C1geb2Rz9j+PBcWFEYH2PxOza5y+jvY/l2ASs2uc9j8bDrnJGKr2P5+7X+DFt/Y/I2kG93LF9j+nFq0NINP2PyvEUyTN4PY/r3H6Onru9j8zH6FRJ/z2P7fMR2jUCfc/O3rufoEX9z+/J5WVLiX3P0PVO6zbMvc/x4LiwohA9z9LMInZNU73P9DdL/DiW/c/VIvWBpBp9z/YOH0dPXf3P1zmIzTqhPc/4JPKSpeS9z9kQXFhRKD3P+juF3jxrfc/bJy+jp679z/wSWWlS8n3P3T3C7z41vc/+KSy0qXk9z98UlnpUvL3PwAAAAAAAPg/",
+ "dtype": "f8"
+ },
+ "y": {
+ "bdata": "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",
+ "dtype": "f8"
+ }
+ }
+ ],
+ "layout": {
+ "height": 450,
+ "template": {
+ "data": {
+ "bar": [
+ {
+ "error_x": {
+ "color": "#2a3f5f"
+ },
+ "error_y": {
+ "color": "#2a3f5f"
+ },
+ "marker": {
+ "line": {
+ "color": "white",
+ "width": 0.5
+ },
+ "pattern": {
+ "fillmode": "overlay",
+ "size": 10,
+ "solidity": 0.2
+ }
+ },
+ "type": "bar"
+ }
+ ],
+ "barpolar": [
+ {
+ "marker": {
+ "line": {
+ "color": "white",
+ "width": 0.5
+ },
+ "pattern": {
+ "fillmode": "overlay",
+ "size": 10,
+ "solidity": 0.2
+ }
+ },
+ "type": "barpolar"
+ }
+ ],
+ "carpet": [
+ {
+ "aaxis": {
+ "endlinecolor": "#2a3f5f",
+ "gridcolor": "#C8D4E3",
+ "linecolor": "#C8D4E3",
+ "minorgridcolor": "#C8D4E3",
+ "startlinecolor": "#2a3f5f"
+ },
+ "baxis": {
+ "endlinecolor": "#2a3f5f",
+ "gridcolor": "#C8D4E3",
+ "linecolor": "#C8D4E3",
+ "minorgridcolor": "#C8D4E3",
+ "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": "white",
+ "showlakes": true,
+ "showland": true,
+ "subunitcolor": "#C8D4E3"
+ },
+ "hoverlabel": {
+ "align": "left"
+ },
+ "hovermode": "closest",
+ "mapbox": {
+ "style": "light"
+ },
+ "paper_bgcolor": "white",
+ "plot_bgcolor": "white",
+ "polar": {
+ "angularaxis": {
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": ""
+ },
+ "bgcolor": "white",
+ "radialaxis": {
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": ""
+ }
+ },
+ "scene": {
+ "xaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ },
+ "yaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ },
+ "zaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ }
+ },
+ "shapedefaults": {
+ "line": {
+ "color": "#2a3f5f"
+ }
+ },
+ "ternary": {
+ "aaxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ },
+ "baxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ },
+ "bgcolor": "white",
+ "caxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ }
+ },
+ "title": {
+ "x": 0.05
+ },
+ "xaxis": {
+ "automargin": true,
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": "",
+ "title": {
+ "standoff": 15
+ },
+ "zerolinecolor": "#EBF0F8",
+ "zerolinewidth": 2
+ },
+ "yaxis": {
+ "automargin": true,
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": "",
+ "title": {
+ "standoff": 15
+ },
+ "zerolinecolor": "#EBF0F8",
+ "zerolinewidth": 2
+ }
+ }
+ },
+ "title": {
+ "text": "FourierBasis Fit (periodic beyond [0, 1])"
+ },
+ "width": 900,
+ "xaxis": {
+ "title": {
+ "text": "time t"
+ }
+ },
+ "yaxis": {
+ "title": {
+ "text": "value"
+ }
+ }
+ }
+ }
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "x_fourier = 2.0 * np.pi * t\n",
+ "sequence : dict = {float(xi): float(yi) for xi, yi in zip(x_fourier, y)}\n",
+ "model = gtsam.noiseModel.Isotropic.Sigma(1, 0.05)\n",
+ "fit = gtsam.FitBasisFourierBasis(sequence, model, N)\n",
+ "params = np.asarray(fit.parameters()).ravel()\n",
+ "\n",
+ "# Extend the time domain to show periodic behavior\n",
+ "t_dense = np.linspace(-0.5, 1.5, 600)\n",
+ "x_dense = 2.0 * np.pi * t_dense\n",
+ "W = np.asarray(gtsam.FourierBasis.WeightMatrix(len(params), x_dense))\n",
+ "y_fit = W @ params\n",
+ "\n",
+ "plot_fit(t, y, t_dense, y_fit, \"FourierBasis Fit (periodic beyond [0, 1])\")\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "34962068",
+ "metadata": {},
+ "source": [
+ "\n",
+ "## Chebyshev1Basis Fit\n",
+ "\n",
+ "This cell:\n",
+ "1. Maps time to the Chebyshev interval with `x = 2t - 1`.\n",
+ "2. Fits Chebyshev-1 coefficients with `FitBasisChebyshev1Basis`.\n",
+ "3. Evaluates the fit using `Chebyshev1Basis.WeightMatrix`.\n",
+ "\n",
+ "Copy the fit + evaluation steps to reuse with your own data or noise model.\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 17,
+ "id": "ddacb31c",
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "application/vnd.plotly.v1+json": {
+ "config": {
+ "plotlyServerURL": "https://plot.ly"
+ },
+ "data": [
+ {
+ "marker": {
+ "color": "blue",
+ "symbol": "diamond"
+ },
+ "mode": "markers",
+ "name": "Samples",
+ "type": "scatter",
+ "x": {
+ "bdata": "AAAAAAAAAACWexphuaehP5Z7GmG5p7E/YbmnEZZ7uj+WexphuafBP3waYbmnEcY/YbmnEZZ7yj9GWO5phOXOP5Z7GmG5p9E/Ccs9jbDc0z98GmG5pxHWP+5phOWeRtg/YbmnEZZ72j/UCMs9jbDcP0ZY7mmE5d4/3dMIyz2N4D+WexphuafhP08jLPc0wuI/Ccs9jbDc4z/Cck8jLPfkP3waYbmnEeY/NcJyTyMs5z/uaYTlnkboP6gRlnsaYek/YbmnEZZ76j8aYbmnEZbrP9QIyz2NsOw/jbDc0wjL7T9GWO5phOXuPwAAAAAAAPA/",
+ "dtype": "f8"
+ },
+ "y": {
+ "bdata": "bNnZANMs1D87DzzjZyvYP1/q4t00Q+E/W93Nm4hK4j/9htzjk4/aPwJ3IkOy2No/ouTpv9LF3T8nN6aaernbPzkayBL+fd0/sExPovXr3D+auSyw0JniP34j9yWkmOM/zzzfso7M4j/2gpF4p3fjPxDkkfgqRd8/RmY1DkHH0T/om8bU13HCPz0e0IwxVsO/cHLYTHsD078FowRs9/rhvwUauYQeqee/KYBEpkqo67/AIDqigRnpv6quPF8R++i/Cu+DUhyR5L82oNlO6lfbv4w4MoeOl8G/lPMgx2DSuj+vwUkRYXnVP6dbPdt2sOA/",
+ "dtype": "f8"
+ }
+ },
+ {
+ "mode": "lines",
+ "name": "Fit",
+ "type": "scatter",
+ "x": {
+ "bdata": "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",
+ "dtype": "f8"
+ },
+ "y": {
+ "bdata": "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",
+ "dtype": "f8"
+ }
+ }
+ ],
+ "layout": {
+ "height": 450,
+ "template": {
+ "data": {
+ "bar": [
+ {
+ "error_x": {
+ "color": "#2a3f5f"
+ },
+ "error_y": {
+ "color": "#2a3f5f"
+ },
+ "marker": {
+ "line": {
+ "color": "white",
+ "width": 0.5
+ },
+ "pattern": {
+ "fillmode": "overlay",
+ "size": 10,
+ "solidity": 0.2
+ }
+ },
+ "type": "bar"
+ }
+ ],
+ "barpolar": [
+ {
+ "marker": {
+ "line": {
+ "color": "white",
+ "width": 0.5
+ },
+ "pattern": {
+ "fillmode": "overlay",
+ "size": 10,
+ "solidity": 0.2
+ }
+ },
+ "type": "barpolar"
+ }
+ ],
+ "carpet": [
+ {
+ "aaxis": {
+ "endlinecolor": "#2a3f5f",
+ "gridcolor": "#C8D4E3",
+ "linecolor": "#C8D4E3",
+ "minorgridcolor": "#C8D4E3",
+ "startlinecolor": "#2a3f5f"
+ },
+ "baxis": {
+ "endlinecolor": "#2a3f5f",
+ "gridcolor": "#C8D4E3",
+ "linecolor": "#C8D4E3",
+ "minorgridcolor": "#C8D4E3",
+ "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": "white",
+ "showlakes": true,
+ "showland": true,
+ "subunitcolor": "#C8D4E3"
+ },
+ "hoverlabel": {
+ "align": "left"
+ },
+ "hovermode": "closest",
+ "mapbox": {
+ "style": "light"
+ },
+ "paper_bgcolor": "white",
+ "plot_bgcolor": "white",
+ "polar": {
+ "angularaxis": {
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": ""
+ },
+ "bgcolor": "white",
+ "radialaxis": {
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": ""
+ }
+ },
+ "scene": {
+ "xaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ },
+ "yaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ },
+ "zaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ }
+ },
+ "shapedefaults": {
+ "line": {
+ "color": "#2a3f5f"
+ }
+ },
+ "ternary": {
+ "aaxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ },
+ "baxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ },
+ "bgcolor": "white",
+ "caxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ }
+ },
+ "title": {
+ "x": 0.05
+ },
+ "xaxis": {
+ "automargin": true,
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": "",
+ "title": {
+ "standoff": 15
+ },
+ "zerolinecolor": "#EBF0F8",
+ "zerolinewidth": 2
+ },
+ "yaxis": {
+ "automargin": true,
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": "",
+ "title": {
+ "standoff": 15
+ },
+ "zerolinecolor": "#EBF0F8",
+ "zerolinewidth": 2
+ }
+ }
+ },
+ "title": {
+ "text": "Chebyshev1Basis Fit (extrapolation outside [0, 1])"
+ },
+ "width": 900,
+ "xaxis": {
+ "title": {
+ "text": "time t"
+ }
+ },
+ "yaxis": {
+ "title": {
+ "text": "value"
+ }
+ }
+ }
+ }
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "x_cheb = 2.0 * t - 1.0\n",
+ "sequence = {float(xi): float(yi) for xi, yi in zip(x_cheb, y)}\n",
+ "model = gtsam.noiseModel.Isotropic.Sigma(1, 0.05)\n",
+ "fit = gtsam.FitBasisChebyshev1Basis(sequence, model, N)\n",
+ "params = np.asarray(fit.parameters()).ravel()\n",
+ "\n",
+ "t_dense = np.linspace(-0.1, 1.1, 600)\n",
+ "x_dense = 2.0 * t_dense - 1.0\n",
+ "W = np.asarray(gtsam.Chebyshev1Basis.WeightMatrix(len(params), x_dense))\n",
+ "y_fit = W @ params\n",
+ "\n",
+ "plot_fit(t, y, t_dense, y_fit, \"Chebyshev1Basis Fit (extrapolation outside [0, 1])\")\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "88a6344a",
+ "metadata": {},
+ "source": [
+ "\n",
+ "## Chebyshev2Basis Fit\n",
+ "\n",
+ "This cell uses the second-kind Chebyshev basis (coefficient form):\n",
+ "\n",
+ "1. Map time to `x = 2t - 1`.\n",
+ "2. Fit with `FitBasisChebyshev2Basis`.\n",
+ "3. Evaluate with `Chebyshev2Basis.WeightMatrix`.\n",
+ "\n",
+ "These steps are the minimal pieces you need for non-plotting usage.\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 18,
+ "id": "fc3d1235",
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "application/vnd.plotly.v1+json": {
+ "config": {
+ "plotlyServerURL": "https://plot.ly"
+ },
+ "data": [
+ {
+ "marker": {
+ "color": "blue",
+ "symbol": "diamond"
+ },
+ "mode": "markers",
+ "name": "Samples",
+ "type": "scatter",
+ "x": {
+ "bdata": "AAAAAAAAAACWexphuaehP5Z7GmG5p7E/YbmnEZZ7uj+WexphuafBP3waYbmnEcY/YbmnEZZ7yj9GWO5phOXOP5Z7GmG5p9E/Ccs9jbDc0z98GmG5pxHWP+5phOWeRtg/YbmnEZZ72j/UCMs9jbDcP0ZY7mmE5d4/3dMIyz2N4D+WexphuafhP08jLPc0wuI/Ccs9jbDc4z/Cck8jLPfkP3waYbmnEeY/NcJyTyMs5z/uaYTlnkboP6gRlnsaYek/YbmnEZZ76j8aYbmnEZbrP9QIyz2NsOw/jbDc0wjL7T9GWO5phOXuPwAAAAAAAPA/",
+ "dtype": "f8"
+ },
+ "y": {
+ "bdata": "bNnZANMs1D87DzzjZyvYP1/q4t00Q+E/W93Nm4hK4j/9htzjk4/aPwJ3IkOy2No/ouTpv9LF3T8nN6aaernbPzkayBL+fd0/sExPovXr3D+auSyw0JniP34j9yWkmOM/zzzfso7M4j/2gpF4p3fjPxDkkfgqRd8/RmY1DkHH0T/om8bU13HCPz0e0IwxVsO/cHLYTHsD078FowRs9/rhvwUauYQeqee/KYBEpkqo67/AIDqigRnpv6quPF8R++i/Cu+DUhyR5L82oNlO6lfbv4w4MoeOl8G/lPMgx2DSuj+vwUkRYXnVP6dbPdt2sOA/",
+ "dtype": "f8"
+ }
+ },
+ {
+ "mode": "lines",
+ "name": "Fit",
+ "type": "scatter",
+ "x": {
+ "bdata": "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",
+ "dtype": "f8"
+ },
+ "y": {
+ "bdata": "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",
+ "dtype": "f8"
+ }
+ }
+ ],
+ "layout": {
+ "height": 450,
+ "template": {
+ "data": {
+ "bar": [
+ {
+ "error_x": {
+ "color": "#2a3f5f"
+ },
+ "error_y": {
+ "color": "#2a3f5f"
+ },
+ "marker": {
+ "line": {
+ "color": "white",
+ "width": 0.5
+ },
+ "pattern": {
+ "fillmode": "overlay",
+ "size": 10,
+ "solidity": 0.2
+ }
+ },
+ "type": "bar"
+ }
+ ],
+ "barpolar": [
+ {
+ "marker": {
+ "line": {
+ "color": "white",
+ "width": 0.5
+ },
+ "pattern": {
+ "fillmode": "overlay",
+ "size": 10,
+ "solidity": 0.2
+ }
+ },
+ "type": "barpolar"
+ }
+ ],
+ "carpet": [
+ {
+ "aaxis": {
+ "endlinecolor": "#2a3f5f",
+ "gridcolor": "#C8D4E3",
+ "linecolor": "#C8D4E3",
+ "minorgridcolor": "#C8D4E3",
+ "startlinecolor": "#2a3f5f"
+ },
+ "baxis": {
+ "endlinecolor": "#2a3f5f",
+ "gridcolor": "#C8D4E3",
+ "linecolor": "#C8D4E3",
+ "minorgridcolor": "#C8D4E3",
+ "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": "white",
+ "showlakes": true,
+ "showland": true,
+ "subunitcolor": "#C8D4E3"
+ },
+ "hoverlabel": {
+ "align": "left"
+ },
+ "hovermode": "closest",
+ "mapbox": {
+ "style": "light"
+ },
+ "paper_bgcolor": "white",
+ "plot_bgcolor": "white",
+ "polar": {
+ "angularaxis": {
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": ""
+ },
+ "bgcolor": "white",
+ "radialaxis": {
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": ""
+ }
+ },
+ "scene": {
+ "xaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ },
+ "yaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ },
+ "zaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ }
+ },
+ "shapedefaults": {
+ "line": {
+ "color": "#2a3f5f"
+ }
+ },
+ "ternary": {
+ "aaxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ },
+ "baxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ },
+ "bgcolor": "white",
+ "caxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ }
+ },
+ "title": {
+ "x": 0.05
+ },
+ "xaxis": {
+ "automargin": true,
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": "",
+ "title": {
+ "standoff": 15
+ },
+ "zerolinecolor": "#EBF0F8",
+ "zerolinewidth": 2
+ },
+ "yaxis": {
+ "automargin": true,
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": "",
+ "title": {
+ "standoff": 15
+ },
+ "zerolinecolor": "#EBF0F8",
+ "zerolinewidth": 2
+ }
+ }
+ },
+ "title": {
+ "text": "Chebyshev2Basis Fit (extrapolation outside [0, 1])"
+ },
+ "width": 900,
+ "xaxis": {
+ "title": {
+ "text": "time t"
+ }
+ },
+ "yaxis": {
+ "title": {
+ "text": "value"
+ }
+ }
+ }
+ }
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "sequence = {float(xi): float(yi) for xi, yi in zip(x_cheb, y)}\n",
+ "model = gtsam.noiseModel.Isotropic.Sigma(1, 0.05)\n",
+ "fit = gtsam.FitBasisChebyshev2Basis(sequence, model, N)\n",
+ "params = np.asarray(fit.parameters()).ravel()\n",
+ "\n",
+ "t_dense = np.linspace(-0.1, 1.1, 600)\n",
+ "x_dense = 2.0 * t_dense - 1.0\n",
+ "W = np.asarray(gtsam.Chebyshev2Basis.WeightMatrix(len(params), x_dense))\n",
+ "y_fit = W @ params\n",
+ "\n",
+ "plot_fit(t, y, t_dense, y_fit, \"Chebyshev2Basis Fit (extrapolation outside [0, 1])\")\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "4d2ebb77",
+ "metadata": {},
+ "source": [
+ "\n",
+ "## Chebyshev2 (Pseudo-Spectral) Fit\n",
+ "\n",
+ "This variant treats the parameters as function values at Chebyshev points.\n",
+ "The steps here are slightly different conceptually:\n",
+ "\n",
+ "1. Fit values at Chebyshev points with `FitBasisChebyshev2`.\n",
+ "2. Evaluate by barycentric interpolation using `Chebyshev2.WeightMatrix`.\n",
+ "3. Plot the interpolation nodes alongside the fitted curve.\n",
+ "\n",
+ "If you don't need plots, copy the fit + evaluation and skip the marker trace.\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 19,
+ "id": "37db92b8",
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "application/vnd.plotly.v1+json": {
+ "config": {
+ "plotlyServerURL": "https://plot.ly"
+ },
+ "data": [
+ {
+ "marker": {
+ "color": "blue",
+ "symbol": "diamond"
+ },
+ "mode": "markers",
+ "name": "Samples",
+ "type": "scatter",
+ "x": {
+ "bdata": "AAAAAAAAAACWexphuaehP5Z7GmG5p7E/YbmnEZZ7uj+WexphuafBP3waYbmnEcY/YbmnEZZ7yj9GWO5phOXOP5Z7GmG5p9E/Ccs9jbDc0z98GmG5pxHWP+5phOWeRtg/YbmnEZZ72j/UCMs9jbDcP0ZY7mmE5d4/3dMIyz2N4D+WexphuafhP08jLPc0wuI/Ccs9jbDc4z/Cck8jLPfkP3waYbmnEeY/NcJyTyMs5z/uaYTlnkboP6gRlnsaYek/YbmnEZZ76j8aYbmnEZbrP9QIyz2NsOw/jbDc0wjL7T9GWO5phOXuPwAAAAAAAPA/",
+ "dtype": "f8"
+ },
+ "y": {
+ "bdata": "bNnZANMs1D87DzzjZyvYP1/q4t00Q+E/W93Nm4hK4j/9htzjk4/aPwJ3IkOy2No/ouTpv9LF3T8nN6aaernbPzkayBL+fd0/sExPovXr3D+auSyw0JniP34j9yWkmOM/zzzfso7M4j/2gpF4p3fjPxDkkfgqRd8/RmY1DkHH0T/om8bU13HCPz0e0IwxVsO/cHLYTHsD078FowRs9/rhvwUauYQeqee/KYBEpkqo67/AIDqigRnpv6quPF8R++i/Cu+DUhyR5L82oNlO6lfbv4w4MoeOl8G/lPMgx2DSuj+vwUkRYXnVP6dbPdt2sOA/",
+ "dtype": "f8"
+ }
+ },
+ {
+ "mode": "lines",
+ "name": "Fit",
+ "type": "scatter",
+ "x": {
+ "bdata": "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",
+ "dtype": "f8"
+ },
+ "y": {
+ "bdata": "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",
+ "dtype": "f8"
+ }
+ },
+ {
+ "marker": {
+ "color": "red"
+ },
+ "mode": "markers",
+ "name": "Chebyshev2 points",
+ "type": "scatter",
+ "x": {
+ "bdata": "AAAAAAAAAABALt3am+CePxy/wnRB8r0//v//////zz8dI31geXHaP3JuwU9Dx+I/AAAAAAAA6D8cqGfRt0HsP44WKSH7CO8/AAAAAAAA8D8=",
+ "dtype": "f8"
+ },
+ "y": {
+ "bdata": "R4qQtgF40z+e8Y0tARnaP3HiFl/5YOA/7SJUgXv72j+QTCgsC7fjP3bOVf1x0L2/2l7H+y0Q678M/CXu68TQv1F0nf9Cq9c/QC12MnCb4D8=",
+ "dtype": "f8"
+ }
+ }
+ ],
+ "layout": {
+ "height": 450,
+ "template": {
+ "data": {
+ "bar": [
+ {
+ "error_x": {
+ "color": "#2a3f5f"
+ },
+ "error_y": {
+ "color": "#2a3f5f"
+ },
+ "marker": {
+ "line": {
+ "color": "white",
+ "width": 0.5
+ },
+ "pattern": {
+ "fillmode": "overlay",
+ "size": 10,
+ "solidity": 0.2
+ }
+ },
+ "type": "bar"
+ }
+ ],
+ "barpolar": [
+ {
+ "marker": {
+ "line": {
+ "color": "white",
+ "width": 0.5
+ },
+ "pattern": {
+ "fillmode": "overlay",
+ "size": 10,
+ "solidity": 0.2
+ }
+ },
+ "type": "barpolar"
+ }
+ ],
+ "carpet": [
+ {
+ "aaxis": {
+ "endlinecolor": "#2a3f5f",
+ "gridcolor": "#C8D4E3",
+ "linecolor": "#C8D4E3",
+ "minorgridcolor": "#C8D4E3",
+ "startlinecolor": "#2a3f5f"
+ },
+ "baxis": {
+ "endlinecolor": "#2a3f5f",
+ "gridcolor": "#C8D4E3",
+ "linecolor": "#C8D4E3",
+ "minorgridcolor": "#C8D4E3",
+ "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": "white",
+ "showlakes": true,
+ "showland": true,
+ "subunitcolor": "#C8D4E3"
+ },
+ "hoverlabel": {
+ "align": "left"
+ },
+ "hovermode": "closest",
+ "mapbox": {
+ "style": "light"
+ },
+ "paper_bgcolor": "white",
+ "plot_bgcolor": "white",
+ "polar": {
+ "angularaxis": {
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": ""
+ },
+ "bgcolor": "white",
+ "radialaxis": {
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": ""
+ }
+ },
+ "scene": {
+ "xaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ },
+ "yaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ },
+ "zaxis": {
+ "backgroundcolor": "white",
+ "gridcolor": "#DFE8F3",
+ "gridwidth": 2,
+ "linecolor": "#EBF0F8",
+ "showbackground": true,
+ "ticks": "",
+ "zerolinecolor": "#EBF0F8"
+ }
+ },
+ "shapedefaults": {
+ "line": {
+ "color": "#2a3f5f"
+ }
+ },
+ "ternary": {
+ "aaxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ },
+ "baxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ },
+ "bgcolor": "white",
+ "caxis": {
+ "gridcolor": "#DFE8F3",
+ "linecolor": "#A2B1C6",
+ "ticks": ""
+ }
+ },
+ "title": {
+ "x": 0.05
+ },
+ "xaxis": {
+ "automargin": true,
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": "",
+ "title": {
+ "standoff": 15
+ },
+ "zerolinecolor": "#EBF0F8",
+ "zerolinewidth": 2
+ },
+ "yaxis": {
+ "automargin": true,
+ "gridcolor": "#EBF0F8",
+ "linecolor": "#EBF0F8",
+ "ticks": "",
+ "title": {
+ "standoff": 15
+ },
+ "zerolinecolor": "#EBF0F8",
+ "zerolinewidth": 2
+ }
+ }
+ },
+ "title": {
+ "text": "Chebyshev2 Pseudo-Spectral Fit (extrapolation outside [0, 1])"
+ },
+ "width": 900,
+ "xaxis": {
+ "title": {
+ "text": "time t"
+ }
+ },
+ "yaxis": {
+ "title": {
+ "text": "value"
+ }
+ }
+ }
+ }
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "sequence = {float(xi): float(yi) for xi, yi in zip(x_cheb, y)}\n",
+ "model = gtsam.noiseModel.Isotropic.Sigma(1, 0.05)\n",
+ "fit = gtsam.FitBasisChebyshev2(sequence, model, N)\n",
+ "params = np.asarray(fit.parameters()).ravel()\n",
+ "\n",
+ "t_dense = np.linspace(-0.1, 1.1, 600)\n",
+ "x_dense = 2.0 * t_dense - 1.0\n",
+ "W = np.asarray(gtsam.Chebyshev2.WeightMatrix(len(params), x_dense))\n",
+ "y_fit = W @ params\n",
+ "\n",
+ "cheb_points = np.asarray(gtsam.Chebyshev2.Points(N)).ravel()\n",
+ "t_cheb = 0.5 * (cheb_points + 1.0)\n",
+ "y_cheb = params\n",
+ "markers = go.Scatter(x=t_cheb, y=y_cheb, mode=\"markers\", name=\"Chebyshev2 points\", marker=dict(color=\"red\"))\n",
+ "\n",
+ "plot_fit(t, y, t_dense, y_fit, \"Chebyshev2 Pseudo-Spectral Fit (extrapolation outside [0, 1])\", extra=markers)\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "bf516bde",
+ "metadata": {},
+ "source": [
+ "The Chebyshev points above *are* the parameterization. They values at those points are moved up and down to make the blue points fit the polynomial as closely as possible. Because for every $N$ points we can exactly fit an $n=N-1$ degree polynomial, the values at these Chebyshev points *are* a parameterization of the polynomial.\n",
+ "\n",
+ "Chebyshev points are fixed nodes that cluster near the interval ends; this improves interpolation stability and reduces endpoint oscillations compared to equally spaced nodes (mitigating the Runge phenomenon)."
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "7d4c0b1d",
+ "metadata": {},
+ "source": []
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "py312",
+ "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.6"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/python/gtsam/examples/README.md b/python/gtsam/examples/README.md
index be160f8475..73ad0bbf02 100644
--- a/python/gtsam/examples/README.md
+++ b/python/gtsam/examples/README.md
@@ -2,15 +2,15 @@
| C++ Example Name | Ported |
|-------------------------------------------------------|--------|
-| CameraResectioning | :heavy_check_mark: |
+| [CameraResectioning](CameraResectioning.ipynb) | :heavy_check_mark: |
| CombinedImuFactorsExample | :heavy_check_mark: |
-| CreateSFMExampleData | :heavy_check_mark: |
-| DiscreteBayesNetExample | :heavy_check_mark: |
+| [CreateSFMExampleData](CreateSFMExampleData.ipynb) | :heavy_check_mark: |
+| [DiscreteBayesNetExample](DiscreteBayesNetExample.ipynb) | :heavy_check_mark: |
| DiscreteBayesNet_FG | none of the required discrete functionality is exposed through Python |
-| easyPoint2KalmanFilter | ExtendedKalmanFilter not yet exposed through Python |
-| elaboratePoint2KalmanFilter | GaussianSequentialSolver not yet exposed through Python |
-| FisheyeExample | :heavy_check_mark: |
-| HMMExample | :heavy_check_mark: |
+| [easyPoint2KalmanFilter](easyPoint2KalmanFilter.ipynb) | ExtendedKalmanFilter not yet exposed through Python |
+| [elaboratePoint2KalmanFilter](elaboratePoint2KalmanFilter.ipynb) | GaussianSequentialSolver not yet exposed through Python |
+| [FisheyeExample](FisheyeExample.ipynb) | :heavy_check_mark: |
+| [HMMExample](HMMExample.ipynb) | :heavy_check_mark: |
| ImuFactorsExample2 | :heavy_check_mark: |
| ImuFactorsExample | |
| IMUKittiExampleGPS | :heavy_check_mark: |
@@ -20,22 +20,22 @@
| LocalizationExample | :heavy_check_mark: |
| METISOrderingExample | |
| OdometryExample | :heavy_check_mark: |
-| PlanarSLAMExample | :heavy_check_mark: |
-| Pose2SLAMExample | :heavy_check_mark: |
+| [PlanarSLAMExample](PlanarSLAMExample.ipynb) | :heavy_check_mark: |
+| [Pose2SLAMExample](Pose2SLAMExample.ipynb) | :heavy_check_mark: |
| Pose2SLAMExampleExpressions | ExpressionFactorGraph not yet exposed through Python |
| Pose2SLAMExample_g2o | :heavy_check_mark: |
| Pose2SLAMExample_graph | :heavy_check_mark: |
| Pose2SLAMExample_graphviz | :heavy_check_mark: |
| Pose2SLAMExample_lago | lago not yet exposed through Python |
-| Pose2SLAMStressTest | :heavy_check_mark: |
-| Pose2SLAMwSPCG | :heavy_check_mark: |
+| [Pose2SLAMStressTest](Pose2SLAMStressTest.ipynb) | :heavy_check_mark: |
+| [Pose2SLAMwSPCG](Pose2SLAMwSPCG.ipynb) | :heavy_check_mark: |
| Pose3Localization | |
| Pose3SLAMExample_changeKeys | |
| Pose3SLAMExampleExpressions_BearingRangeWithTransform | |
| Pose3SLAMExample_g2o | :heavy_check_mark: |
| Pose3SLAMExample_initializePose3Chordal | :heavy_check_mark: |
| Pose3SLAMExample_initializePose3Gradient | |
-| RangeISAMExample_plaza2 | :heavy_check_mark: |
+| [RangeISAMExample_plaza2](RangeISAMExample_plaza2.ipynb) | :heavy_check_mark: |
| SelfCalibrationExample | :heavy_check_mark: |
| SFMdata | :heavy_check_mark: |
| SFMExample_bal_COLAMD_METIS | |
@@ -48,8 +48,8 @@
| ShonanAveragingCLI | :heavy_check_mark: |
| SimpleRotation | :heavy_check_mark: |
| SolverComparer | |
-| StereoVOExample | :heavy_check_mark: |
-| StereoVOExample_large | :heavy_check_mark: |
+| [StereoVOExample](StereoVOExample.ipynb) | :heavy_check_mark: |
+| [StereoVOExample_large](StereoVOExample_large.ipynb) | :heavy_check_mark: |
| TimeTBB | |
| UGM_chain | discrete functionality not yet exposed |
| UGM_small | discrete functionality not yet exposed |
@@ -57,8 +57,29 @@
| VisualISAMExample | :heavy_check_mark: |
Extra Examples (with no C++ equivalent)
+- [FitBasisExample](FitBasisExample.ipynb)
- DogLegOptimizerExample
- GPSFactorExample
- PlanarManipulatorExample
- PreintegrationExample
- SFMData
+
+Additional Notebook Examples
+
+- [BearingRange3DExample](BearingRange3DExample.ipynb)
+- [DiscreteBayesTree](DiscreteBayesTree.ipynb)
+- [DiscreteMotionModel](DiscreteMotionModel.ipynb)
+- [DiscreteSwitching](DiscreteSwitching.ipynb)
+- [EKF_SLAM](EKF_SLAM.ipynb)
+- [EqF](EqF.ipynb)
+- [Gal3ImuASVExample](Gal3ImuASVExample.ipynb)
+- [Gal3ImuExample](Gal3ImuExample.ipynb)
+- [Gal3ImuNEESReset](Gal3ImuNEESReset.ipynb)
+- [LQRExample](LQRExample.ipynb)
+- [NavStateImuASVExample](NavStateImuASVExample.ipynb)
+- [NavStateImuExample](NavStateImuExample.ipynb)
+- [NonlinearEqualityExample](NonlinearEqualityExample.ipynb)
+- [RangeSLAMExample_plaza2](RangeSLAMExample_plaza2.ipynb)
+- [SL4SLAMExample](SL4SLAMExample.ipynb)
+- [SinglePointPositioningExample](SinglePointPositioningExample.ipynb)
+- [iLQRExample](iLQRExample.ipynb)