Merge branch 'develop' into feature/LogmapDerivative

# Conflicts:
#	gtsam/geometry/doc/Rot3.ipynb
release/4.3a0
Frank Dellaert 2025-04-20 08:50:57 -04:00
commit 795782d449
34 changed files with 2926 additions and 316 deletions

View File

@ -14,17 +14,47 @@ export PYTHON="python${PYTHON_VERSION}"
if [ "$(uname)" == "Linux" ]; then if [ "$(uname)" == "Linux" ]; then
# manylinux2014 is based on CentOS 7, so use yum to install dependencies # manylinux2014 is based on CentOS 7, so use yum to install dependencies
yum install -y wget yum install -y wget doxygen
# Install Boost from source
wget https://archives.boost.io/release/1.87.0/source/boost_1_87_0.tar.gz --quiet
tar -xzf boost_1_87_0.tar.gz
cd boost_1_87_0
./bootstrap.sh --prefix=/opt/boost
./b2 install --prefix=/opt/boost --with=all
cd ..
elif [ "$(uname)" == "Darwin" ]; then elif [ "$(uname)" == "Darwin" ]; then
brew install wget cmake boost brew install cmake doxygen
# If MACOSX_DEPLOYMENT_TARGET is not explicitly set, default to the version of the host system.
if [[ -z "${MACOSX_DEPLOYMENT_TARGET}" ]]; then
export MACOSX_DEPLOYMENT_TARGET="$(sw_vers -productVersion | cut -d '.' -f 1-2)"
fi
fi
# Install Boost from source
wget https://archives.boost.io/release/1.87.0/source/boost_1_87_0.tar.gz --quiet
tar -xzf boost_1_87_0.tar.gz
cd boost_1_87_0
BOOST_PREFIX="$HOME/opt/boost"
./bootstrap.sh --prefix=${BOOST_PREFIX}
if [ "$(uname)" == "Linux" ]; then
./b2 install --prefix=${BOOST_PREFIX} --with=all -d0
elif [ "$(uname)" == "Darwin" ]; then
./b2 install --prefix=${BOOST_PREFIX} --with=all -d0 \
cxxflags="-mmacosx-version-min=${MACOSX_DEPLOYMENT_TARGET}" \
linkflags="-mmacosx-version-min=${MACOSX_DEPLOYMENT_TARGET}"
fi
cd ..
# Export paths so CMake or build system can find Boost
export BOOST_ROOT="${BOOST_PREFIX}"
export BOOST_INCLUDEDIR="${BOOST_PREFIX}/include"
export BOOST_LIBRARYDIR="${BOOST_PREFIX}/lib"
# Ensure runtime linker can find Boost libraries
export LD_LIBRARY_PATH="${BOOST_LIBRARYDIR}:$LD_LIBRARY_PATH" # For Linux
export REPAIR_LIBRARY_PATH="${BOOST_LIBRARYDIR}:$DYLD_LIBRARY_PATH" # For macOS, REPAIR_LIBRARY_PATH is used by delocate
if [ "$(uname)" == "Darwin" ]; then
# Explicitly add rpath to Boost dylibs so delocate can find them
for dylib in ${BOOST_LIBRARYDIR}/*.dylib; do
install_name_tool -add_rpath "@loader_path" "$dylib"
done
fi fi
$(which $PYTHON) -m pip install -r $PROJECT_DIR/python/dev_requirements.txt $(which $PYTHON) -m pip install -r $PROJECT_DIR/python/dev_requirements.txt
@ -48,11 +78,15 @@ cmake $PROJECT_DIR \
-DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \ -DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \
-DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \ -DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \
-DGTSAM_ALLOW_DEPRECATED_SINCE_V43=OFF \ -DGTSAM_ALLOW_DEPRECATED_SINCE_V43=OFF \
-DCMAKE_INSTALL_PREFIX=$PROJECT_DIR/gtsam_install -DCMAKE_INSTALL_PREFIX=$PROJECT_DIR/gtsam_install \
-DGTSAM_GENERATE_DOC_XML=1 \
-DGTWRAP_ADD_DOCSTRINGS=ON
cd $PROJECT_DIR/build/python # Generate Doxygen XML documentation
doxygen build/doc/Doxyfile
# Install the Python wrapper module and generate Python stubs # Install the Python wrapper module and generate Python stubs
cd $PROJECT_DIR/build/python
if [ "$(uname)" == "Linux" ]; then if [ "$(uname)" == "Linux" ]; then
make -j $(nproc) install make -j $(nproc) install
make -j $(nproc) python-stubs make -j $(nproc) python-stubs

View File

@ -76,22 +76,40 @@ jobs:
manylinux_image: manylinux2014 manylinux_image: manylinux2014
# MacOS x86_64 # MacOS x86_64
# - os: macos-13 - os: macos-13
# python_version: "3.10" python_version: "3.10"
# cibw_python_version: 310 cibw_python_version: 310
# platform_id: macosx_x86_64 platform_id: macosx_x86_64
# - os: macos-13 - os: macos-13
# python_version: "3.11" python_version: "3.11"
# cibw_python_version: 311 cibw_python_version: 311
# platform_id: macosx_x86_64 platform_id: macosx_x86_64
# - os: macos-13 - os: macos-13
# python_version: "3.12" python_version: "3.12"
# cibw_python_version: 312 cibw_python_version: 312
# platform_id: macosx_x86_64 platform_id: macosx_x86_64
# - os: macos-13 - os: macos-13
# python_version: "3.13" python_version: "3.13"
# cibw_python_version: 313 cibw_python_version: 313
# platform_id: macosx_x86_64 platform_id: macosx_x86_64
# MacOS arm64
- os: macos-14
python_version: "3.10"
cibw_python_version: 310
platform_id: macosx_arm64
- os: macos-14
python_version: "3.11"
cibw_python_version: 311
platform_id: macosx_arm64
- os: macos-14
python_version: "3.12"
cibw_python_version: 312
platform_id: macosx_arm64
- os: macos-14
python_version: "3.13"
cibw_python_version: 313
platform_id: macosx_arm64
steps: steps:
- name: Checkout - name: Checkout
@ -130,6 +148,14 @@ jobs:
run: | run: |
cmake . -B build -DGTSAM_BUILD_PYTHON=1 -DGTSAM_PYTHON_VERSION=${{ matrix.python_version }} cmake . -B build -DGTSAM_BUILD_PYTHON=1 -DGTSAM_PYTHON_VERSION=${{ matrix.python_version }}
# If on macOS, we previously installed boost using homebrew for the first build.
# We need to uninstall it before building the wheels with cibuildwheel, which will
# install boost from source.
- name: Uninstall Boost (MacOS)
if: runner.os == 'macOS'
run: |
brew uninstall boost
- name: Build and test wheels - name: Build and test wheels
env: env:
# Generate the platform identifier. See https://cibuildwheel.pypa.io/en/stable/options/#build-skip. # Generate the platform identifier. See https://cibuildwheel.pypa.io/en/stable/options/#build-skip.
@ -139,6 +165,13 @@ jobs:
CIBW_ARCHS: all CIBW_ARCHS: all
CIBW_ENVIRONMENT_PASS_LINUX: DEVELOP TIMESTAMP CIBW_ENVIRONMENT_PASS_LINUX: DEVELOP TIMESTAMP
# Set the minimum required MacOS version for the wheels.
MACOSX_DEPLOYMENT_TARGET: 10.15
# Set DYLD_LIBRARY_PATH to REPAIR_LIBRARY_PATH, which is set in cibw_before_all.sh. REPAIR_LIBRARY_PATH
# simply appends BOOST_LIBRARYDIR to the path, which is required during during link-time repair.
CIBW_REPAIR_WHEEL_COMMAND_MACOS: DYLD_LIBRARY_PATH=$REPAIR_LIBRARY_PATH delocate-wheel --require-archs {delocate_archs} -w {dest_dir} -v {wheel}
# Use build instead of pip wheel to build the wheels. This is recommended by PyPA. # Use build instead of pip wheel to build the wheels. This is recommended by PyPA.
# See https://cibuildwheel.pypa.io/en/stable/options/#build-frontend. # See https://cibuildwheel.pypa.io/en/stable/options/#build-frontend.
CIBW_BUILD_FRONTEND: "build" CIBW_BUILD_FRONTEND: "build"

View File

@ -39,7 +39,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -30,7 +30,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -1,45 +1,31 @@
{ {
"nbformat": 4,
"nbformat_minor": 0,
"metadata": {
"colab": {
"provenance": []
},
"kernelspec": {
"name": "python3",
"display_name": "Python 3"
},
"language_info": {
"name": "python"
}
},
"cells": [ "cells": [
{ {
"cell_type": "markdown", "cell_type": "markdown",
"source": [
"# Rot2"
],
"metadata": { "metadata": {
"id": "-3NPWeM5nKTz" "id": "-3NPWeM5nKTz"
} },
"source": [
"# Rot2"
]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"source": [
"A `gtsam.Rot2` represents rotation in 2D space. It models a 2D rotation in the Special Orthogonal Group $\\text{SO}(2)$."
],
"metadata": { "metadata": {
"id": "zKQLwRQWvRAW" "id": "zKQLwRQWvRAW"
} },
"source": [
"A `gtsam.Rot2` represents rotation in 2D space. It models a 2D rotation in the Special Orthogonal Group $\\text{SO}(2)$."
]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"source": [
"<a href=\"https://colab.research.google.com/github/borglab/gtsam/blob/develop/gtsam/geometry/doc/Rot2.ipynb\" target=\"_parent\"><img src=\"https://colab.research.google.com/assets/colab-badge.svg\" alt=\"Open In Colab\"/></a>"
],
"metadata": { "metadata": {
"id": "1MUA6xip5fG4" "id": "1MUA6xip5fG4"
} },
"source": [
"<a href=\"https://colab.research.google.com/github/borglab/gtsam/blob/develop/gtsam/geometry/doc/Rot2.ipynb\" target=\"_parent\"><img src=\"https://colab.research.google.com/assets/colab-badge.svg\" alt=\"Open In Colab\"/></a>"
]
}, },
{ {
"cell_type": "code", "cell_type": "code",
@ -49,41 +35,70 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {
"cell_type": "code", "cell_type": "code",
"source": [ "execution_count": 6,
"from gtsam import Rot2, Point2\n",
"import numpy as np"
],
"metadata": { "metadata": {
"id": "-dp28DoR7WsD" "id": "-dp28DoR7WsD"
}, },
"execution_count": 6, "outputs": [],
"outputs": [] "source": [
"from gtsam import Rot2, Point2\n",
"import numpy as np"
]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"source": [
"## Initialization and properties"
],
"metadata": { "metadata": {
"id": "gZRXZTrJ7mqJ" "id": "gZRXZTrJ7mqJ"
} },
"source": [
"## Initialization and properties"
]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"source": [
"A `Rot2` can be initialized with no arguments, which yields the identity rotation, or it can be constructed from an angle in radians, degrees, cos-sin form, or the bearing or arctangent of a 2D point. `Rot2` uses radians to communicate angle by default."
],
"metadata": { "metadata": {
"id": "PK-HWTDm7sU4" "id": "PK-HWTDm7sU4"
} },
"source": [
"A `Rot2` can be initialized with no arguments, which yields the identity rotation, or it can be constructed from an angle in radians, degrees, cos-sin form, or the bearing or arctangent of a 2D point. `Rot2` uses radians to communicate angle by default."
]
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 58,
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "oIakIOAB9afi",
"outputId": "c2cb005d-056f-4a4f-b5ff-2226be1ba3e7"
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Identities:\n",
"0.0\n",
"0.0\n",
"Radians:\n",
"1.5707963267948966\n",
"1.5707963267948966\n",
"Degrees:\n",
"1.5707963267948966\n",
"Cos-Sin:\n",
"0.5235987755982988\n",
"Bearing:\n",
"0.7853981633974483\n",
"0.7853981633974483\n"
]
}
],
"source": [ "source": [
"# The identity rotation has theta = 0.\n", "# The identity rotation has theta = 0.\n",
"identity = Rot2()\n", "identity = Rot2()\n",
@ -118,39 +133,13 @@
"# Or with atan2(y, x), which accomplishes the same thing.\n", "# Or with atan2(y, x), which accomplishes the same thing.\n",
"atan = Rot2.atan2(p[1], p[0])\n", "atan = Rot2.atan2(p[1], p[0])\n",
"print(atan.theta())" "print(atan.theta())"
],
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "oIakIOAB9afi",
"outputId": "c2cb005d-056f-4a4f-b5ff-2226be1ba3e7"
},
"execution_count": 58,
"outputs": [
{
"output_type": "stream",
"name": "stdout",
"text": [
"Identities:\n",
"0.0\n",
"0.0\n",
"Radians:\n",
"1.5707963267948966\n",
"1.5707963267948966\n",
"Degrees:\n",
"1.5707963267948966\n",
"Cos-Sin:\n",
"0.5235987755982988\n",
"Bearing:\n",
"0.7853981633974483\n",
"0.7853981633974483\n"
]
}
] ]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"metadata": {
"id": "rHovUXbUys5r"
},
"source": [ "source": [
"The following properties are available from the standard interface:\n", "The following properties are available from the standard interface:\n",
"- `theta()` (in radians)\n", "- `theta()` (in radians)\n",
@ -161,25 +150,11 @@
"\\cos\\theta & -\\sin\\theta \\\\\n", "\\cos\\theta & -\\sin\\theta \\\\\n",
"\\sin\\theta & \\cos\\theta\n", "\\sin\\theta & \\cos\\theta\n",
"\\end{bmatrix}$)" "\\end{bmatrix}$)"
], ]
"metadata": {
"id": "rHovUXbUys5r"
}
}, },
{ {
"cell_type": "code", "cell_type": "code",
"source": [ "execution_count": 18,
"example_rot = Rot2(3 * np.pi / 4)\n",
"\n",
"# The default print statement includes 'theta: ' and a newline at the end.\n",
"print(example_rot)\n",
"\n",
"print(f\"Radians: {example_rot.theta()}\")\n",
"print(f\"Degrees: {example_rot.degrees()}\")\n",
"print(f\"Cosine: {example_rot.c()}\")\n",
"print(f\"Sine: {example_rot.s()}\")\n",
"print(f\"Matrix:\\n{example_rot.matrix()}\")\n"
],
"metadata": { "metadata": {
"colab": { "colab": {
"base_uri": "https://localhost:8080/" "base_uri": "https://localhost:8080/"
@ -187,11 +162,10 @@
"id": "P5OXTjFu2DeX", "id": "P5OXTjFu2DeX",
"outputId": "70848419-c055-44bc-de11-08e8f93fe3bf" "outputId": "70848419-c055-44bc-de11-08e8f93fe3bf"
}, },
"execution_count": 18,
"outputs": [ "outputs": [
{ {
"output_type": "stream",
"name": "stdout", "name": "stdout",
"output_type": "stream",
"text": [ "text": [
"theta: 2.35619\n", "theta: 2.35619\n",
"\n", "\n",
@ -204,28 +178,59 @@
" [ 0.70710678 -0.70710678]]\n" " [ 0.70710678 -0.70710678]]\n"
] ]
} }
],
"source": [
"example_rot = Rot2(3 * np.pi / 4)\n",
"\n",
"# The default print statement includes 'theta: ' and a newline at the end.\n",
"print(example_rot)\n",
"\n",
"print(f\"Radians: {example_rot.theta()}\")\n",
"print(f\"Degrees: {example_rot.degrees()}\")\n",
"print(f\"Cosine: {example_rot.c()}\")\n",
"print(f\"Sine: {example_rot.s()}\")\n",
"print(f\"Matrix:\\n{example_rot.matrix()}\")\n"
] ]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"source": [
"## Basic operations"
],
"metadata": { "metadata": {
"id": "PpqHUDnl5rTW" "id": "PpqHUDnl5rTW"
} },
"source": [
"## Basic operations"
]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"source": [
"For basic use, a `Rot2` can rotate and unrotate a point."
],
"metadata": { "metadata": {
"id": "sa4qx58n5tG9" "id": "sa4qx58n5tG9"
} },
"source": [
"For basic use, a `Rot2` can rotate and unrotate a point."
]
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 25,
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "yaBKjGn05_-c",
"outputId": "fb89fe09-b2b8-496d-e835-f379d197a4eb"
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Rotated: [-2.82842712e+00 2.22044605e-16]\n",
"Unrotated: [-2. 2.]\n",
"Unrotated again: [-2.22044605e-16 2.82842712e+00]\n"
]
}
],
"source": [ "source": [
"rot = Rot2.fromDegrees(45)\n", "rot = Rot2.fromDegrees(45)\n",
"p = Point2(-2, 2)\n", "p = Point2(-2, 2)\n",
@ -237,38 +242,37 @@
"print(f\"Unrotated: {rot.unrotate(rotated)}\")\n", "print(f\"Unrotated: {rot.unrotate(rotated)}\")\n",
"# Of course, unrotating a point you didn't rotate just rotates it backwards.\n", "# Of course, unrotating a point you didn't rotate just rotates it backwards.\n",
"print(f\"Unrotated again: {rot.unrotate(p)}\")" "print(f\"Unrotated again: {rot.unrotate(p)}\")"
],
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "yaBKjGn05_-c",
"outputId": "fb89fe09-b2b8-496d-e835-f379d197a4eb"
},
"execution_count": 25,
"outputs": [
{
"output_type": "stream",
"name": "stdout",
"text": [
"Rotated: [-2.82842712e+00 2.22044605e-16]\n",
"Unrotated: [-2. 2.]\n",
"Unrotated again: [-2.22044605e-16 2.82842712e+00]\n"
]
}
] ]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"source": [
"Also, the `equals()` function allows for comparison of two `Rot2` objects with a tolerance."
],
"metadata": { "metadata": {
"id": "RVFCoBpW6Bvh" "id": "RVFCoBpW6Bvh"
} },
"source": [
"Also, the `equals()` function allows for comparison of two `Rot2` objects with a tolerance."
]
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 31,
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "m74YbK5h6CPU",
"outputId": "1b16695e-cdfe-4348-875f-c41d8b4a3b26"
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"True\n",
"False\n"
]
}
],
"source": [ "source": [
"eq_rads = Rot2(np.pi / 4)\n", "eq_rads = Rot2(np.pi / 4)\n",
"eq_degs = Rot2.fromDegrees(45)\n", "eq_degs = Rot2.fromDegrees(45)\n",
@ -277,48 +281,60 @@
"\n", "\n",
"# Direct comparison does not work for Rot2.\n", "# Direct comparison does not work for Rot2.\n",
"print(eq_rads == eq_degs)" "print(eq_rads == eq_degs)"
],
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "m74YbK5h6CPU",
"outputId": "1b16695e-cdfe-4348-875f-c41d8b4a3b26"
},
"execution_count": 31,
"outputs": [
{
"output_type": "stream",
"name": "stdout",
"text": [
"True\n",
"False\n"
]
}
] ]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"source": [
"## Lie group $\\text{SO}(2)$"
],
"metadata": { "metadata": {
"id": "ko9KSZgd4bCp" "id": "ko9KSZgd4bCp"
} },
"source": [
"## Lie group $\\text{SO}(2)$"
]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"metadata": {
"id": "76D2KkX241zX"
},
"source": [ "source": [
"### Group operations\n", "### Group operations\n",
"\n", "\n",
"`Rot2` implements the group operations `inverse`, `compose`, `between` and `identity`. For more information on groups and their use here, see [GTSAM concepts](https://gtsam.org/notes/GTSAM-Concepts.html)." "`Rot2` implements the group operations `inverse`, `compose`, `between` and `identity`. For more information on groups and their use here, see [GTSAM concepts](https://gtsam.org/notes/GTSAM-Concepts.html)."
], ]
"metadata": {
"id": "76D2KkX241zX"
}
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 57,
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "QZ_NTeXK87Wq",
"outputId": "12af920d-8f86-473d-88ab-ee57d316cb72"
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Inverse:\n",
"theta: -0.523599\n",
"\n",
"Compose:\n",
"theta: 1.5708\n",
"\n",
"theta: 1.5708\n",
"\n",
"Between:\n",
"theta: 0.523599\n",
"\n",
"Identity:\n",
"theta: 0\n",
"\n"
]
}
],
"source": [ "source": [
"a = Rot2(np.pi / 6)\n", "a = Rot2(np.pi / 6)\n",
"b = Rot2(np.pi / 3)\n", "b = Rot2(np.pi / 3)\n",
@ -340,51 +356,44 @@
"# The identity is theta = 0, as above.\n", "# The identity is theta = 0, as above.\n",
"print(\"Identity:\")\n", "print(\"Identity:\")\n",
"print(Rot2.Identity())" "print(Rot2.Identity())"
],
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "QZ_NTeXK87Wq",
"outputId": "12af920d-8f86-473d-88ab-ee57d316cb72"
},
"execution_count": 57,
"outputs": [
{
"output_type": "stream",
"name": "stdout",
"text": [
"Inverse:\n",
"theta: -0.523599\n",
"\n",
"Compose:\n",
"theta: 1.5708\n",
"\n",
"theta: 1.5708\n",
"\n",
"Between:\n",
"theta: 0.523599\n",
"\n",
"Identity:\n",
"theta: 0\n",
"\n"
]
}
] ]
}, },
{ {
"cell_type": "markdown", "cell_type": "markdown",
"metadata": {
"id": "YfiYuVpL-cgq"
},
"source": [ "source": [
"## Lie group operations\n", "## Lie group operations\n",
"\n", "\n",
"`Rot2` implements the Lie group operations for exponential mapping and log mapping. For more information on Lie groups and their use here, see [GTSAM concepts](https://gtsam.org/notes/GTSAM-Concepts.html)." "`Rot2` implements the Lie group operations for exponential mapping and log mapping. For more information on Lie groups and their use here, see [GTSAM concepts](https://gtsam.org/notes/GTSAM-Concepts.html)."
], ]
"metadata": {
"id": "YfiYuVpL-cgq"
}
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 54,
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "4JiDEGqG-van",
"outputId": "56047f8d-3349-4ee6-e73c-cd2fa1efb95d"
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"theta: 1.5708\n",
"\n",
"theta: 3.14159\n",
"\n",
"[1.57079633]\n",
"[-0.78539816]\n",
"[-0.78539816]\n"
]
}
],
"source": [ "source": [
"r = Rot2(np.pi / 2)\n", "r = Rot2(np.pi / 2)\n",
"w = Rot2(np.pi / 4)\n", "w = Rot2(np.pi / 4)\n",
@ -405,30 +414,21 @@
"# logmap is the same as calculating the coordinate of the second Rot2 in the\n", "# logmap is the same as calculating the coordinate of the second Rot2 in the\n",
"# local frame of the first, which localCoordinates (inherited from LieGroup) does.\n", "# local frame of the first, which localCoordinates (inherited from LieGroup) does.\n",
"print(r.localCoordinates(w))\n" "print(r.localCoordinates(w))\n"
],
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "4JiDEGqG-van",
"outputId": "56047f8d-3349-4ee6-e73c-cd2fa1efb95d"
},
"execution_count": 54,
"outputs": [
{
"output_type": "stream",
"name": "stdout",
"text": [
"theta: 1.5708\n",
"\n",
"theta: 3.14159\n",
"\n",
"[1.57079633]\n",
"[-0.78539816]\n",
"[-0.78539816]\n"
]
}
] ]
} }
] ],
} "metadata": {
"colab": {
"provenance": []
},
"kernelspec": {
"display_name": "Python 3",
"name": "python3"
},
"language_info": {
"name": "python"
}
},
"nbformat": 4,
"nbformat_minor": 0
}

View File

@ -35,7 +35,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -52,7 +52,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -52,7 +52,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -63,7 +63,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -40,7 +40,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -38,7 +38,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -44,7 +44,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -51,7 +51,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -53,7 +53,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -42,7 +42,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -44,7 +44,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -38,7 +38,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -38,7 +38,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -17,7 +17,7 @@
"source": [ "source": [
"An `Ordering` specifies the order in which variables are eliminated during inference (e.g., Gaussian elimination, multifrontal QR). The choice of ordering significantly impacts the computational cost and fill-in (sparsity) of the resulting Bayes net or Bayes tree.\n", "An `Ordering` specifies the order in which variables are eliminated during inference (e.g., Gaussian elimination, multifrontal QR). The choice of ordering significantly impacts the computational cost and fill-in (sparsity) of the resulting Bayes net or Bayes tree.\n",
"\n", "\n",
"GTSAM provides several algorithms to compute good orderings automatically (like COLAMD, METIS) or allows you to specify a custom ordering." "GTSAM provides several algorithms to compute good orderings automatically, such as COLAMD and METIS, or allows you to specify a custom ordering."
] ]
}, },
{ {
@ -40,22 +40,23 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 15, "execution_count": 21,
"metadata": { "metadata": {
"id": "ordering_import_code" "id": "ordering_import_code"
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"import gtsam\n", "import gtsam\n",
"from gtsam import Ordering, VariableIndex\n", "from gtsam import Ordering\n",
"# Need a graph type for automatic ordering\n", "# Need graph types\n",
"from gtsam import SymbolicFactorGraph\n", "from gtsam import SymbolicFactorGraph\n",
"from gtsam import symbol_shorthand\n", "from gtsam import symbol_shorthand\n",
"import graphviz\n",
"\n", "\n",
"X = symbol_shorthand.X\n", "X = symbol_shorthand.X\n",
"L = symbol_shorthand.L" "L = symbol_shorthand.L"
@ -74,7 +75,7 @@
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 16, "execution_count": 22,
"metadata": { "metadata": {
"colab": { "colab": {
"base_uri": "https://localhost:8080/" "base_uri": "https://localhost:8080/"
@ -99,21 +100,14 @@
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 18, "execution_count": 23,
"metadata": { "metadata": {},
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "ordering_auto_code",
"outputId": "789abcde-f012-3456-789a-bcdef0123456"
},
"outputs": [ "outputs": [
{ {
"name": "stdout", "name": "stdout",
"output_type": "stream", "output_type": "stream",
"text": [ "text": [
"COLAMD Ordering: Position 0: l1, x0, x1, l2, x2\n", "COLAMD Ordering: Position 0: l1, x0, x1, l2, x2\n"
"Constrained COLAMD (x0, x2 last): Position 0: l2, l1, x1, x2, x0\n"
] ]
} }
], ],
@ -129,13 +123,672 @@
"graph.push_factor(X(1), L(2))\n", "graph.push_factor(X(1), L(2))\n",
"graph.push_factor(X(2), L(2))\n", "graph.push_factor(X(2), L(2))\n",
"\n", "\n",
"# COLAMD (Column Approximate Minimum Degree) ordering\n", "# COLAMD ordering\n",
"colamd_ordering = Ordering.ColamdSymbolicFactorGraph(graph)\n", "colamd_ordering = Ordering.ColamdSymbolicFactorGraph(graph)\n",
"colamd_ordering.print(\"COLAMD Ordering: \")\n", "colamd_ordering.print(\"COLAMD Ordering: \")"
]
},
{
"cell_type": "markdown",
"metadata": {
"id": "ordering_auto_intro_md"
},
"source": [
"## Automatic Ordering Algorithms: COLAMD vs METIS\n",
"\n", "\n",
"# Constrained COLAMD (force x0 and x2 to be eliminated last)\n", "GTSAM provides algorithms to automatically compute an elimination ordering from a factor graph. Two common algorithms are:\n",
"constrained_ordering = Ordering.ColamdConstrainedLastSymbolicFactorGraph(graph, gtsam.KeyVector([X(0), X(2)]))\n", "\n",
"constrained_ordering.print(\"Constrained COLAMD (x0, x2 last): \")" "1. **COLAMD (Column Approximate Minimum Degree):** A greedy algorithm that aims to minimize *fill-in* at each elimination step. It typically produces orderings that are good for sparse direct methods executed sequentially.\n",
"2. **METIS:** A graph partitioning algorithm. It aims to find orderings that partition the graph well, often leading to more balanced elimination trees which can be beneficial for parallel computation and sometimes reduce overall fill-in compared to purely local greedy methods like COLAMD, especially on large, structured problems.\n",
"\n",
"Let's illustrate the difference using a 2D grid factor graph."
]
},
{
"cell_type": "code",
"execution_count": 24,
"metadata": {
"id": "ordering_grid_setup_code"
},
"outputs": [],
"source": [
"# Create a 3x4 grid graph\n",
"ROWS, COLS = 3, 4\n",
"\n",
"# Use 'x' symbols for grid nodes\n",
"X_grid = lambda r, c: X(10 * (r + 1) + c + 1)\n",
"\n",
"\n",
"def create_grid_graph():\n",
" \"\"\"Creates a SymbolicFactorGraph representing a 2D grid.\"\"\"\n",
" graph = SymbolicFactorGraph()\n",
" keys = []\n",
" positions = {}\n",
" for r in range(ROWS):\n",
" for c in range(COLS):\n",
" key = X_grid(r, c)\n",
" positions[key] = gtsam.Point2(c, COLS-r)\n",
" keys.append(key)\n",
" # Add binary factors connecting to right and down neighbors\n",
" if c + 1 < COLS:\n",
" key_right = X_grid(r, c + 1)\n",
" graph.push_factor(key, key_right)\n",
" if r + 1 < ROWS:\n",
" key_down = X_grid(r + 1, c)\n",
" graph.push_factor(key, key_down)\n",
" return graph, keys, positions\n",
"\n",
"\n",
"grid_graph, grid_keys, positions = create_grid_graph()"
]
},
{
"cell_type": "markdown",
"metadata": {
"id": "ordering_grid_viz_md"
},
"source": [
"Here's the structure of our grid graph. Edges represent factors connecting variables (nodes)."
]
},
{
"cell_type": "code",
"execution_count": 25,
"metadata": {},
"outputs": [
{
"data": {
"image/svg+xml": [
"<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n",
"<!DOCTYPE svg PUBLIC \"-//W3C//DTD SVG 1.1//EN\"\n",
" \"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd\">\n",
"<!-- Generated by graphviz version 2.50.0 (0)\n",
" -->\n",
"<!-- Pages: 1 -->\n",
"<svg width=\"278pt\" height=\"188pt\"\n",
" viewBox=\"0.00 0.00 278.00 188.00\" xmlns=\"http://www.w3.org/2000/svg\" xmlns:xlink=\"http://www.w3.org/1999/xlink\">\n",
"<g id=\"graph0\" class=\"graph\" transform=\"scale(1 1) rotate(0) translate(4 184)\">\n",
"<polygon fill=\"white\" stroke=\"transparent\" points=\"-4,4 -4,-184 274,-184 274,4 -4,4\"/>\n",
"<!-- var8646911284551352331 -->\n",
"<g id=\"node1\" class=\"node\">\n",
"<title>var8646911284551352331</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"27\" cy=\"-162\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"27\" y=\"-158.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x11</text>\n",
"</g>\n",
"<!-- var8646911284551352332 -->\n",
"<g id=\"node2\" class=\"node\">\n",
"<title>var8646911284551352332</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"99\" cy=\"-162\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"99\" y=\"-158.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x12</text>\n",
"</g>\n",
"<!-- var8646911284551352331&#45;&#45;var8646911284551352332 -->\n",
"<g id=\"edge1\" class=\"edge\">\n",
"<title>var8646911284551352331&#45;&#45;var8646911284551352332</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M54.22,-162C59.95,-162 66.01,-162 71.74,-162\"/>\n",
"</g>\n",
"<!-- var8646911284551352341 -->\n",
"<g id=\"node5\" class=\"node\">\n",
"<title>var8646911284551352341</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"27\" cy=\"-90\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"27\" y=\"-86.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x21</text>\n",
"</g>\n",
"<!-- var8646911284551352331&#45;&#45;var8646911284551352341 -->\n",
"<g id=\"edge2\" class=\"edge\">\n",
"<title>var8646911284551352331&#45;&#45;var8646911284551352341</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M27,-143.83C27,-133 27,-119.29 27,-108.41\"/>\n",
"</g>\n",
"<!-- var8646911284551352333 -->\n",
"<g id=\"node3\" class=\"node\">\n",
"<title>var8646911284551352333</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"171\" cy=\"-162\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"171\" y=\"-158.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x13</text>\n",
"</g>\n",
"<!-- var8646911284551352332&#45;&#45;var8646911284551352333 -->\n",
"<g id=\"edge3\" class=\"edge\">\n",
"<title>var8646911284551352332&#45;&#45;var8646911284551352333</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M126.22,-162C131.95,-162 138.01,-162 143.74,-162\"/>\n",
"</g>\n",
"<!-- var8646911284551352342 -->\n",
"<g id=\"node6\" class=\"node\">\n",
"<title>var8646911284551352342</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"99\" cy=\"-90\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"99\" y=\"-86.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x22</text>\n",
"</g>\n",
"<!-- var8646911284551352332&#45;&#45;var8646911284551352342 -->\n",
"<g id=\"edge4\" class=\"edge\">\n",
"<title>var8646911284551352332&#45;&#45;var8646911284551352342</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M99,-143.83C99,-133 99,-119.29 99,-108.41\"/>\n",
"</g>\n",
"<!-- var8646911284551352334 -->\n",
"<g id=\"node4\" class=\"node\">\n",
"<title>var8646911284551352334</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"243\" cy=\"-162\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"243\" y=\"-158.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x14</text>\n",
"</g>\n",
"<!-- var8646911284551352333&#45;&#45;var8646911284551352334 -->\n",
"<g id=\"edge5\" class=\"edge\">\n",
"<title>var8646911284551352333&#45;&#45;var8646911284551352334</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M198.22,-162C203.95,-162 210.01,-162 215.74,-162\"/>\n",
"</g>\n",
"<!-- var8646911284551352343 -->\n",
"<g id=\"node7\" class=\"node\">\n",
"<title>var8646911284551352343</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"171\" cy=\"-90\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"171\" y=\"-86.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x23</text>\n",
"</g>\n",
"<!-- var8646911284551352333&#45;&#45;var8646911284551352343 -->\n",
"<g id=\"edge6\" class=\"edge\">\n",
"<title>var8646911284551352333&#45;&#45;var8646911284551352343</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M171,-143.83C171,-133 171,-119.29 171,-108.41\"/>\n",
"</g>\n",
"<!-- var8646911284551352344 -->\n",
"<g id=\"node8\" class=\"node\">\n",
"<title>var8646911284551352344</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"243\" cy=\"-90\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"243\" y=\"-86.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x24</text>\n",
"</g>\n",
"<!-- var8646911284551352334&#45;&#45;var8646911284551352344 -->\n",
"<g id=\"edge7\" class=\"edge\">\n",
"<title>var8646911284551352334&#45;&#45;var8646911284551352344</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M243,-143.83C243,-133 243,-119.29 243,-108.41\"/>\n",
"</g>\n",
"<!-- var8646911284551352341&#45;&#45;var8646911284551352342 -->\n",
"<g id=\"edge8\" class=\"edge\">\n",
"<title>var8646911284551352341&#45;&#45;var8646911284551352342</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M54.22,-90C59.95,-90 66.01,-90 71.74,-90\"/>\n",
"</g>\n",
"<!-- var8646911284551352351 -->\n",
"<g id=\"node9\" class=\"node\">\n",
"<title>var8646911284551352351</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"27\" cy=\"-18\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"27\" y=\"-14.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x31</text>\n",
"</g>\n",
"<!-- var8646911284551352341&#45;&#45;var8646911284551352351 -->\n",
"<g id=\"edge9\" class=\"edge\">\n",
"<title>var8646911284551352341&#45;&#45;var8646911284551352351</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M27,-71.83C27,-61 27,-47.29 27,-36.41\"/>\n",
"</g>\n",
"<!-- var8646911284551352342&#45;&#45;var8646911284551352343 -->\n",
"<g id=\"edge10\" class=\"edge\">\n",
"<title>var8646911284551352342&#45;&#45;var8646911284551352343</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M126.22,-90C131.95,-90 138.01,-90 143.74,-90\"/>\n",
"</g>\n",
"<!-- var8646911284551352352 -->\n",
"<g id=\"node10\" class=\"node\">\n",
"<title>var8646911284551352352</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"99\" cy=\"-18\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"99\" y=\"-14.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x32</text>\n",
"</g>\n",
"<!-- var8646911284551352342&#45;&#45;var8646911284551352352 -->\n",
"<g id=\"edge11\" class=\"edge\">\n",
"<title>var8646911284551352342&#45;&#45;var8646911284551352352</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M99,-71.83C99,-61 99,-47.29 99,-36.41\"/>\n",
"</g>\n",
"<!-- var8646911284551352343&#45;&#45;var8646911284551352344 -->\n",
"<g id=\"edge12\" class=\"edge\">\n",
"<title>var8646911284551352343&#45;&#45;var8646911284551352344</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M198.22,-90C203.95,-90 210.01,-90 215.74,-90\"/>\n",
"</g>\n",
"<!-- var8646911284551352353 -->\n",
"<g id=\"node11\" class=\"node\">\n",
"<title>var8646911284551352353</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"171\" cy=\"-18\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"171\" y=\"-14.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x33</text>\n",
"</g>\n",
"<!-- var8646911284551352343&#45;&#45;var8646911284551352353 -->\n",
"<g id=\"edge13\" class=\"edge\">\n",
"<title>var8646911284551352343&#45;&#45;var8646911284551352353</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M171,-71.83C171,-61 171,-47.29 171,-36.41\"/>\n",
"</g>\n",
"<!-- var8646911284551352354 -->\n",
"<g id=\"node12\" class=\"node\">\n",
"<title>var8646911284551352354</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"243\" cy=\"-18\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"243\" y=\"-14.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x34</text>\n",
"</g>\n",
"<!-- var8646911284551352344&#45;&#45;var8646911284551352354 -->\n",
"<g id=\"edge14\" class=\"edge\">\n",
"<title>var8646911284551352344&#45;&#45;var8646911284551352354</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M243,-71.83C243,-61 243,-47.29 243,-36.41\"/>\n",
"</g>\n",
"<!-- var8646911284551352351&#45;&#45;var8646911284551352352 -->\n",
"<g id=\"edge15\" class=\"edge\">\n",
"<title>var8646911284551352351&#45;&#45;var8646911284551352352</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M54.22,-18C59.95,-18 66.01,-18 71.74,-18\"/>\n",
"</g>\n",
"<!-- var8646911284551352352&#45;&#45;var8646911284551352353 -->\n",
"<g id=\"edge16\" class=\"edge\">\n",
"<title>var8646911284551352352&#45;&#45;var8646911284551352353</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M126.22,-18C131.95,-18 138.01,-18 143.74,-18\"/>\n",
"</g>\n",
"<!-- var8646911284551352353&#45;&#45;var8646911284551352354 -->\n",
"<g id=\"edge17\" class=\"edge\">\n",
"<title>var8646911284551352353&#45;&#45;var8646911284551352354</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M198.22,-18C203.95,-18 210.01,-18 215.74,-18\"/>\n",
"</g>\n",
"</g>\n",
"</svg>\n"
],
"text/plain": [
"<graphviz.sources.Source at 0x2d89d88e510>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"writer = gtsam.DotWriter(binaryEdges = True)\n",
"writer.variablePositions = positions\n",
"display(graphviz.Source(grid_graph.dot(writer=writer), engine='neato'))"
]
},
{
"cell_type": "markdown",
"metadata": {
"id": "ordering_colamd_md"
},
"source": [
"### COLAMD Ordering and Resulting Bayes Net\n",
"\n",
"Now, we compute the COLAMD ordering and eliminate the variables according to this order."
]
},
{
"cell_type": "code",
"execution_count": 26,
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "ordering_colamd_code",
"outputId": "789abcde-f012-3456-789a-bcdef0123456"
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"COLAMD Ordering: \n",
"Position 0: x11, x31, x14, x34, x33, x24, x23, x32, x13, x22\n",
"Position 10: x21, x12\n"
]
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"\n",
"COLAMD Bayes Net Structure:\n"
]
},
{
"data": {
"image/svg+xml": [
"<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n",
"<!DOCTYPE svg PUBLIC \"-//W3C//DTD SVG 1.1//EN\"\n",
" \"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd\">\n",
"<!-- Generated by graphviz version 2.50.0 (0)\n",
" -->\n",
"<!-- Title: G Pages: 1 -->\n",
"<svg width=\"393pt\" height=\"476pt\"\n",
" viewBox=\"0.00 0.00 392.99 476.00\" xmlns=\"http://www.w3.org/2000/svg\" xmlns:xlink=\"http://www.w3.org/1999/xlink\">\n",
"<g id=\"graph0\" class=\"graph\" transform=\"scale(1 1) rotate(0) translate(4 472)\">\n",
"<title>G</title>\n",
"<polygon fill=\"white\" stroke=\"transparent\" points=\"-4,4 -4,-472 388.99,-472 388.99,4 -4,4\"/>\n",
"<!-- 0 -->\n",
"<g id=\"node1\" class=\"node\">\n",
"<title>0</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"142.39\" cy=\"-450\" rx=\"59.59\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"142.39\" y=\"-446.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x11, x21, x12</text>\n",
"</g>\n",
"<!-- 1 -->\n",
"<g id=\"node2\" class=\"node\">\n",
"<title>1</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"142.39\" cy=\"-378\" rx=\"80.69\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"142.39\" y=\"-374.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x13, x22 : x12, x21</text>\n",
"</g>\n",
"<!-- 0&#45;&gt;1 -->\n",
"<g id=\"edge1\" class=\"edge\">\n",
"<title>0&#45;&gt;1</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M142.39,-431.7C142.39,-423.98 142.39,-414.71 142.39,-406.11\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"145.89,-406.1 142.39,-396.1 138.89,-406.1 145.89,-406.1\"/>\n",
"</g>\n",
"<!-- 2 -->\n",
"<g id=\"node3\" class=\"node\">\n",
"<title>2</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"142.39\" cy=\"-306\" rx=\"80.69\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"142.39\" y=\"-302.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x32 : x13, x21, x22</text>\n",
"</g>\n",
"<!-- 1&#45;&gt;2 -->\n",
"<g id=\"edge2\" class=\"edge\">\n",
"<title>1&#45;&gt;2</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M142.39,-359.7C142.39,-351.98 142.39,-342.71 142.39,-334.11\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"145.89,-334.1 142.39,-324.1 138.89,-334.1 145.89,-334.1\"/>\n",
"</g>\n",
"<!-- 3 -->\n",
"<g id=\"node4\" class=\"node\">\n",
"<title>3</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"62.39\" cy=\"-234\" rx=\"62.29\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"62.39\" y=\"-230.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x31 : x21, x32</text>\n",
"</g>\n",
"<!-- 2&#45;&gt;3 -->\n",
"<g id=\"edge3\" class=\"edge\">\n",
"<title>2&#45;&gt;3</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M123.44,-288.41C113,-279.28 99.89,-267.81 88.5,-257.84\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"90.77,-255.18 80.94,-251.23 86.16,-260.45 90.77,-255.18\"/>\n",
"</g>\n",
"<!-- 4 -->\n",
"<g id=\"node5\" class=\"node\">\n",
"<title>4</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"223.39\" cy=\"-234\" rx=\"80.69\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"223.39\" y=\"-230.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x23 : x13, x22, x32</text>\n",
"</g>\n",
"<!-- 2&#45;&gt;4 -->\n",
"<g id=\"edge4\" class=\"edge\">\n",
"<title>2&#45;&gt;4</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M161.59,-288.41C172.01,-279.41 185.05,-268.14 196.46,-258.27\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"198.78,-260.9 204.06,-251.71 194.2,-255.6 198.78,-260.9\"/>\n",
"</g>\n",
"<!-- 5 -->\n",
"<g id=\"node6\" class=\"node\">\n",
"<title>5</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"223.39\" cy=\"-162\" rx=\"80.69\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"223.39\" y=\"-158.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x24 : x13, x23, x32</text>\n",
"</g>\n",
"<!-- 4&#45;&gt;5 -->\n",
"<g id=\"edge5\" class=\"edge\">\n",
"<title>4&#45;&gt;5</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M223.39,-215.7C223.39,-207.98 223.39,-198.71 223.39,-190.11\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"226.89,-190.1 223.39,-180.1 219.89,-190.1 226.89,-190.1\"/>\n",
"</g>\n",
"<!-- 6 -->\n",
"<g id=\"node7\" class=\"node\">\n",
"<title>6</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"143.39\" cy=\"-90\" rx=\"62.29\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"143.39\" y=\"-86.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x14 : x13, x24</text>\n",
"</g>\n",
"<!-- 5&#45;&gt;6 -->\n",
"<g id=\"edge6\" class=\"edge\">\n",
"<title>5&#45;&gt;6</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M204.44,-144.41C194,-135.28 180.89,-123.81 169.5,-113.84\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"171.77,-111.18 161.94,-107.23 167.16,-116.45 171.77,-111.18\"/>\n",
"</g>\n",
"<!-- 7 -->\n",
"<g id=\"node8\" class=\"node\">\n",
"<title>7</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"304.39\" cy=\"-90\" rx=\"80.69\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"304.39\" y=\"-86.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x33 : x23, x24, x32</text>\n",
"</g>\n",
"<!-- 5&#45;&gt;7 -->\n",
"<g id=\"edge7\" class=\"edge\">\n",
"<title>5&#45;&gt;7</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M242.59,-144.41C253.01,-135.41 266.05,-124.14 277.46,-114.27\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"279.78,-116.9 285.06,-107.71 275.2,-111.6 279.78,-116.9\"/>\n",
"</g>\n",
"<!-- 8 -->\n",
"<g id=\"node9\" class=\"node\">\n",
"<title>8</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"304.39\" cy=\"-18\" rx=\"62.29\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"304.39\" y=\"-14.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x34 : x24, x33</text>\n",
"</g>\n",
"<!-- 7&#45;&gt;8 -->\n",
"<g id=\"edge8\" class=\"edge\">\n",
"<title>7&#45;&gt;8</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M304.39,-71.7C304.39,-63.98 304.39,-54.71 304.39,-46.11\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"307.89,-46.1 304.39,-36.1 300.89,-46.1 307.89,-46.1\"/>\n",
"</g>\n",
"</g>\n",
"</svg>\n"
],
"text/plain": [
"<graphviz.sources.Source at 0x2d89d882990>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"# COLAMD (Column Approximate Minimum Degree) ordering\n",
"colamd_ordering = Ordering.ColamdSymbolicFactorGraph(grid_graph)\n",
"print(\"COLAMD Ordering: \")\n",
"colamd_ordering.print()\n",
"\n",
"# Eliminate using COLAMD ordering\n",
"bayes_tree_colamd = grid_graph.eliminateMultifrontal(colamd_ordering)\n",
"\n",
"# Visualize the resulting Bayes Net\n",
"print(\"\\nCOLAMD Bayes Net Structure:\")\n",
"display(graphviz.Source(bayes_tree_colamd.dot()))"
]
},
{
"cell_type": "markdown",
"metadata": {
"id": "ordering_metis_md"
},
"source": [
"### METIS Ordering and Resulting Bayes Net\n",
"\n",
"Next, we compute the METIS ordering and visualize its resulting Bayes Net. Compare its structure to the one generated by COLAMD."
]
},
{
"cell_type": "code",
"execution_count": 27,
"metadata": {
"id": "ordering_metis_code"
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"METIS Ordering: \n",
"Position 0: x34, x23, x14, x24, x13, x32, x11, x31, x21, x12\n",
"Position 10: x33, x22\n",
"\n",
"METIS Bayes Net Structure:\n"
]
},
{
"data": {
"image/svg+xml": [
"<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n",
"<!DOCTYPE svg PUBLIC \"-//W3C//DTD SVG 1.1//EN\"\n",
" \"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd\">\n",
"<!-- Generated by graphviz version 2.50.0 (0)\n",
" -->\n",
"<!-- Title: G Pages: 1 -->\n",
"<svg width=\"557pt\" height=\"260pt\"\n",
" viewBox=\"0.00 0.00 556.79 260.00\" xmlns=\"http://www.w3.org/2000/svg\" xmlns:xlink=\"http://www.w3.org/1999/xlink\">\n",
"<g id=\"graph0\" class=\"graph\" transform=\"scale(1 1) rotate(0) translate(4 256)\">\n",
"<title>G</title>\n",
"<polygon fill=\"white\" stroke=\"transparent\" points=\"-4,4 -4,-256 552.79,-256 552.79,4 -4,4\"/>\n",
"<!-- 8 -->\n",
"<g id=\"node1\" class=\"node\">\n",
"<title>8</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"223.39\" cy=\"-234\" rx=\"77.99\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"223.39\" y=\"-230.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x21, x12, x33, x22</text>\n",
"</g>\n",
"<!-- 9 -->\n",
"<g id=\"node2\" class=\"node\">\n",
"<title>9</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"62.39\" cy=\"-162\" rx=\"62.29\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"62.39\" y=\"-158.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x11 : x12, x21</text>\n",
"</g>\n",
"<!-- 8&#45;&gt;9 -->\n",
"<g id=\"edge1\" class=\"edge\">\n",
"<title>8&#45;&gt;9</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M188.46,-217.81C163.83,-207.1 130.72,-192.71 104.61,-181.36\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"105.9,-178.1 95.34,-177.32 103.11,-184.52 105.9,-178.1\"/>\n",
"</g>\n",
"<!-- 10 -->\n",
"<g id=\"node3\" class=\"node\">\n",
"<title>10</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"223.39\" cy=\"-162\" rx=\"80.69\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"223.39\" y=\"-158.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x31 : x21, x22, x33</text>\n",
"</g>\n",
"<!-- 8&#45;&gt;10 -->\n",
"<g id=\"edge2\" class=\"edge\">\n",
"<title>8&#45;&gt;10</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M223.39,-215.7C223.39,-207.98 223.39,-198.71 223.39,-190.11\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"226.89,-190.1 223.39,-180.1 219.89,-190.1 226.89,-190.1\"/>\n",
"</g>\n",
"<!-- 12 -->\n",
"<g id=\"node5\" class=\"node\">\n",
"<title>12</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"411.39\" cy=\"-162\" rx=\"80.69\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"411.39\" y=\"-158.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x13 : x12, x22, x33</text>\n",
"</g>\n",
"<!-- 8&#45;&gt;12 -->\n",
"<g id=\"edge4\" class=\"edge\">\n",
"<title>8&#45;&gt;12</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M262.81,-218.33C291.66,-207.58 331.02,-192.93 361.98,-181.4\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"363.56,-184.54 371.71,-177.78 361.12,-177.98 363.56,-184.54\"/>\n",
"</g>\n",
"<!-- 11 -->\n",
"<g id=\"node4\" class=\"node\">\n",
"<title>11</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"218.39\" cy=\"-90\" rx=\"80.69\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"218.39\" y=\"-86.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x32 : x22, x31, x33</text>\n",
"</g>\n",
"<!-- 10&#45;&gt;11 -->\n",
"<g id=\"edge3\" class=\"edge\">\n",
"<title>10&#45;&gt;11</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M222.16,-143.7C221.61,-135.98 220.95,-126.71 220.33,-118.11\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"223.82,-117.83 219.62,-108.1 216.84,-118.33 223.82,-117.83\"/>\n",
"</g>\n",
"<!-- 13 -->\n",
"<g id=\"node6\" class=\"node\">\n",
"<title>13</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"415.39\" cy=\"-90\" rx=\"98.58\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"415.39\" y=\"-86.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x23, x24 : x13, x22, x33</text>\n",
"</g>\n",
"<!-- 12&#45;&gt;13 -->\n",
"<g id=\"edge5\" class=\"edge\">\n",
"<title>12&#45;&gt;13</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M412.38,-143.7C412.82,-135.98 413.35,-126.71 413.85,-118.11\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"417.34,-118.29 414.42,-108.1 410.35,-117.89 417.34,-118.29\"/>\n",
"</g>\n",
"<!-- 14 -->\n",
"<g id=\"node7\" class=\"node\">\n",
"<title>14</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"343.39\" cy=\"-18\" rx=\"62.29\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"343.39\" y=\"-14.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x14 : x13, x24</text>\n",
"</g>\n",
"<!-- 13&#45;&gt;14 -->\n",
"<g id=\"edge6\" class=\"edge\">\n",
"<title>13&#45;&gt;14</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M397.97,-72.05C388.94,-63.28 377.78,-52.43 367.91,-42.83\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"370.27,-40.25 360.66,-35.79 365.39,-45.27 370.27,-40.25\"/>\n",
"</g>\n",
"<!-- 15 -->\n",
"<g id=\"node8\" class=\"node\">\n",
"<title>15</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"486.39\" cy=\"-18\" rx=\"62.29\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"486.39\" y=\"-14.3\" font-family=\"Times New Roman,serif\" font-size=\"14.00\">x34 : x24, x33</text>\n",
"</g>\n",
"<!-- 13&#45;&gt;15 -->\n",
"<g id=\"edge7\" class=\"edge\">\n",
"<title>13&#45;&gt;15</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M432.58,-72.05C441.48,-63.28 452.49,-52.43 462.22,-42.83\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"464.7,-45.3 469.37,-35.79 459.79,-40.32 464.7,-45.3\"/>\n",
"</g>\n",
"</g>\n",
"</svg>\n"
],
"text/plain": [
"<graphviz.sources.Source at 0x2d89d882990>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"metis_ordering = Ordering.MetisSymbolicFactorGraph(grid_graph)\n",
"print(\"METIS Ordering: \")\n",
"metis_ordering.print()\n",
"\n",
"# Eliminate using METIS ordering\n",
"bayes_tree_metis = grid_graph.eliminateMultifrontal(metis_ordering)\n",
"\n",
"# Visualize the resulting Bayes Net\n",
"print(\"\\nMETIS Bayes Net Structure:\")\n",
"display(graphviz.Source(bayes_tree_metis.dot()))"
]
},
{
"cell_type": "markdown",
"metadata": {
"id": "ordering_comparison_md"
},
"source": [
"### Comparison\n",
"\n",
"Observe the differences in the Bayes tree structures produced by COLAMD and METIS:\n",
"\n",
"* **COLAMD:** Often produces a more 'stringy' or deeper Bayes tree. The cliques (conditionals in the Bayes tree) might be smaller initially but can grow larger towards the root (variables eliminated last).\n",
"* **METIS:** Tends to produce a more 'bushy' or balanced tree. It tries to partition the graph, eliminating variables within partitions first, leading to potentially larger initial cliques but often a shallower overall structure and smaller separators (variables connecting cliques high up in the tree). \n",
"\n",
"When should you choose one over the other? The best choice often depends on the specific problem structure and computational goals:\n",
"\n",
"* **Use COLAMD when:**\n",
" * You need a good, general-purpose ordering quickly. COLAMD is typically much faster *to compute the ordering itself* than METIS.\n",
" * You are primarily using a *sequential* solver (running on a single CPU core). COLAMD's greedy strategy is often well-suited for minimizing fill-in in this scenario.\n",
" * The factor graph is relatively small or doesn't have a highly regular structure where complex partitioning would yield significant benefits.\n",
"\n",
"* **Use METIS when:**\n",
" * You are aiming for maximum performance with a *parallel* solver (e.g., using GTSAM's multifrontal solvers with TBB). METIS's graph partitioning approach tends to create more balanced Bayes trees, which allows for better workload distribution across multiple CPU cores.\n",
" * You are dealing with very large-scale problems, especially those with a regular structure (like large grids, meshes from finite element analysis, or extensive SLAM maps). On such problems, METIS can sometimes find an ordering with significantly less *total fill-in* than COLAMD, leading to faster factorization, even if computing the ordering itself takes longer.\n",
" * The cost of computing the ordering is negligible compared to the cost of the subsequent factorization and solve steps (e.g., you compute the ordering once for a structure that is solved repeatedly).\n",
"\n",
"**In summary:** COLAMD is a robust and fast default. METIS is often the preferred choice for large-scale problems and parallel execution, potentially offering better final factorization performance at the cost of a slower ordering computation. Experimentation on your specific problem type might be necessary to determine the optimal choice.\n",
"\n",
"For more information on COLAMD and METIS, see [Factor Graphs for Robot Perception](https://www.cs.cmu.edu/~kaess/pub/Dellaert17fnt.pdf)."
]
},
{
"cell_type": "markdown",
"metadata": {
"id": "ordering_constrained_md"
},
"source": [
"### Constrained Ordering\n",
"\n",
"Sometimes, we want to force certain variables to be eliminated last (e.g., the current robot pose in SLAM). `Ordering.ColamdConstrainedLast` allows this for COLAMD."
]
},
{
"cell_type": "code",
"execution_count": 28,
"metadata": {
"colab": {
"base_uri": "https://localhost:8080/"
},
"id": "ordering_constrained_code",
"outputId": "89abcdef-0123-4567-89ab-cdef01234567"
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Constrained COLAMD (x11, x34 last):\n",
"Position 0: x31, x32, x21, x14, x24, x13, x23, x33, x22, x12\n",
"Position 10: x34, x11\n"
]
}
],
"source": [
"# Example: Constrained COLAMD forcing corners (x0, x24) to be eliminated last\n",
"# Note: We use the grid_graph defined earlier\n",
"corner_keys = gtsam.KeyVector([X_grid(0, 0), X_grid(ROWS-1, COLS-1)])\n",
"constrained_ordering = Ordering.ColamdConstrainedLastSymbolicFactorGraph(grid_graph, corner_keys)\n",
"print(f\"Constrained COLAMD ({gtsam.DefaultKeyFormatter(corner_keys[0])}, {gtsam.DefaultKeyFormatter(corner_keys[1])} last):\")\n",
"constrained_ordering.print()"
] ]
}, },
{ {
@ -151,7 +804,7 @@
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 19, "execution_count": 29,
"metadata": { "metadata": {
"colab": { "colab": {
"base_uri": "https://localhost:8080/" "base_uri": "https://localhost:8080/"
@ -164,17 +817,17 @@
"name": "stdout", "name": "stdout",
"output_type": "stream", "output_type": "stream",
"text": [ "text": [
"Ordering size: 5\n", "COLAMD Ordering size: 12\n",
"Key at position 0: l1\n" "Key at position 0 (COLAMD): x11\n"
] ]
} }
], ],
"source": [ "source": [
"print(f\"Ordering size: {colamd_ordering.size()}\")\n", "print(f\"COLAMD Ordering size: {colamd_ordering.size()}\")\n",
"\n", "\n",
"# Access by index\n", "# Access by index\n",
"key_at_0 = colamd_ordering.at(0)\n", "key_at_0 = colamd_ordering.at(0)\n",
"print(f\"Key at position 0: {gtsam.DefaultKeyFormatter(key_at_0)}\")" "print(f\"Key at position 0 (COLAMD): {gtsam.DefaultKeyFormatter(key_at_0)}\")"
] ]
}, },
{ {
@ -185,12 +838,12 @@
"source": [ "source": [
"## Appending Keys\n", "## Appending Keys\n",
"\n", "\n",
"You can append keys using `push_back`." "You can append keys to an existing ordering using `push_back`."
] ]
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 20, "execution_count": 30,
"metadata": { "metadata": {
"colab": { "colab": {
"base_uri": "https://localhost:8080/" "base_uri": "https://localhost:8080/"
@ -203,25 +856,24 @@
"name": "stdout", "name": "stdout",
"output_type": "stream", "output_type": "stream",
"text": [ "text": [
"Appended Ordering: Position 0: l1, x0, x1, l2, x2, l0, x3\n" "Appended Ordering: Position 0: x11, x31, x14, x34, x33, x24, x23, x32, x13, x22\n",
"Position 10: x21, x12, l0, x12\n"
] ]
} }
], ],
"source": [ "source": [
"# Use the COLAMD ordering from the grid example\n",
"appended_ordering = Ordering(colamd_ordering)\n", "appended_ordering = Ordering(colamd_ordering)\n",
"appended_ordering.push_back(L(0))\n", "appended_ordering.push_back(L(0)) # Append a landmark key\n",
"appended_ordering.push_back(X(3))\n", "appended_ordering.push_back(X(ROWS*COLS)) # Append a new pose key x25\n",
"\n", "\n",
"appended_ordering.print(\"Appended Ordering: \")" "appended_ordering.print(\"Appended Ordering: \")"
] ]
} }
], ],
"metadata": { "metadata": {
"colab": {
"provenance": []
},
"kernelspec": { "kernelspec": {
"display_name": "gtsam", "display_name": "py312",
"language": "python", "language": "python",
"name": "python3" "name": "python3"
}, },
@ -235,7 +887,7 @@
"name": "python", "name": "python",
"nbconvert_exporter": "python", "nbconvert_exporter": "python",
"pygments_lexer": "ipython3", "pygments_lexer": "ipython3",
"version": "3.13.1" "version": "3.12.6"
} }
}, },
"nbformat": 4, "nbformat": 4,

View File

@ -38,12 +38,12 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 1, "execution_count": 6,
"metadata": { "metadata": {
"id": "symbol_import_code" "id": "symbol_import_code"
}, },
@ -66,7 +66,7 @@
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 2, "execution_count": 7,
"metadata": { "metadata": {
"colab": { "colab": {
"base_uri": "https://localhost:8080/" "base_uri": "https://localhost:8080/"
@ -110,7 +110,7 @@
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 3, "execution_count": 8,
"metadata": { "metadata": {
"colab": { "colab": {
"base_uri": "https://localhost:8080/" "base_uri": "https://localhost:8080/"
@ -151,12 +151,12 @@
"source": [ "source": [
"## Shorthand Functions\n", "## Shorthand Functions\n",
"\n", "\n",
"GTSAM provides convenient shorthand functions `gtsam.symbol_shorthand.X(j)`, `gtsam.symbol_shorthand.L(j)`, etc., which are equivalent to `gtsam.Symbol('x', j)`, `gtsam.Symbol('l', j)`." "GTSAM provides convenient shorthand functions `X(j)`, `L(j)`, etc., which are equivalent to `gtsam.Symbol('x', j)`, `gtsam.Symbol('l', j)`. To use these, first import with `from gtsam import symbol_shorthand`, then set up the variables you want to use with statements like `X = symbol_shorthand.X`."
] ]
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 4, "execution_count": 9,
"metadata": { "metadata": {
"colab": { "colab": {
"base_uri": "https://localhost:8080/" "base_uri": "https://localhost:8080/"
@ -169,19 +169,19 @@
"name": "stdout", "name": "stdout",
"output_type": "stream", "output_type": "stream",
"text": [ "text": [
"Symbol('x', 0).key() == gtsam.symbol_shorthand.X(0): True\n", "Symbol('x', 0).key() == X(0): True\n",
"Symbol('l', 1).key() == gtsam.symbol_shorthand.L(1): True\n" "Symbol('l', 1).key() == L(1): True\n"
] ]
} }
], ],
"source": [ "source": [
"from gtsam import symbol_shorthand\n", "from gtsam import symbol_shorthand\n",
"\n", "\n",
"x0_key = symbol_shorthand.X(0)\n", "X = symbol_shorthand.X\n",
"l1_key = symbol_shorthand.L(1)\n", "L = symbol_shorthand.L\n",
"\n", "\n",
"print(f\"Symbol('x', 0).key() == gtsam.symbol_shorthand.X(0): {Symbol('x', 0).key() == x0_key}\")\n", "print(f\"Symbol('x', 0).key() == X(0): {Symbol('x', 0).key() == X(0)}\")\n",
"print(f\"Symbol('l', 1).key() == gtsam.symbol_shorthand.L(1): {Symbol('l', 1).key() == l1_key}\")" "print(f\"Symbol('l', 1).key() == L(1): {Symbol('l', 1).key() == L(1)}\")"
] ]
} }
], ],

View File

@ -40,7 +40,7 @@
}, },
"outputs": [], "outputs": [],
"source": [ "source": [
"%pip install gtsam-develop" "%pip install --quiet gtsam-develop"
] ]
}, },
{ {

View File

@ -657,6 +657,21 @@ virtual class GaussianBayesNet {
}; };
#include <gtsam/linear/GaussianBayesTree.h> #include <gtsam/linear/GaussianBayesTree.h>
class GaussianBayesTreeClique {
GaussianBayesTreeClique();
GaussianBayesTreeClique(const gtsam::GaussianConditional* conditional);
bool equals(const gtsam::GaussianBayesTreeClique& other, double tol) const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter);
const gtsam::GaussianConditional* conditional() const;
bool isRoot() const;
gtsam::GaussianBayesTreeClique* parent() const;
size_t nrChildren() const;
gtsam::GaussianBayesTreeClique* operator[](size_t j) const;
size_t treeSize() const;
size_t numCachedSeparatorMarginals() const;
void deleteCachedShortcuts();
};
virtual class GaussianBayesTree { virtual class GaussianBayesTree {
// Standard Constructors and Named Constructors // Standard Constructors and Named Constructors
GaussianBayesTree(); GaussianBayesTree();
@ -666,6 +681,8 @@ virtual class GaussianBayesTree {
gtsam::DefaultKeyFormatter); gtsam::DefaultKeyFormatter);
size_t size() const; size_t size() const;
bool empty() const; bool empty() const;
const GaussianBayesTree::Roots& roots() const;
const gtsam::GaussianBayesTreeClique* operator[](size_t j) const;
size_t numCachedSeparatorMarginals() const; size_t numCachedSeparatorMarginals() const;
string dot(const gtsam::KeyFormatter& keyFormatter = string dot(const gtsam::KeyFormatter& keyFormatter =

View File

@ -18,7 +18,7 @@
}, },
{ {
"cell_type": "code", "cell_type": "code",
"execution_count": 1, "execution_count": null,
"id": "5ccb48e4", "id": "5ccb48e4",
"metadata": { "metadata": {
"tags": [ "tags": [
@ -28,17 +28,7 @@
"languageId": "markdown" "languageId": "markdown"
} }
}, },
"outputs": [ "outputs": [],
{
"name": "stdout",
"output_type": "stream",
"text": [
"\u001b[31mERROR: Could not find a version that satisfies the requirement gtsam-develop (from versions: none)\u001b[0m\u001b[31m\n",
"\u001b[0m\u001b[31mERROR: No matching distribution found for gtsam-develop\u001b[0m\u001b[31m\n",
"\u001b[0mNote: you may need to restart the kernel to use updated packages.\n"
]
}
],
"source": [ "source": [
"%pip install --quiet gtsam-develop" "%pip install --quiet gtsam-develop"
] ]

View File

@ -0,0 +1,231 @@
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# SymbolicBayesNet"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"A `SymbolicBayesNet` is a directed acyclic graph (DAG) composed of `SymbolicConditional` objects. It represents the structure of a factorized probability distribution P(X) = Π P(Xi | Parents(Xi)) purely in terms of variable connectivity.\n",
"\n",
"It is typically the result of running sequential variable elimination on a `SymbolicFactorGraph`."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"<a href=\"https://colab.research.google.com/github/borglab/gtsam/blob/develop/gtsam/symbolic/doc/SymbolicBayesNet.ipynb\" target=\"_parent\"><img src=\"https://colab.research.google.com/assets/colab-badge.svg\" alt=\"Open In Colab\"/></a>"
]
},
{
"cell_type": "code",
"execution_count": 13,
"metadata": {
"tags": [
"remove-cell"
]
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Note: you may need to restart the kernel to use updated packages.\n"
]
}
],
"source": [
"%pip install --quiet gtsam-develop"
]
},
{
"cell_type": "code",
"execution_count": 14,
"metadata": {},
"outputs": [],
"source": [
"from gtsam import SymbolicConditional, SymbolicFactorGraph, Ordering\n",
"from gtsam.symbol_shorthand import X, L\n",
"import graphviz"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Creating a SymbolicBayesNet\n",
"\n",
"SymbolicBayesNets are usually created by eliminating a [SymbolicFactorGraph](SymbolicFactorGraph.ipynb). But you can also build them directly:"
]
},
{
"cell_type": "code",
"execution_count": 15,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Directly Built Symbolic Bayes Net:\n",
" \n",
"size: 5\n",
"conditional 0: P( l1 | x0)\n",
"conditional 1: P( x0 | x1)\n",
"conditional 2: P( l2 | x1)\n",
"conditional 3: P( x1 | x2)\n",
"conditional 4: P( x2)\n"
]
}
],
"source": [
"from gtsam import SymbolicBayesNet\n",
"\n",
"# Create a new Bayes Net\n",
"symbolic_bayes_net = SymbolicBayesNet()\n",
"\n",
"# Add conditionals directly\n",
"symbolic_bayes_net.push_back(SymbolicConditional(L(1), X(0))) # P(l1 | x0)\n",
"symbolic_bayes_net.push_back(SymbolicConditional(X(0), X(1))) # P(x0 | x1)\n",
"symbolic_bayes_net.push_back(SymbolicConditional(L(2), X(1))) # P(l2 | x1)\n",
"symbolic_bayes_net.push_back(SymbolicConditional(X(1), X(2))) # P(x1 | x2)\n",
"symbolic_bayes_net.push_back(SymbolicConditional(X(2))) # P(x2)\n",
"\n",
"symbolic_bayes_net.print(\"Directly Built Symbolic Bayes Net:\\n\")"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Accessing Conditionals and Visualization"
]
},
{
"cell_type": "code",
"execution_count": 16,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Conditional at index 1: P( x0 | x1)\n"
]
},
{
"data": {
"image/svg+xml": [
"<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n",
"<!DOCTYPE svg PUBLIC \"-//W3C//DTD SVG 1.1//EN\"\n",
" \"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd\">\n",
"<!-- Generated by graphviz version 12.0.0 (0)\n",
" -->\n",
"<!-- Pages: 1 -->\n",
"<svg width=\"134pt\" height=\"260pt\"\n",
" viewBox=\"0.00 0.00 134.00 260.00\" xmlns=\"http://www.w3.org/2000/svg\" xmlns:xlink=\"http://www.w3.org/1999/xlink\">\n",
"<g id=\"graph0\" class=\"graph\" transform=\"scale(1 1) rotate(0) translate(4 256)\">\n",
"<polygon fill=\"white\" stroke=\"none\" points=\"-4,4 -4,-256 130,-256 130,4 -4,4\"/>\n",
"<!-- var7782220156096217089 -->\n",
"<g id=\"node1\" class=\"node\">\n",
"<title>var7782220156096217089</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"99\" cy=\"-18\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"99\" y=\"-12.95\" font-family=\"Times,serif\" font-size=\"14.00\">l1</text>\n",
"</g>\n",
"<!-- var7782220156096217090 -->\n",
"<g id=\"node2\" class=\"node\">\n",
"<title>var7782220156096217090</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"27\" cy=\"-90\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"27\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">l2</text>\n",
"</g>\n",
"<!-- var8646911284551352320 -->\n",
"<g id=\"node3\" class=\"node\">\n",
"<title>var8646911284551352320</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"99\" cy=\"-90\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"99\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">x0</text>\n",
"</g>\n",
"<!-- var8646911284551352320&#45;&gt;var7782220156096217089 -->\n",
"<g id=\"edge4\" class=\"edge\">\n",
"<title>var8646911284551352320&#45;&gt;var7782220156096217089</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M99,-71.7C99,-64.41 99,-55.73 99,-47.54\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"102.5,-47.62 99,-37.62 95.5,-47.62 102.5,-47.62\"/>\n",
"</g>\n",
"<!-- var8646911284551352321 -->\n",
"<g id=\"node4\" class=\"node\">\n",
"<title>var8646911284551352321</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"63\" cy=\"-162\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"63\" y=\"-156.95\" font-family=\"Times,serif\" font-size=\"14.00\">x1</text>\n",
"</g>\n",
"<!-- var8646911284551352321&#45;&gt;var7782220156096217090 -->\n",
"<g id=\"edge2\" class=\"edge\">\n",
"<title>var8646911284551352321&#45;&gt;var7782220156096217090</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M54.65,-144.76C50.42,-136.55 45.19,-126.37 40.42,-117.09\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"43.68,-115.79 36,-108.49 37.46,-118.99 43.68,-115.79\"/>\n",
"</g>\n",
"<!-- var8646911284551352321&#45;&gt;var8646911284551352320 -->\n",
"<g id=\"edge3\" class=\"edge\">\n",
"<title>var8646911284551352321&#45;&gt;var8646911284551352320</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M71.35,-144.76C75.58,-136.55 80.81,-126.37 85.58,-117.09\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"88.54,-118.99 90,-108.49 82.32,-115.79 88.54,-118.99\"/>\n",
"</g>\n",
"<!-- var8646911284551352322 -->\n",
"<g id=\"node5\" class=\"node\">\n",
"<title>var8646911284551352322</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"63\" cy=\"-234\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"63\" y=\"-228.95\" font-family=\"Times,serif\" font-size=\"14.00\">x2</text>\n",
"</g>\n",
"<!-- var8646911284551352322&#45;&gt;var8646911284551352321 -->\n",
"<g id=\"edge1\" class=\"edge\">\n",
"<title>var8646911284551352322&#45;&gt;var8646911284551352321</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M63,-215.7C63,-208.41 63,-199.73 63,-191.54\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"66.5,-191.62 63,-181.62 59.5,-191.62 66.5,-191.62\"/>\n",
"</g>\n",
"</g>\n",
"</svg>\n"
],
"text/plain": [
"<graphviz.sources.Source at 0x10c18fda0>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"# Access a conditional by index\n",
"conditional_1 = bayes_net.at(1) # P(x0 | l1)\n",
"conditional_1.print(\"Conditional at index 1: \")\n",
"\n",
"# Visualize the Bayes Net structure\n",
"display(graphviz.Source(bayes_net.dot()))"
]
}
],
"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": 4
}

View File

@ -0,0 +1,325 @@
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# SymbolicBayesTree"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"A `SymbolicBayesTree` is a tree structure where each node (`SymbolicBayesTreeClique`) represents a clique of variables that were eliminated together during multifrontal elimination. Unlike a `SymbolicJunctionTree` which stores factors, a `SymbolicBayesTree` stores the resulting `SymbolicConditional` for each clique.\n",
"\n",
"It represents the factored structure $P(X) = Π P(C_j | S_j)$, where $C_j$ are the frontal variables of clique $j$ and $S_j$ are its separator variables (parents in the Bayes Tree). This structure is computationally advantageous for inference, especially for calculating marginals or performing incremental updates (like in iSAM)."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"<a href=\"https://colab.research.google.com/github/borglab/gtsam/blob/develop/gtsam/symbolic/doc/SymbolicBayesTree.ipynb\" target=\"_parent\"><img src=\"https://colab.research.google.com/assets/colab-badge.svg\" alt=\"Open In Colab\"/></a>"
]
},
{
"cell_type": "code",
"execution_count": 1,
"metadata": {
"tags": [
"remove-cell"
]
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Note: you may need to restart the kernel to use updated packages.\n"
]
}
],
"source": [
"%pip install --quiet gtsam-develop"
]
},
{
"cell_type": "code",
"execution_count": 1,
"metadata": {},
"outputs": [],
"source": [
"from gtsam import SymbolicFactorGraph, Ordering\n",
"from gtsam.symbol_shorthand import X, L\n",
"import graphviz # For visualization"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Creating a SymbolicBayesTree\n",
"\n",
"A Bayes tree is typically created by eliminating a `SymbolicFactorGraph` using the multifrontal method."
]
},
{
"cell_type": "code",
"execution_count": 20,
"metadata": {},
"outputs": [],
"source": [
"# Create a factor graph from a GTSFM problem\n",
"graph = SymbolicFactorGraph()\n",
"\n",
"edges = [(2, 4), (2, 5), (2, 27), (4, 6), (5, 6), (5, 7), (5, 8), (5, 9), (6, 7), (6, 8), (6, 9), \n",
" (7, 8), (7, 9), (8, 9), (9, 12), (9, 24), (9, 28), (10, 12), (10, 29), (20, 21), (20, 22), \n",
" (20, 23), (20, 24), (21, 22), (21, 23), (21, 24), (22, 23), (22, 24), (23, 24), (25, 26), \n",
" (25, 27), (25, 28), (25, 29), (26, 27), (26, 28), (26, 29), (27, 28), (27, 29), (28, 29)]\n",
"\n",
"for i,j in edges:\n",
" graph.push_factor(X(i), X(j))\n",
"\n",
"# Define an elimination ordering\n",
"ordering = Ordering.MetisSymbolicFactorGraph(graph) # Use METIS for this example\n",
"\n",
"# Eliminate using Multifrontal method\n",
"bayes_tree = graph.eliminateMultifrontal(ordering)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Visualization and Properties\n",
"\n",
"The Bayes tree structure can be visualized, and we can query its properties."
]
},
{
"cell_type": "code",
"execution_count": 21,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"\n",
"Bayes Tree size (number of cliques): 8\n",
"Is the Bayes Tree empty? False\n"
]
}
],
"source": [
"print(f\"\\nBayes Tree size (number of cliques): {bayes_tree.size()}\")\n",
"print(f\"Is the Bayes Tree empty? {bayes_tree.empty()}\")"
]
},
{
"cell_type": "code",
"execution_count": 22,
"metadata": {},
"outputs": [
{
"data": {
"image/svg+xml": [
"<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n",
"<!DOCTYPE svg PUBLIC \"-//W3C//DTD SVG 1.1//EN\"\n",
" \"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd\">\n",
"<!-- Generated by graphviz version 12.0.0 (0)\n",
" -->\n",
"<!-- Title: G Pages: 1 -->\n",
"<svg width=\"695pt\" height=\"260pt\"\n",
" viewBox=\"0.00 0.00 694.66 260.00\" xmlns=\"http://www.w3.org/2000/svg\" xmlns:xlink=\"http://www.w3.org/1999/xlink\">\n",
"<g id=\"graph0\" class=\"graph\" transform=\"scale(1 1) rotate(0) translate(4 256)\">\n",
"<title>G</title>\n",
"<polygon fill=\"white\" stroke=\"none\" points=\"-4,4 -4,-256 690.66,-256 690.66,4 -4,4\"/>\n",
"<!-- 20 -->\n",
"<g id=\"node1\" class=\"node\">\n",
"<title>20</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"373.29\" cy=\"-234\" rx=\"114.82\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"373.29\" y=\"-228.95\" font-family=\"Times,serif\" font-size=\"14.00\">x28, x25, x26, x9, x29, x27</text>\n",
"</g>\n",
"<!-- 21 -->\n",
"<g id=\"node2\" class=\"node\">\n",
"<title>21</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"224.29\" cy=\"-162\" rx=\"70.29\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"224.29\" y=\"-156.95\" font-family=\"Times,serif\" font-size=\"14.00\">x5, x4 : x9, x27</text>\n",
"</g>\n",
"<!-- 20&#45;&gt;21 -->\n",
"<g id=\"edge1\" class=\"edge\">\n",
"<title>20&#45;&gt;21</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M337.98,-216.41C316.8,-206.46 289.73,-193.74 267.31,-183.21\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"268.96,-180.12 258.42,-179.04 265.98,-186.46 268.96,-180.12\"/>\n",
"</g>\n",
"<!-- 25 -->\n",
"<g id=\"node6\" class=\"node\">\n",
"<title>25</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"373.29\" cy=\"-162\" rx=\"60.56\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"373.29\" y=\"-156.95\" font-family=\"Times,serif\" font-size=\"14.00\">x12 : x9, x29</text>\n",
"</g>\n",
"<!-- 20&#45;&gt;25 -->\n",
"<g id=\"edge5\" class=\"edge\">\n",
"<title>20&#45;&gt;25</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M373.29,-215.7C373.29,-208.41 373.29,-199.73 373.29,-191.54\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"376.79,-191.62 373.29,-181.62 369.79,-191.62 376.79,-191.62\"/>\n",
"</g>\n",
"<!-- 27 -->\n",
"<g id=\"node8\" class=\"node\">\n",
"<title>27</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"569.29\" cy=\"-162\" rx=\"117.37\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"569.29\" y=\"-156.95\" font-family=\"Times,serif\" font-size=\"14.00\">x24, x23, x22, x21, x20 : x9</text>\n",
"</g>\n",
"<!-- 20&#45;&gt;27 -->\n",
"<g id=\"edge7\" class=\"edge\">\n",
"<title>20&#45;&gt;27</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M417.76,-217.12C446.26,-206.94 483.45,-193.66 513.86,-182.79\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"514.64,-186.23 522.89,-179.57 512.29,-179.64 514.64,-186.23\"/>\n",
"</g>\n",
"<!-- 22 -->\n",
"<g id=\"node3\" class=\"node\">\n",
"<title>22</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"70.29\" cy=\"-90\" rx=\"70.29\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"70.29\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">x2 : x4, x5, x27</text>\n",
"</g>\n",
"<!-- 21&#45;&gt;22 -->\n",
"<g id=\"edge2\" class=\"edge\">\n",
"<title>21&#45;&gt;22</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M190.87,-145.81C168.45,-135.62 138.67,-122.08 114.32,-111.01\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"115.83,-107.86 105.28,-106.91 112.94,-114.23 115.83,-107.86\"/>\n",
"</g>\n",
"<!-- 23 -->\n",
"<g id=\"node4\" class=\"node\">\n",
"<title>23</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"224.29\" cy=\"-90\" rx=\"65.68\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"224.29\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">x6 : x4, x5, x9</text>\n",
"</g>\n",
"<!-- 21&#45;&gt;23 -->\n",
"<g id=\"edge3\" class=\"edge\">\n",
"<title>21&#45;&gt;23</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M224.29,-143.7C224.29,-136.41 224.29,-127.73 224.29,-119.54\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"227.79,-119.62 224.29,-109.62 220.79,-119.62 227.79,-119.62\"/>\n",
"</g>\n",
"<!-- 24 -->\n",
"<g id=\"node5\" class=\"node\">\n",
"<title>24</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"224.29\" cy=\"-18\" rx=\"80.01\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"224.29\" y=\"-12.95\" font-family=\"Times,serif\" font-size=\"14.00\">x8, x7 : x5, x6, x9</text>\n",
"</g>\n",
"<!-- 23&#45;&gt;24 -->\n",
"<g id=\"edge4\" class=\"edge\">\n",
"<title>23&#45;&gt;24</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M224.29,-71.7C224.29,-64.41 224.29,-55.73 224.29,-47.54\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"227.79,-47.62 224.29,-37.62 220.79,-47.62 227.79,-47.62\"/>\n",
"</g>\n",
"<!-- 26 -->\n",
"<g id=\"node7\" class=\"node\">\n",
"<title>26</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"373.29\" cy=\"-90\" rx=\"65.17\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"373.29\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">x10 : x12, x29</text>\n",
"</g>\n",
"<!-- 25&#45;&gt;26 -->\n",
"<g id=\"edge6\" class=\"edge\">\n",
"<title>25&#45;&gt;26</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M373.29,-143.7C373.29,-136.41 373.29,-127.73 373.29,-119.54\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"376.79,-119.62 373.29,-109.62 369.79,-119.62 376.79,-119.62\"/>\n",
"</g>\n",
"</g>\n",
"</svg>\n"
],
"text/plain": [
"<graphviz.sources.Source at 0x1120de8a0>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"# Visualize the Bayes tree using graphviz\n",
"display(graphviz.Source(bayes_tree.dot()))"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Traversing a Bayes Tree"
]
},
{
"cell_type": "code",
"execution_count": 23,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Number of roots: 1\n",
"\n",
"Clique:\n",
" P( x28 x25 x26 x9 x29 x27)\n",
"\n",
"Clique:\n",
" P( x5 x4 | x9 x27)\n",
"\n",
"Clique:\n",
" P( x2 | x4 x5 x27)\n",
"\n",
"Clique:\n",
" P( x6 | x4 x5 x9)\n",
"\n",
"Clique:\n",
" P( x8 x7 | x5 x6 x9)\n",
"\n",
"Clique:\n",
" P( x12 | x9 x29)\n",
"\n",
"Clique:\n",
" P( x10 | x12 x29)\n",
"\n",
"Clique:\n",
" P( x24 x23 x22 x21 x20 | x9)\n"
]
}
],
"source": [
"roots = bayes_tree.roots()\n",
"print(f\"Number of roots: {len(roots)}\")\n",
"\n",
"def traverse_clique(clique):\n",
" if clique:\n",
" clique.print(\"\\nClique:\\n\")\n",
" for j in range(clique.nrChildren()):\n",
" traverse_clique(clique[j])\n",
"\n",
"for root in roots:\n",
" traverse_clique(root)"
]
}
],
"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": 4
}

View File

@ -0,0 +1,262 @@
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# SymbolicBayesTreeClique"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"A `SymbolicBayesTreeClique` represents a single node within a `SymbolicBayesTree`. Each clique corresponds to a set of variables (frontal variables) that were eliminated together during the multifrontal elimination process.\n",
"\n",
"Key aspects of a clique:\n",
"* **Conditional:** It stores the `SymbolicConditional` P(Frontals | Parents/Separator) that results from eliminating the frontal variables.\n",
"* **Tree Structure:** It maintains pointers to its parent and children cliques within the Bayes Tree, defining the tree's topology.\n",
"* **Frontal and Separator Variables:** Implicitly defines the frontal variables (eliminated in this clique) and separator variables (parents in the Bayes Tree, connecting it to its parent clique).\n",
"\n",
"Users typically interact with the `SymbolicBayesTree` as a whole, but understanding the clique structure is helpful for comprehending how the Bayes Tree represents the factored distribution and facilitates efficient inference."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"<a href=\"https://colab.research.google.com/github/borglab/gtsam/blob/develop/gtsam/symbolic/doc/SymbolicBayesTreeClique.ipynb\" target=\"_parent\"><img src=\"https://colab.research.google.com/assets/colab-badge.svg\" alt=\"Open In Colab\"/></a>"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {
"tags": [
"remove-cell"
]
},
"outputs": [],
"source": [
"%pip install --quiet gtsam-develop"
]
},
{
"cell_type": "code",
"execution_count": 11,
"metadata": {},
"outputs": [],
"source": [
"from gtsam import SymbolicFactorGraph, Ordering\n",
"# SymbolicBayesTreeClique is accessed *through* a SymbolicBayesTree\n",
"from gtsam.symbol_shorthand import X, L\n",
"import graphviz"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Accessing and Inspecting Cliques\n",
"\n",
"Cliques are obtained by first creating a `SymbolicBayesTree` (usually via elimination) and then accessing its nodes."
]
},
{
"cell_type": "code",
"execution_count": 16,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Bayes Tree has 4 cliques.\n",
"Number of roots: 1\n"
]
},
{
"data": {
"image/svg+xml": [
"<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n",
"<!DOCTYPE svg PUBLIC \"-//W3C//DTD SVG 1.1//EN\"\n",
" \"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd\">\n",
"<!-- Generated by graphviz version 12.0.0 (0)\n",
" -->\n",
"<!-- Title: G Pages: 1 -->\n",
"<svg width=\"170pt\" height=\"188pt\"\n",
" viewBox=\"0.00 0.00 169.99 188.00\" xmlns=\"http://www.w3.org/2000/svg\" xmlns:xlink=\"http://www.w3.org/1999/xlink\">\n",
"<g id=\"graph0\" class=\"graph\" transform=\"scale(1 1) rotate(0) translate(4 184)\">\n",
"<title>G</title>\n",
"<polygon fill=\"white\" stroke=\"none\" points=\"-4,4 -4,-184 165.99,-184 165.99,4 -4,4\"/>\n",
"<!-- 6 -->\n",
"<g id=\"node1\" class=\"node\">\n",
"<title>6</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"82.02\" cy=\"-162\" rx=\"34.46\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"82.02\" y=\"-156.95\" font-family=\"Times,serif\" font-size=\"14.00\">x1, x2</text>\n",
"</g>\n",
"<!-- 7 -->\n",
"<g id=\"node2\" class=\"node\">\n",
"<title>7</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"37.02\" cy=\"-90\" rx=\"37.02\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"37.02\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">x0 : x1</text>\n",
"</g>\n",
"<!-- 6&#45;&gt;7 -->\n",
"<g id=\"edge1\" class=\"edge\">\n",
"<title>6&#45;&gt;7</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M71.36,-144.41C66.09,-136.22 59.61,-126.14 53.71,-116.95\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"56.78,-115.26 48.43,-108.74 50.89,-119.05 56.78,-115.26\"/>\n",
"</g>\n",
"<!-- 9 -->\n",
"<g id=\"node4\" class=\"node\">\n",
"<title>9</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"127.02\" cy=\"-90\" rx=\"34.97\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"127.02\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">l2 : x1</text>\n",
"</g>\n",
"<!-- 6&#45;&gt;9 -->\n",
"<g id=\"edge3\" class=\"edge\">\n",
"<title>6&#45;&gt;9</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M92.69,-144.41C97.95,-136.22 104.43,-126.14 110.34,-116.95\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"113.15,-119.05 115.61,-108.74 107.26,-115.26 113.15,-119.05\"/>\n",
"</g>\n",
"<!-- 8 -->\n",
"<g id=\"node3\" class=\"node\">\n",
"<title>8</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"37.02\" cy=\"-18\" rx=\"34.97\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"37.02\" y=\"-12.95\" font-family=\"Times,serif\" font-size=\"14.00\">l1 : x0</text>\n",
"</g>\n",
"<!-- 7&#45;&gt;8 -->\n",
"<g id=\"edge2\" class=\"edge\">\n",
"<title>7&#45;&gt;8</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M37.02,-71.7C37.02,-64.41 37.02,-55.73 37.02,-47.54\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"40.52,-47.62 37.02,-37.62 33.52,-47.62 40.52,-47.62\"/>\n",
"</g>\n",
"</g>\n",
"</svg>\n"
],
"text/plain": [
"<graphviz.sources.Source at 0x105c27740>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"# Create a factor graph\n",
"graph = SymbolicFactorGraph()\n",
"graph.push_factor(X(0))\n",
"graph.push_factor(X(0), X(1))\n",
"graph.push_factor(X(1), X(2))\n",
"graph.push_factor(X(0), L(1))\n",
"graph.push_factor(X(1), L(2))\n",
"\n",
"# Eliminate to get a Bayes Tree\n",
"ordering = Ordering.ColamdSymbolicFactorGraph(graph)\n",
"bayes_tree = graph.eliminateMultifrontal(ordering)\n",
"\n",
"print(f\"Bayes Tree has {bayes_tree.size()} cliques.\")\n",
"\n",
"roots = bayes_tree.roots()\n",
"print(f\"Number of roots: {len(roots)}\")\n",
"\n",
"# Visualize the Bayes tree using graphviz\n",
"display(graphviz.Source(bayes_tree.dot()))"
]
},
{
"cell_type": "code",
"execution_count": 17,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"\n",
"Inspecting Clique 0:\n",
" Clique Structure: P( x1 x2)\n",
" Associated Conditional: P( P( x1 x2)\n",
" Is Root? True\n",
" Parent Clique is None (likely a root clique).\n",
" Number of Children: 2\n",
"\n",
"Inspecting Clique 0:\n",
" Clique Structure: P( x0 | x1)\n",
" Associated Conditional: P( P( x0 | x1)\n",
" Is Root? False\n",
" Parent Clique exists.\n",
" Number of Children: 1\n",
"\n",
"Inspecting Clique 0:\n",
" Clique Structure: P( l1 | x0)\n",
" Associated Conditional: P( P( l1 | x0)\n",
" Is Root? False\n",
" Parent Clique exists.\n",
" Number of Children: 0\n",
"\n",
"Inspecting Clique 0:\n",
" Clique Structure: P( l2 | x1)\n",
" Associated Conditional: P( P( l2 | x1)\n",
" Is Root? False\n",
" Parent Clique exists.\n",
" Number of Children: 0\n"
]
}
],
"source": [
"def inspect(clique):\n",
" print(\"\\nInspecting Clique 0:\")\n",
" clique.print(\" Clique Structure: \")\n",
" \n",
" # Get the conditional stored in the clique\n",
" conditional = clique.conditional()\n",
" if conditional:\n",
" conditional.print(\" Associated Conditional: P(\")\n",
" else:\n",
" print(\" Clique has no associated conditional (might be empty root)\")\n",
" \n",
" # Check properties\n",
" print(f\" Is Root? {clique.isRoot()}\")\n",
" # Accessing parent/children is possible in C++ but might be less direct or typical in Python wrapper usage\n",
" # Parent clique (careful, might be null for root)\n",
" parent_clique = clique.parent() \n",
" if parent_clique:\n",
" print(\" Parent Clique exists.\")\n",
" else:\n",
" print(\" Parent Clique is None (likely a root clique).\")\n",
" \n",
" print(f\" Number of Children: {clique.nrChildren()}\") # Example if method existed\n",
"\n",
"def traverse_clique(clique):\n",
" inspect(clique)\n",
" for j in range(clique.nrChildren()):\n",
" traverse_clique(clique[j])\n",
"\n",
"for root in roots:\n",
" traverse_clique(root)"
]
}
],
"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": 4
}

View File

@ -0,0 +1,142 @@
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# SymbolicConditional"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"A `SymbolicConditional` represents a conditional probability distribution P(Frontals | Parents) in purely symbolic form. It only stores the keys of the frontal variables and the parent variables, without any associated numerical probability function.\n",
"\n",
"`SymbolicConditional` objects are typically produced as the result of symbolic elimination on a `SymbolicFactorGraph`. A collection of these forms a `SymbolicBayesNet`."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"<a href=\"https://colab.research.google.com/github/borglab/gtsam/blob/develop/gtsam/symbolic/doc/SymbolicConditional.ipynb\" target=\"_parent\"><img src=\"https://colab.research.google.com/assets/colab-badge.svg\" alt=\"Open In Colab\"/></a>"
]
},
{
"cell_type": "code",
"execution_count": 1,
"metadata": {
"tags": [
"remove-cell"
]
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Note: you may need to restart the kernel to use updated packages.\n"
]
}
],
"source": [
"%pip install --quiet gtsam-develop"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"from gtsam import SymbolicConditional\n",
"from gtsam.symbol_shorthand import X, L"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Creating SymbolicConditionals\n",
"\n",
"Conditionals specify frontal (conditioned) variables and parent variables."
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"P(X(0)): P( x0)\n",
" Nr Frontals: 1, Nr Parents: 0\n",
"\n",
"P(X(1) | X(0)): P( x1 | x0)\n",
" Nr Frontals: 1, Nr Parents: 1\n",
"\n",
"P(X(2) | X(0), X(1)): P( x2 | x0 x1)\n",
" Nr Frontals: 1, Nr Parents: 2\n",
"\n",
"P(L(1) | X(0), X(1)): P( l1 | x0 x1)\n",
" Nr Frontals: 1, Nr Parents: 2\n",
"\n",
"P(X(2), L(1) | X(0), X(1)): P( x2 l1 | x0 x1)\n",
" Nr Frontals: 2, Nr Parents: 2\n"
]
}
],
"source": [
"# P(X(0))\n",
"c0 = SymbolicConditional(X(0))\n",
"c0.print(\"P(X(0)): \")\n",
"print(f\" Nr Frontals: {c0.nrFrontals()}, Nr Parents: {c0.nrParents()}\\n\")\n",
"\n",
"# P(X(1) | X(0))\n",
"c1 = SymbolicConditional(X(1), X(0))\n",
"c1.print(\"P(X(1) | X(0)): \")\n",
"print(f\" Nr Frontals: {c1.nrFrontals()}, Nr Parents: {c1.nrParents()}\\n\")\n",
"\n",
"# P(X(2) | X(0), X(1))\n",
"c2 = SymbolicConditional(X(2), X(0), X(1))\n",
"c2.print(\"P(X(2) | X(0), X(1)): \")\n",
"print(f\" Nr Frontals: {c2.nrFrontals()}, Nr Parents: {c2.nrParents()}\\n\")\n",
"\n",
"# P(L(1) | X(0), X(1))\n",
"c3 = SymbolicConditional(L(1), X(0), X(1))\n",
"c3.print(\"P(L(1) | X(0), X(1)): \")\n",
"print(f\" Nr Frontals: {c3.nrFrontals()}, Nr Parents: {c3.nrParents()}\\n\")\n",
"\n",
"# Create from keys and number of frontals, e.g. P(X(2), L(1) | X(0), X(1))\n",
"# Keys = [Frontals..., Parents...]\n",
"c4 = SymbolicConditional.FromKeys([X(2), L(1), X(0), X(1)], 2)\n",
"c4.print(\"P(X(2), L(1) | X(0), X(1)): \")\n",
"print(f\" Nr Frontals: {c4.nrFrontals()}, Nr Parents: {c4.nrParents()}\")"
]
}
],
"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": 4
}

View File

@ -0,0 +1,138 @@
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# SymbolicEliminationTree"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"A `SymbolicEliminationTree` represents the computational structure used in variable elimination, particularly in sparse Cholesky or QR factorization. Each node in the tree corresponds to the elimination of a single variable.\n",
"\n",
"The tree structure reveals dependencies: the elimination of a variable (node) depends on the results from its children in the tree. The root of the tree corresponds to the last variable eliminated. This structure is closely related to the resulting Bayes net or Bayes tree."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"<a href=\"https://colab.research.google.com/github/borglab/gtsam/blob/develop/gtsam/symbolic/doc/SymbolicEliminationTree.ipynb\" target=\"_parent\"><img src=\"https://colab.research.google.com/assets/colab-badge.svg\" alt=\"Open In Colab\"/></a>"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {
"tags": [
"remove-cell"
]
},
"outputs": [],
"source": [
"%pip install --quiet gtsam-develop"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"from gtsam import SymbolicEliminationTree, SymbolicFactorGraph, Ordering\n",
"from gtsam.symbol_shorthand import X, L"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Creating a SymbolicEliminationTree\n",
"\n",
"An elimination tree is constructed from a `SymbolicFactorGraph` and an `Ordering`."
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Symbolic Elimination Tree:\n",
"-(x2)\n",
"Symbolic Elimination Tree:\n",
"| -(x1)\n",
"Symbolic Elimination Tree:\n",
"| - x1 x2\n",
"Symbolic Elimination Tree:\n",
"| | -(x0)\n",
"Symbolic Elimination Tree:\n",
"| | - x0\n",
"Symbolic Elimination Tree:\n",
"| | - x0 x1\n",
"Symbolic Elimination Tree:\n",
"| | | -(l1)\n",
"Symbolic Elimination Tree:\n",
"| | | - x0 l1\n",
"Symbolic Elimination Tree:\n",
"| | -(l2)\n",
"Symbolic Elimination Tree:\n",
"| | - x1 l2\n"
]
}
],
"source": [
"# Create a factor graph\n",
"graph = SymbolicFactorGraph()\n",
"graph.push_factor(X(0))\n",
"graph.push_factor(X(0), X(1))\n",
"graph.push_factor(X(1), X(2))\n",
"graph.push_factor(X(0), L(1))\n",
"graph.push_factor(X(1), L(2))\n",
"\n",
"# Define an elimination ordering\n",
"ordering = Ordering([L(1), L(2), X(0), X(1), X(2)]) # Eliminate L(1) first, then X(0), X(1), X(2) last\n",
"\n",
"# Construct the elimination tree\n",
"elimination_tree = SymbolicEliminationTree(graph, ordering)\n",
"\n",
"# Print the tree structure (text representation)\n",
"elimination_tree.print(\"Symbolic Elimination Tree:\\n\")"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"*(Note: Direct visualization of the elimination tree structure isn't available via a simple `.dot()` method like factor graphs or Bayes nets/trees in the Python wrapper, but the print output shows the parent-child relationships.)*"
]
}
],
"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": 4
}

View File

@ -0,0 +1,131 @@
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# SymbolicFactor"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"A `SymbolicFactor` represents the connectivity (topology) between variables in a factor graph without any specific numerical function associated with it. It's primarily to *illustrate* symbolic elimination. Internally, GTSAM does analyze the structure of other factor graph types without explicitly converting to a symbolic factor graph.\n",
"\n",
"It inherits from `gtsam.Factor` and stores the keys (indices) of the variables it connects."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"<a href=\"https://colab.research.google.com/github/borglab/gtsam/blob/develop/gtsam/symbolic/doc/SymbolicFactor.ipynb\" target=\"_parent\"><img src=\"https://colab.research.google.com/assets/colab-badge.svg\" alt=\"Open In Colab\"/></a>"
]
},
{
"cell_type": "code",
"execution_count": 1,
"metadata": {
"tags": [
"remove-cell"
]
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Note: you may need to restart the kernel to use updated packages.\n"
]
}
],
"source": [
"%pip install --quiet gtsam-develop"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [],
"source": [
"import gtsam\n",
"from gtsam import SymbolicFactor\n",
"from gtsam.symbol_shorthand import X\n",
"\n",
"# Example Keys\n",
"x0, x1, x2 = X(0), X(1), X(2)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Creating SymbolicFactors\n",
"\n",
"SymbolicFactors can be created by specifying the keys they involve."
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Unary Factor f0: \n",
" x0\n",
"Binary Factor f1: \n",
" x0 x1\n",
"Ternary Factor f2: \n",
" x1 x2 x0\n",
"Factor f3 from KeyVector: \n",
" x0 x1 x2\n"
]
}
],
"source": [
"# Unary factor\n",
"f0 = SymbolicFactor(x0)\n",
"f0.print(\"Unary Factor f0: \\n\")\n",
"\n",
"# Binary factor\n",
"f1 = SymbolicFactor(x0, x1)\n",
"f1.print(\"Binary Factor f1: \\n\")\n",
"\n",
"# Ternary factor\n",
"f2 = SymbolicFactor(x1, x2, x0)\n",
"f2.print(\"Ternary Factor f2: \\n\")\n",
"\n",
"# From a list of keys\n",
"keys = gtsam.KeyVector([x0, x1, x2])\n",
"f3 = SymbolicFactor.FromKeys(keys)\n",
"f3.print(\"Factor f3 from KeyVector: \\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": 4
}

View File

@ -0,0 +1,479 @@
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# SymbolicFactorGraph"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"A `SymbolicFactorGraph` is a factor graph consisting purely of `SymbolicFactor` objects. It represents the structure or topology of a probabilistic graphical model (like a Markov Random Field) without the numerical details.\n",
"\n",
"It's primarily used to *illustrate* symbolic elimination, which determines the structure of the resulting Bayes net or Bayes tree and finds an efficient variable elimination ordering (e.g., using COLAMD or METIS)."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"<a href=\"https://colab.research.google.com/github/borglab/gtsam/blob/develop/gtsam/symbolic/doc/SymbolicFactorGraph.ipynb\" target=\"_parent\"><img src=\"https://colab.research.google.com/assets/colab-badge.svg\" alt=\"Open In Colab\"/></a>"
]
},
{
"cell_type": "code",
"execution_count": 1,
"metadata": {
"tags": [
"remove-cell"
]
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Note: you may need to restart the kernel to use updated packages.\n"
]
}
],
"source": [
"%pip install --quiet gtsam-develop"
]
},
{
"cell_type": "code",
"execution_count": 13,
"metadata": {},
"outputs": [],
"source": [
"from gtsam import SymbolicFactorGraph, Ordering\n",
"from gtsam.symbol_shorthand import X, L\n",
"import graphviz"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Creating and Manipulating Symbolic Factor Graphs"
]
},
{
"cell_type": "code",
"execution_count": 12,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Symbolic Factor Graph:\n",
" \n",
"size: 5\n",
"factor 0: x0\n",
"factor 1: x0 x1\n",
"factor 2: x1 x2\n",
"factor 3: x0 l1\n",
"factor 4: x1 l2\n"
]
},
{
"data": {
"image/svg+xml": [
"<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n",
"<!DOCTYPE svg PUBLIC \"-//W3C//DTD SVG 1.1//EN\"\n",
" \"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd\">\n",
"<!-- Generated by graphviz version 12.0.0 (0)\n",
" -->\n",
"<!-- Pages: 1 -->\n",
"<svg width=\"350pt\" height=\"84pt\"\n",
" viewBox=\"0.00 0.00 350.00 83.60\" xmlns=\"http://www.w3.org/2000/svg\" xmlns:xlink=\"http://www.w3.org/1999/xlink\">\n",
"<g id=\"graph0\" class=\"graph\" transform=\"scale(1 1) rotate(0) translate(4 79.6)\">\n",
"<polygon fill=\"white\" stroke=\"none\" points=\"-4,4 -4,-79.6 346,-79.6 346,4 -4,4\"/>\n",
"<!-- var7782220156096217089 -->\n",
"<g id=\"node1\" class=\"node\">\n",
"<title>var7782220156096217089</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"27\" cy=\"-57.6\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"27\" y=\"-52.55\" font-family=\"Times,serif\" font-size=\"14.00\">l1</text>\n",
"</g>\n",
"<!-- factor3 -->\n",
"<g id=\"node9\" class=\"node\">\n",
"<title>factor3</title>\n",
"<ellipse fill=\"black\" stroke=\"black\" cx=\"52\" cy=\"-1.8\" rx=\"1.8\" ry=\"1.8\"/>\n",
"</g>\n",
"<!-- var7782220156096217089&#45;&#45;factor3 -->\n",
"<g id=\"edge7\" class=\"edge\">\n",
"<title>var7782220156096217089&#45;&#45;factor3</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M34.77,-39.87C41.08,-26.3 49.27,-8.68 51.45,-3.99\"/>\n",
"</g>\n",
"<!-- var7782220156096217090 -->\n",
"<g id=\"node2\" class=\"node\">\n",
"<title>var7782220156096217090</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"315\" cy=\"-57.6\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"315\" y=\"-52.55\" font-family=\"Times,serif\" font-size=\"14.00\">l2</text>\n",
"</g>\n",
"<!-- factor4 -->\n",
"<g id=\"node10\" class=\"node\">\n",
"<title>factor4</title>\n",
"<ellipse fill=\"black\" stroke=\"black\" cx=\"279\" cy=\"-1.8\" rx=\"1.8\" ry=\"1.8\"/>\n",
"</g>\n",
"<!-- var7782220156096217090&#45;&#45;factor4 -->\n",
"<g id=\"edge9\" class=\"edge\">\n",
"<title>var7782220156096217090&#45;&#45;factor4</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M304.39,-40.75C295.1,-26.86 282.63,-8.22 279.66,-3.78\"/>\n",
"</g>\n",
"<!-- var8646911284551352320 -->\n",
"<g id=\"node3\" class=\"node\">\n",
"<title>var8646911284551352320</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"99\" cy=\"-57.6\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"99\" y=\"-52.55\" font-family=\"Times,serif\" font-size=\"14.00\">x0</text>\n",
"</g>\n",
"<!-- factor0 -->\n",
"<g id=\"node6\" class=\"node\">\n",
"<title>factor0</title>\n",
"<ellipse fill=\"black\" stroke=\"black\" cx=\"99\" cy=\"-1.8\" rx=\"1.8\" ry=\"1.8\"/>\n",
"</g>\n",
"<!-- var8646911284551352320&#45;&#45;factor0 -->\n",
"<g id=\"edge1\" class=\"edge\">\n",
"<title>var8646911284551352320&#45;&#45;factor0</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M99,-39.28C99,-25.77 99,-8.54 99,-3.96\"/>\n",
"</g>\n",
"<!-- factor1 -->\n",
"<g id=\"node7\" class=\"node\">\n",
"<title>factor1</title>\n",
"<ellipse fill=\"black\" stroke=\"black\" cx=\"160\" cy=\"-1.8\" rx=\"1.8\" ry=\"1.8\"/>\n",
"</g>\n",
"<!-- var8646911284551352320&#45;&#45;factor1 -->\n",
"<g id=\"edge2\" class=\"edge\">\n",
"<title>var8646911284551352320&#45;&#45;factor1</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M114.71,-42.75C131.09,-28.3 154.98,-7.23 159.31,-3.41\"/>\n",
"</g>\n",
"<!-- var8646911284551352320&#45;&#45;factor3 -->\n",
"<g id=\"edge6\" class=\"edge\">\n",
"<title>var8646911284551352320&#45;&#45;factor3</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M85.91,-41.61C73.74,-27.68 56.91,-8.41 52.89,-3.81\"/>\n",
"</g>\n",
"<!-- var8646911284551352321 -->\n",
"<g id=\"node4\" class=\"node\">\n",
"<title>var8646911284551352321</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"243\" cy=\"-57.6\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"243\" y=\"-52.55\" font-family=\"Times,serif\" font-size=\"14.00\">x1</text>\n",
"</g>\n",
"<!-- var8646911284551352321&#45;&#45;factor1 -->\n",
"<g id=\"edge3\" class=\"edge\">\n",
"<title>var8646911284551352321&#45;&#45;factor1</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M224.17,-44.39C201.97,-30.01 167.31,-7.54 161,-3.45\"/>\n",
"</g>\n",
"<!-- factor2 -->\n",
"<g id=\"node8\" class=\"node\">\n",
"<title>factor2</title>\n",
"<ellipse fill=\"black\" stroke=\"black\" cx=\"196\" cy=\"-1.8\" rx=\"1.8\" ry=\"1.8\"/>\n",
"</g>\n",
"<!-- var8646911284551352321&#45;&#45;factor2 -->\n",
"<g id=\"edge4\" class=\"edge\">\n",
"<title>var8646911284551352321&#45;&#45;factor2</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M229.91,-41.61C217.74,-27.68 200.91,-8.41 196.89,-3.81\"/>\n",
"</g>\n",
"<!-- var8646911284551352321&#45;&#45;factor4 -->\n",
"<g id=\"edge8\" class=\"edge\">\n",
"<title>var8646911284551352321&#45;&#45;factor4</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M253.61,-40.75C262.9,-26.86 275.37,-8.22 278.34,-3.78\"/>\n",
"</g>\n",
"<!-- var8646911284551352322 -->\n",
"<g id=\"node5\" class=\"node\">\n",
"<title>var8646911284551352322</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"171\" cy=\"-57.6\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"171\" y=\"-52.55\" font-family=\"Times,serif\" font-size=\"14.00\">x2</text>\n",
"</g>\n",
"<!-- var8646911284551352322&#45;&#45;factor2 -->\n",
"<g id=\"edge5\" class=\"edge\">\n",
"<title>var8646911284551352322&#45;&#45;factor2</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M178.77,-39.87C185.08,-26.3 193.27,-8.68 195.45,-3.99\"/>\n",
"</g>\n",
"</g>\n",
"</svg>\n"
],
"text/plain": [
"<graphviz.sources.Source at 0x107b7c890>"
]
},
"execution_count": 12,
"metadata": {},
"output_type": "execute_result"
}
],
"source": [
"# Create an empty graph\n",
"graph = SymbolicFactorGraph()\n",
"\n",
"# Add factors (using convenience methods)\n",
"graph.push_factor(X(0)) # Unary\n",
"graph.push_factor(X(0), X(1))\n",
"graph.push_factor(X(1), X(2))\n",
"graph.push_factor(X(0), L(1))\n",
"graph.push_factor(X(1), L(2))\n",
"\n",
"# Print the graph structure\n",
"graph.print(\"Symbolic Factor Graph:\\n\")\n",
"\n",
"# Visualize the graph using Graphviz\n",
"graphviz.Source(graph.dot())"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Symbolic Elimination\n",
"\n",
"We can perform symbolic elimination to get the structure of the resulting Bayes net or Bayes tree."
]
},
{
"cell_type": "code",
"execution_count": 16,
"metadata": {},
"outputs": [],
"source": [
"# Define an elimination ordering (can also be computed automatically)\n",
"ordering = Ordering([L(1), L(2), X(0), X(1), X(2)])"
]
},
{
"cell_type": "code",
"execution_count": 18,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"\n",
"Resulting Symbolic Bayes Net:\n",
" \n",
"size: 5\n",
"conditional 0: P( l1 | x0)\n",
"conditional 1: P( x0 | x1)\n",
"conditional 2: P( l2 | x1)\n",
"conditional 3: P( x1 | x2)\n",
"conditional 4: P( x2)\n"
]
},
{
"data": {
"image/svg+xml": [
"<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n",
"<!DOCTYPE svg PUBLIC \"-//W3C//DTD SVG 1.1//EN\"\n",
" \"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd\">\n",
"<!-- Generated by graphviz version 12.0.0 (0)\n",
" -->\n",
"<!-- Pages: 1 -->\n",
"<svg width=\"134pt\" height=\"260pt\"\n",
" viewBox=\"0.00 0.00 134.00 260.00\" xmlns=\"http://www.w3.org/2000/svg\" xmlns:xlink=\"http://www.w3.org/1999/xlink\">\n",
"<g id=\"graph0\" class=\"graph\" transform=\"scale(1 1) rotate(0) translate(4 256)\">\n",
"<polygon fill=\"white\" stroke=\"none\" points=\"-4,4 -4,-256 130,-256 130,4 -4,4\"/>\n",
"<!-- var7782220156096217089 -->\n",
"<g id=\"node1\" class=\"node\">\n",
"<title>var7782220156096217089</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"99\" cy=\"-18\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"99\" y=\"-12.95\" font-family=\"Times,serif\" font-size=\"14.00\">l1</text>\n",
"</g>\n",
"<!-- var7782220156096217090 -->\n",
"<g id=\"node2\" class=\"node\">\n",
"<title>var7782220156096217090</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"27\" cy=\"-90\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"27\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">l2</text>\n",
"</g>\n",
"<!-- var8646911284551352320 -->\n",
"<g id=\"node3\" class=\"node\">\n",
"<title>var8646911284551352320</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"99\" cy=\"-90\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"99\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">x0</text>\n",
"</g>\n",
"<!-- var8646911284551352320&#45;&gt;var7782220156096217089 -->\n",
"<g id=\"edge4\" class=\"edge\">\n",
"<title>var8646911284551352320&#45;&gt;var7782220156096217089</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M99,-71.7C99,-64.41 99,-55.73 99,-47.54\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"102.5,-47.62 99,-37.62 95.5,-47.62 102.5,-47.62\"/>\n",
"</g>\n",
"<!-- var8646911284551352321 -->\n",
"<g id=\"node4\" class=\"node\">\n",
"<title>var8646911284551352321</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"63\" cy=\"-162\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"63\" y=\"-156.95\" font-family=\"Times,serif\" font-size=\"14.00\">x1</text>\n",
"</g>\n",
"<!-- var8646911284551352321&#45;&gt;var7782220156096217090 -->\n",
"<g id=\"edge2\" class=\"edge\">\n",
"<title>var8646911284551352321&#45;&gt;var7782220156096217090</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M54.65,-144.76C50.42,-136.55 45.19,-126.37 40.42,-117.09\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"43.68,-115.79 36,-108.49 37.46,-118.99 43.68,-115.79\"/>\n",
"</g>\n",
"<!-- var8646911284551352321&#45;&gt;var8646911284551352320 -->\n",
"<g id=\"edge3\" class=\"edge\">\n",
"<title>var8646911284551352321&#45;&gt;var8646911284551352320</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M71.35,-144.76C75.58,-136.55 80.81,-126.37 85.58,-117.09\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"88.54,-118.99 90,-108.49 82.32,-115.79 88.54,-118.99\"/>\n",
"</g>\n",
"<!-- var8646911284551352322 -->\n",
"<g id=\"node5\" class=\"node\">\n",
"<title>var8646911284551352322</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"63\" cy=\"-234\" rx=\"27\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"63\" y=\"-228.95\" font-family=\"Times,serif\" font-size=\"14.00\">x2</text>\n",
"</g>\n",
"<!-- var8646911284551352322&#45;&gt;var8646911284551352321 -->\n",
"<g id=\"edge1\" class=\"edge\">\n",
"<title>var8646911284551352322&#45;&gt;var8646911284551352321</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M63,-215.7C63,-208.41 63,-199.73 63,-191.54\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"66.5,-191.62 63,-181.62 59.5,-191.62 66.5,-191.62\"/>\n",
"</g>\n",
"</g>\n",
"</svg>\n"
],
"text/plain": [
"<graphviz.sources.Source at 0x107815d30>"
]
},
"execution_count": 18,
"metadata": {},
"output_type": "execute_result"
}
],
"source": [
"# Eliminate sequentially to get a Bayes Net structure\n",
"bayes_net = graph.eliminateSequential(ordering)\n",
"bayes_net.print(\"\\nResulting Symbolic Bayes Net:\\n\")\n",
"\n",
"# Visualize the Bayes Net using Graphviz\n",
"graphviz.Source(bayes_net.dot())"
]
},
{
"cell_type": "code",
"execution_count": 19,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"\n",
"Resulting Symbolic Bayes Tree:\n",
": cliques: 4, variables: 5\n",
"\n",
"Resulting Symbolic Bayes Tree:\n",
"- P( x1 x2)\n",
"\n",
"Resulting Symbolic Bayes Tree:\n",
"| - P( x0 | x1)\n",
"\n",
"Resulting Symbolic Bayes Tree:\n",
"| | - P( l1 | x0)\n",
"\n",
"Resulting Symbolic Bayes Tree:\n",
"| - P( l2 | x1)\n"
]
},
{
"data": {
"image/svg+xml": [
"<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n",
"<!DOCTYPE svg PUBLIC \"-//W3C//DTD SVG 1.1//EN\"\n",
" \"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd\">\n",
"<!-- Generated by graphviz version 12.0.0 (0)\n",
" -->\n",
"<!-- Title: G Pages: 1 -->\n",
"<svg width=\"170pt\" height=\"188pt\"\n",
" viewBox=\"0.00 0.00 169.99 188.00\" xmlns=\"http://www.w3.org/2000/svg\" xmlns:xlink=\"http://www.w3.org/1999/xlink\">\n",
"<g id=\"graph0\" class=\"graph\" transform=\"scale(1 1) rotate(0) translate(4 184)\">\n",
"<title>G</title>\n",
"<polygon fill=\"white\" stroke=\"none\" points=\"-4,4 -4,-184 165.99,-184 165.99,4 -4,4\"/>\n",
"<!-- 0 -->\n",
"<g id=\"node1\" class=\"node\">\n",
"<title>0</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"82.02\" cy=\"-162\" rx=\"34.46\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"82.02\" y=\"-156.95\" font-family=\"Times,serif\" font-size=\"14.00\">x1, x2</text>\n",
"</g>\n",
"<!-- 1 -->\n",
"<g id=\"node2\" class=\"node\">\n",
"<title>1</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"37.02\" cy=\"-90\" rx=\"37.02\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"37.02\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">x0 : x1</text>\n",
"</g>\n",
"<!-- 0&#45;&gt;1 -->\n",
"<g id=\"edge1\" class=\"edge\">\n",
"<title>0&#45;&gt;1</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M71.36,-144.41C66.09,-136.22 59.61,-126.14 53.71,-116.95\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"56.78,-115.26 48.43,-108.74 50.89,-119.05 56.78,-115.26\"/>\n",
"</g>\n",
"<!-- 3 -->\n",
"<g id=\"node4\" class=\"node\">\n",
"<title>3</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"127.02\" cy=\"-90\" rx=\"34.97\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"127.02\" y=\"-84.95\" font-family=\"Times,serif\" font-size=\"14.00\">l2 : x1</text>\n",
"</g>\n",
"<!-- 0&#45;&gt;3 -->\n",
"<g id=\"edge3\" class=\"edge\">\n",
"<title>0&#45;&gt;3</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M92.69,-144.41C97.95,-136.22 104.43,-126.14 110.34,-116.95\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"113.15,-119.05 115.61,-108.74 107.26,-115.26 113.15,-119.05\"/>\n",
"</g>\n",
"<!-- 2 -->\n",
"<g id=\"node3\" class=\"node\">\n",
"<title>2</title>\n",
"<ellipse fill=\"none\" stroke=\"black\" cx=\"37.02\" cy=\"-18\" rx=\"34.97\" ry=\"18\"/>\n",
"<text text-anchor=\"middle\" x=\"37.02\" y=\"-12.95\" font-family=\"Times,serif\" font-size=\"14.00\">l1 : x0</text>\n",
"</g>\n",
"<!-- 1&#45;&gt;2 -->\n",
"<g id=\"edge2\" class=\"edge\">\n",
"<title>1&#45;&gt;2</title>\n",
"<path fill=\"none\" stroke=\"black\" d=\"M37.02,-71.7C37.02,-64.41 37.02,-55.73 37.02,-47.54\"/>\n",
"<polygon fill=\"black\" stroke=\"black\" points=\"40.52,-47.62 37.02,-37.62 33.52,-47.62 40.52,-47.62\"/>\n",
"</g>\n",
"</g>\n",
"</svg>\n"
],
"text/plain": [
"<graphviz.sources.Source at 0x111534470>"
]
},
"execution_count": 19,
"metadata": {},
"output_type": "execute_result"
}
],
"source": [
"# Eliminate using Multifrontal method to get a Bayes Tree structure\n",
"bayes_tree = graph.eliminateMultifrontal(ordering)\n",
"bayes_tree.print(\"\\nResulting Symbolic Bayes Tree:\\n\")\n",
"\n",
"# Visualize the Bayes Tree using Graphviz\n",
"graphviz.Source(bayes_tree.dot())"
]
}
],
"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": 4
}

View File

@ -0,0 +1,133 @@
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# SymbolicJunctionTree"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"A `SymbolicJunctionTree` (often used interchangeably with Clique Tree in GTSAM documentation) is a data structure used in multifrontal variable elimination. It's derived from an `EliminationTree`.\n",
"\n",
"Key differences from an Elimination Tree:\n",
"* **Nodes are Cliques:** Each node in a Junction Tree represents a *clique* (a group of variables eliminated together), not just a single variable.\n",
"* **Stores Factors:** Nodes (`SymbolicCluster` objects) store the symbolic factors associated with the variables in that clique.\n",
"\n",
"The Junction Tree organizes the factors and variables for efficient multifrontal elimination, which processes variables in these larger cliques simultaneously. The result of eliminating a Junction Tree is a `SymbolicBayesTree`."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"<a href=\"https://colab.research.google.com/github/borglab/gtsam/blob/develop/gtsam/symbolic/doc/SymbolicJunctionTree.ipynb\" target=\"_parent\"><img src=\"https://colab.research.google.com/assets/colab-badge.svg\" alt=\"Open In Colab\"/></a>"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {
"tags": [
"remove-cell"
]
},
"outputs": [],
"source": [
"%pip install --quiet gtsam-develop"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"from gtsam import SymbolicJunctionTree, SymbolicEliminationTree, SymbolicFactorGraph, Ordering\n",
"from gtsam.symbol_shorthand import X, L"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Creating a SymbolicJunctionTree\n",
"\n",
"A Junction Tree is constructed from a `SymbolicEliminationTree`."
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Symbolic Junction Tree:\n",
"- (6) x1 x2 \n",
"Symbolic Junction Tree:\n",
"| - (6) x0 \n",
"Symbolic Junction Tree:\n",
"| | - (2) l1 \n",
"Symbolic Junction Tree:\n",
"| - (2) l2 \n"
]
}
],
"source": [
"# Create a factor graph\n",
"graph = SymbolicFactorGraph()\n",
"graph.push_factor(X(0))\n",
"graph.push_factor(X(0), X(1))\n",
"graph.push_factor(X(1), X(2))\n",
"graph.push_factor(X(0), L(1))\n",
"graph.push_factor(X(1), L(2))\n",
"\n",
"# Define an elimination ordering\n",
"ordering = Ordering([L(1), L(2), X(0), X(1), X(2)]) \n",
"\n",
"# Construct the elimination tree first\n",
"elimination_tree = SymbolicEliminationTree(graph, ordering)\n",
"\n",
"# Construct the junction tree from the elimination tree\n",
"junction_tree = SymbolicJunctionTree(elimination_tree)\n",
"\n",
"# Print the tree structure (text representation)\n",
"junction_tree.print(\"Symbolic Junction Tree:\\n\")"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"*(Note: The `SymbolicCluster` class represents the nodes within the Junction Tree, containing the factors and frontal/separator keys for that clique. Direct visualization is usually done via the resulting Bayes Tree.)*"
]
}
],
"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": 4
}

View File

@ -185,6 +185,8 @@ class SymbolicBayesTreeClique {
const gtsam::SymbolicConditional* conditional() const; const gtsam::SymbolicConditional* conditional() const;
bool isRoot() const; bool isRoot() const;
gtsam::SymbolicBayesTreeClique* parent() const; gtsam::SymbolicBayesTreeClique* parent() const;
size_t nrChildren() const;
gtsam::SymbolicBayesTreeClique* operator[](size_t j) const;
size_t treeSize() const; size_t treeSize() const;
size_t numCachedSeparatorMarginals() const; size_t numCachedSeparatorMarginals() const;
void deleteCachedShortcuts(); void deleteCachedShortcuts();
@ -204,7 +206,7 @@ class SymbolicBayesTree {
// Standard Interface // Standard Interface
bool empty() const; bool empty() const;
size_t size() const; size_t size() const;
const SymbolicBayesTree::Roots& roots() const;
const gtsam::SymbolicBayesTreeClique* operator[](size_t j) const; const gtsam::SymbolicBayesTreeClique* operator[](size_t j) const;
void saveGraph(string s, void saveGraph(string s,

View File

@ -0,0 +1,40 @@
# Symbolic Module
The `symbolic` module in GTSAM deals with the *structure* of factor graphs and Bayesian networks, independent of the specific numerical types of factors (like Gaussian or discrete). It allows for analyzing graph connectivity, determining optimal variable elimination orders, and understanding the sparsity structure of the resulting inference objects.
This is crucial for efficient inference, as the symbolic elimination steps determine the computational complexity and memory requirements of the numerical factorization.
The classes here are used primarily to *illustrate* symbolic elimination. Internally, GTSAM does analyze the structure of other factor graph types without explicitly converting to a symbolic factor graph.
## Classes
Here's an overview of the key classes in the `symbolic` module:
### Factor Graph
- **[SymbolicFactor](doc/SymbolicFactor.ipynb)**: Represents the connectivity between a set of variables (keys) in a factor graph, without any specific numerical function associated with it. It defines the hyperedges of the graph.
- **[SymbolicFactorGraph](doc/SymbolicFactorGraph.ipynb)**: A collection of `SymbolicFactor` objects, representing the overall structure of a factor graph.
### Elimination Products
These classes represent the results of symbolic variable elimination:
- **[SymbolicConditional](doc/SymbolicConditional.ipynb)**: Represents the structure of a conditional probability distribution P(Frontals | Parents). It stores the keys of the frontal (conditioned) and parent variables resulting from eliminating one or more variables from a set of factors.
- **[SymbolicBayesNet](doc/SymbolicBayesNet.ipynb)**: A directed acyclic graph composed of `SymbolicConditional` objects, representing the structure of a factorized distribution P(X) = Π P(Xi | Parents(Xi)). Typically results from sequential elimination.
- **[SymbolicBayesTree](doc/SymbolicBayesTree.ipynb)**: A tree structure where each node (`SymbolicBayesTreeClique`) represents a `SymbolicConditional` P(Frontals | Separator). This is the result of multifrontal elimination and is the underlying structure for efficient incremental updates (iSAM) and exact marginal computation.
- **[SymbolicBayesTreeClique](doc/SymbolicBayesTreeClique.ipynb)**: Represents a single clique (node) within a `SymbolicBayesTree`, containing a `SymbolicConditional`.
### Elimination Structures
These classes represent intermediate structures used during the elimination process:
- **[SymbolicEliminationTree](doc/SymbolicEliminationTree.ipynb)**: Represents the dependency structure of sequential variable elimination. Each node corresponds to eliminating a single variable.
- **[SymbolicJunctionTree](doc/SymbolicJunctionTree.ipynb)** (Clique Tree): An intermediate structure used in multifrontal elimination, derived from an elimination tree. Each node (`SymbolicCluster`) represents a clique of variables eliminated together and stores the *factors* associated with that clique.
**Importance**
Performing symbolic analysis can be used for:
1. Choosing an Optimal Ordering: Finding an ordering that minimizes fill-in (new connections created during elimination) is key to efficient numerical factorization.
2. Predicting Computational Cost: The structure of the Bayes net or Bayes tree determines the complexity of subsequent numerical operations like solving or marginalization.
3. Memory Allocation: Knowing the structure allows for pre-allocation of memory for the numerical factorization.
The symbolic module provides the foundation for GTSAM's efficient inference algorithms.

View File

@ -19,6 +19,9 @@ project:
- file: ./gtsam/nonlinear/nonlinear.md - file: ./gtsam/nonlinear/nonlinear.md
children: children:
- pattern: ./gtsam/nonlinear/doc/* - pattern: ./gtsam/nonlinear/doc/*
- file: ./gtsam/symbolic/symbolic.md
children:
- pattern: ./gtsam/symbolic/doc/*
- file: ./gtsam/navigation/navigation.md - file: ./gtsam/navigation/navigation.md
children: children:
- pattern: ./gtsam/navigation/doc/* - pattern: ./gtsam/navigation/doc/*
@ -28,17 +31,15 @@ project:
- file: ./doc/expressions.md - file: ./doc/expressions.md
site: site:
nav: nav:
- title: Getting started - title: GTSAM.org
children: url: https://gtsam.org
- title: Overview
url: /readme
- title: Install guide
url: /install
- title: C++ reference - title: C++ reference
url: https://gtsam.org/doxygen/ url: https://gtsam.org/doxygen/
options:
logo_text: GTSAM
template: book-theme template: book-theme
# TODO: Graphics for favicon and to replace "Made with MyST" in the top left # TODO: Graphics for favicon, site logo
# options: # options:
# favicon: favicon.ico # favicon: favicon.ico
# logo: site_logo.png # logo: site_logo.png