{
"cells": [
{
"cell_type": "markdown",
"id": "dc268456",
"metadata": {},
"source": [
"
"
]
},
{
"cell_type": "markdown",
"id": "23d8e5dc",
"metadata": {},
"source": [
"# Pose2 SLAM\n",
"\n",
"A simple way to do Simultaneous Localization and Mapping is to just fuse **relative pose measurements** between successive robot poses. This landmark-less SLAM variant is often called \"Pose SLAM\""
]
},
{
"cell_type": "code",
"execution_count": 16,
"id": "b411e885",
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Note: you may need to restart the kernel to use updated packages.\n"
]
}
],
"source": [
"%pip -q install gtbook # also installs latest gtsam pre-release"
]
},
{
"cell_type": "code",
"execution_count": 1,
"id": "50de8e04",
"metadata": {},
"outputs": [],
"source": [
"import math\n",
"\n",
"import gtsam\n",
"import gtsam.utils.plot as gtsam_plot\n",
"import matplotlib.pyplot as plt"
]
},
{
"cell_type": "code",
"execution_count": 2,
"id": "8a3e738c",
"metadata": {},
"outputs": [],
"source": [
"PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(gtsam.Point3(0.3, 0.3, 0.1))\n",
"ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(\n",
" gtsam.Point3(0.2, 0.2, 0.1))"
]
},
{
"cell_type": "markdown",
"id": "61a0af2d",
"metadata": {},
"source": [
"\n",
"1. Create a factor graph container and add factors to it\n"
]
},
{
"cell_type": "code",
"execution_count": 3,
"id": "2a886c14",
"metadata": {},
"outputs": [],
"source": [
"graph = gtsam.NonlinearFactorGraph()"
]
},
{
"cell_type": "markdown",
"id": "19d98400",
"metadata": {},
"source": [
"2a. Add a prior on the first pose, setting it to the origin\n",
"\n",
"A prior factor consists of a mean and a noise ODOMETRY_NOISE (covariance matrix)"
]
},
{
"cell_type": "code",
"execution_count": 4,
"id": "5e8a16f8",
"metadata": {},
"outputs": [],
"source": [
"graph.add(gtsam.PriorFactorPose2(1, gtsam.Pose2(0, 0, 0), PRIOR_NOISE))"
]
},
{
"cell_type": "markdown",
"id": "b3702aa9",
"metadata": {},
"source": [
"2b. Add odometry factors\n",
"Create odometry (Between) factors between consecutive poses\n"
]
},
{
"cell_type": "code",
"execution_count": 5,
"id": "6f364334",
"metadata": {},
"outputs": [],
"source": [
"graph.add(gtsam.BetweenFactorPose2(1, 2, gtsam.Pose2(2, 0, 0), ODOMETRY_NOISE))\n",
"graph.add(gtsam.BetweenFactorPose2(2, 3, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))\n",
"graph.add(gtsam.BetweenFactorPose2(3, 4, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))\n",
"graph.add(gtsam.BetweenFactorPose2(4, 5, gtsam.Pose2(2, 0, math.pi / 2),ODOMETRY_NOISE))\n"
]
},
{
"cell_type": "markdown",
"id": "c8ca6f8c",
"metadata": {},
"source": [
"2c. Add the loop closure constraint\n",
"This factor encodes the fact that we have returned to the same pose. In real\n",
"systems, these constraints may be identified in many ways, such as appearance-based\n",
"techniques with camera images. We will use another Between Factor to enforce this constraint:\n"
]
},
{
"cell_type": "code",
"execution_count": 6,
"id": "572fd291",
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"\n",
"Factor Graph:\n",
"NonlinearFactorGraph: size: 6\n",
"\n",
"Factor 0: PriorFactor on 1\n",
" prior mean: (0, 0, 0)\n",
" noise model: diagonal sigmas [0.3; 0.3; 0.1];\n",
"\n",
"Factor 1: BetweenFactor(1,2)\n",
" measured: (2, 0, 0)\n",
" noise model: diagonal sigmas [0.2; 0.2; 0.1];\n",
"\n",
"Factor 2: BetweenFactor(2,3)\n",
" measured: (2, 0, 1.57079633)\n",
" noise model: diagonal sigmas [0.2; 0.2; 0.1];\n",
"\n",
"Factor 3: BetweenFactor(3,4)\n",
" measured: (2, 0, 1.57079633)\n",
" noise model: diagonal sigmas [0.2; 0.2; 0.1];\n",
"\n",
"Factor 4: BetweenFactor(4,5)\n",
" measured: (2, 0, 1.57079633)\n",
" noise model: diagonal sigmas [0.2; 0.2; 0.1];\n",
"\n",
"Factor 5: BetweenFactor(5,2)\n",
" measured: (2, 0, 1.57079633)\n",
" noise model: diagonal sigmas [0.2; 0.2; 0.1];\n",
"\n",
"\n"
]
}
],
"source": [
"graph.add( gtsam.BetweenFactorPose2(5, 2, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))\n",
"print(\"\\nFactor Graph:\\n{}\".format(graph))"
]
},
{
"cell_type": "markdown",
"id": "89666b19",
"metadata": {},
"source": [
"3. Create the data structure to hold the initial_estimate estimate to the\n",
"solution. For illustrative purposes, these have been deliberately set to incorrect values\n"
]
},
{
"cell_type": "code",
"execution_count": 7,
"id": "5cfc8900",
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"\n",
"Initial Estimate:\n",
"Values with 5 values:\n",
"Value 1: (gtsam::Pose2)\n",
"(0.5, 0, 0.2)\n",
"\n",
"Value 2: (gtsam::Pose2)\n",
"(2.3, 0.1, -0.2)\n",
"\n",
"Value 3: (gtsam::Pose2)\n",
"(4.1, 0.1, 1.57079633)\n",
"\n",
"Value 4: (gtsam::Pose2)\n",
"(4, 2, 3.14159265)\n",
"\n",
"Value 5: (gtsam::Pose2)\n",
"(2.1, 2.1, -1.57079633)\n",
"\n",
"\n"
]
}
],
"source": [
"initial_estimate = gtsam.Values()\n",
"initial_estimate.insert(1, gtsam.Pose2(0.5, 0.0, 0.2))\n",
"initial_estimate.insert(2, gtsam.Pose2(2.3, 0.1, -0.2))\n",
"initial_estimate.insert(3, gtsam.Pose2(4.1, 0.1, math.pi / 2))\n",
"initial_estimate.insert(4, gtsam.Pose2(4.0, 2.0, math.pi))\n",
"initial_estimate.insert(5, gtsam.Pose2(2.1, 2.1, -math.pi / 2))\n",
"print(\"\\nInitial Estimate:\\n{}\".format(initial_estimate)) "
]
},
{
"cell_type": "markdown",
"id": "591abefb",
"metadata": {},
"source": [
"4. Optimize the initial values using a Gauss-Newton nonlinear optimizer\n",
"The optimizer accepts an optional set of configuration parameters,\n",
"controlling things like convergence criteria, the type of linear\n",
"system solver to use, and the amount of information displayed during\n",
"optimization. We will set a few parameters as a demonstration.\n"
]
},
{
"cell_type": "code",
"execution_count": 8,
"id": "d3809dde",
"metadata": {},
"outputs": [],
"source": [
"parameters = gtsam.GaussNewtonParams()"
]
},
{
"cell_type": "markdown",
"id": "b0fce8d1",
"metadata": {},
"source": [
"Stop iterating once the change in error between steps is less than this value\n"
]
},
{
"cell_type": "code",
"execution_count": 9,
"id": "9e9547ae",
"metadata": {},
"outputs": [],
"source": [
"parameters.setRelativeErrorTol(1e-5)"
]
},
{
"cell_type": "markdown",
"id": "5d4ac412",
"metadata": {},
"source": [
"Do not perform more than N iteration steps\n"
]
},
{
"cell_type": "code",
"execution_count": 10,
"id": "fdc1e292",
"metadata": {},
"outputs": [],
"source": [
"parameters.setMaxIterations(100)"
]
},
{
"cell_type": "markdown",
"id": "cf526e65",
"metadata": {},
"source": [
"Create the optimizer ...\n"
]
},
{
"cell_type": "code",
"execution_count": 11,
"id": "b187bb8f",
"metadata": {},
"outputs": [],
"source": [
"optimizer = gtsam.GaussNewtonOptimizer(graph, initial_estimate, parameters)"
]
},
{
"cell_type": "markdown",
"id": "7f1188c3",
"metadata": {},
"source": [
"... and optimize\n"
]
},
{
"cell_type": "code",
"execution_count": 12,
"id": "5d848f88",
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Final Result:\n",
"Values with 5 values:\n",
"Value 1: (gtsam::Pose2)\n",
"(2.29376924e-21, -4.52805219e-20, -8.15716236e-21)\n",
"\n",
"Value 2: (gtsam::Pose2)\n",
"(2, -8.1719523e-20, -6.25198652e-21)\n",
"\n",
"Value 3: (gtsam::Pose2)\n",
"(4, -3.42174208e-11, 1.57079633)\n",
"\n",
"Value 4: (gtsam::Pose2)\n",
"(4, 2, 3.14159265)\n",
"\n",
"Value 5: (gtsam::Pose2)\n",
"(2, 2, -1.57079633)\n",
"\n",
"\n"
]
}
],
"source": [
"result = optimizer.optimize()\n",
"print(\"Final Result:\\n{}\".format(result))\n"
]
},
{
"cell_type": "markdown",
"id": "409145ce",
"metadata": {},
"source": [
"5. Calculate and print marginal covariances for all variables\n"
]
},
{
"cell_type": "code",
"execution_count": 14,
"id": "b2ca423f",
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"X1 covariance:\n",
"[[ 9.00000000e-02 5.29468059e-19 -1.56871840e-18]\n",
" [ 5.29468059e-19 9.00000000e-02 -6.39488462e-17]\n",
" [-1.56871840e-18 -6.39488462e-17 1.00000000e-02]]\n",
"\n",
"X2 covariance:\n",
"[[ 1.30000000e-01 -3.42668184e-18 -4.70156651e-18]\n",
" [-3.42668184e-18 1.70000000e-01 2.00000000e-02]\n",
" [-4.70156651e-18 2.00000000e-02 2.00000000e-02]]\n",
"\n",
"X3 covariance:\n",
"[[ 3.62000000e-01 -3.29295343e-12 6.20000000e-02]\n",
" [-3.29295409e-12 1.62000000e-01 -2.00000000e-03]\n",
" [ 6.20000000e-02 -2.00000000e-03 2.65000000e-02]]\n",
"\n",
"X4 covariance:\n",
"[[ 0.268 -0.128 0.048]\n",
" [-0.128 0.378 -0.068]\n",
" [ 0.048 -0.068 0.028]]\n",
"\n",
"X5 covariance:\n",
"[[ 0.202 0.036 -0.018 ]\n",
" [ 0.036 0.26 -0.051 ]\n",
" [-0.018 -0.051 0.0265]]\n",
"\n"
]
}
],
"source": [
"marginals = gtsam.Marginals(graph, result)\n",
"for i in range(1, 6):\n",
" print(\"X{} covariance:\\n{}\\n\".format(i, marginals.marginalCovariance(i)))"
]
},
{
"cell_type": "code",
"execution_count": 15,
"id": "c36b8f2d",
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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",
"text/plain": [
""
]
},
"metadata": {
"needs_background": "light"
},
"output_type": "display_data"
}
],
"source": [
"for i in range(1, 6):\n",
" gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5,\n",
" marginals.marginalCovariance(i))\n",
"\n",
"plt.axis('equal')\n",
"plt.show()"
]
}
],
"metadata": {
"interpreter": {
"hash": "eb6fa735d46fb17535ab2fae1363b5f0bf3cf0002d8c03a0f1f784c03cf9acc5"
},
"kernelspec": {
"display_name": "Python 3.8.12 ('nbdev')",
"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.8.12"
}
},
"nbformat": 4,
"nbformat_minor": 5
}