{ "cells": [ { "cell_type": "markdown", "metadata": { "colab_type": "text", "id": "view-in-github", "tags": [ "no-tex" ] }, "source": [ "\"Open" ] }, { "cell_type": "code", "execution_count": 1, "metadata": { "colab": { "base_uri": "https://localhost:8080/" }, "id": "w-CIikP0ZZnm", "outputId": "cef8a493-4d65-46ff-915e-fc59e6be77ef", "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 -q -U gtbook\n" ] }, { "cell_type": "code", "execution_count": 2, "metadata": { "id": "uef6Kglzcrha", "tags": [ "remove-cell" ] }, "outputs": [], "source": [ "import numpy as np\n", "\n", "import matplotlib.pyplot as plt\n", "from matplotlib.collections import PatchCollection\n", "from matplotlib.patches import Circle, Rectangle\n", "from matplotlib.transforms import Affine2D\n", "\n", "import gtsam\n", "from gtbook.display import show\n", "\n", "N = 5\n", "indices = range(1, N+1)\n", "u = {k:gtsam.symbol('u',k) for k in indices[:-1]} # controls u_k\n", "x = {k:gtsam.symbol('x',k) for k in indices} # states x_k\n" ] }, { "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ "# Moving in 2D\n", "\n", "> Omniwheels are a great way to move omni-directionally in 2D.\n", "\n", "\"Splash" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Omni Wheels\n", "> Omni wheels make omnidirectional movement possible.\n", "\n", "An [omni wheel](https://en.wikipedia.org/wiki/Omni_wheel) is a wheel that, instead of a tire, has small rollers along its rim. The axes for these rollers are perpendicular to the wheel's own axis. Because of this, unlike a conventional wheel, movement perpendicular to the wheel is *not* resisted, i.e., the wheel can slide effortlessly from left to right. The image below (from Wikipedia) shows an example:" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "\"Triple" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Apart from being potentially amazing for parallel parking, in robotics omni wheels are very popular because they enable omni-directional movement of robot platforms. " ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Example\n", "\n", "> A mobile robot with three omni wheels can move in any direction.\n", "\n", "As an example, let us imagine that our warehouse robot is circular and has three omni wheels mounted on its rim. The coordinates of each wheel, in body coordinates, are\n", "\n", "$$\n", "\\begin{aligned}\n", "p^i_x &= R \\cos(\\theta^i) \\\\\n", "p^i_y &= R \\sin(\\theta^i) \\\\\n", "\\theta^i &= i \\frac{2\\pi}{3}\n", "\\end{aligned}\n", "$$\n", "\n", "where $R$ is the radius of the robot. The angle $\\theta^i$ is angle between the robot's x-axis and the wheel's axis.\n", "As we will see below, this configuration of wheels allows the robot to move instantaneously in any direction in the plane.\n", "\n", "In code, we create a small function:" ] }, { "cell_type": "code", "execution_count": 3, "metadata": {}, "outputs": [], "source": [ "R = 0.50 # robot is circular with 50 cm radius\n", "r, w = 0.20, 0.06 # wheel radius and width\n", "num_wheels = 3\n", "\n", "def wheel_pose(i:int):\n", " \"\"\"Return x,y, and theta for wheel with given index.\"\"\"\n", " theta = float(i)*np.pi*2/num_wheels\n", " px, py = R*np.cos(theta), R*np.sin(theta)\n", " return px, py, theta\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "This yields the configuration below:" ] }, { "cell_type": "code", "execution_count": 4, "metadata": { "tags": [ "hide-input" ] }, "outputs": [ { "data": { "image/png": "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", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#| caption: Omni wheel configuration.\n", "#| label: fig:omni_wheel\n", "fig, ax = plt.subplots(figsize=(12,8))\n", "\n", "circle = Circle((0, 0), R, alpha=0.4)\n", "ax.add_artist(circle)\n", "\n", "wheels = []\n", "for i in range(3):\n", " px, py, theta = wheel_pose(i)\n", " wheel = Rectangle((-w/2, -r), w, 2*r)\n", " wheel.set_transform(Affine2D().rotate(theta).translate(px, py))\n", " wheels.append(wheel)\n", "\n", "ax.add_collection(PatchCollection(wheels))\n", "ax.axis('equal'); plt.show()\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Kinematics of Omni Wheels\n", "\n", "> Relating the robot velocity to the wheel velocities.\n", "\n", "Kinematics is the study of motion, without regard for the forces required to cause the motion.\n", "In particular, for our omni-directional robot kinematics addresses the question \"What should the individual wheel velocities be given that we want the robot to move with a certain velocity?\"\n", "\n", "The key property of omni-wheels is that they roll without slipping in the steering direction,\n", "but roll freely in the perpendicular direction (sometimes called the slipping direction).\n", "In the figure below, these directions correspond to the unit vectors $u_\\|$ (steering direction)\n", "and $u_\\perp$ (slipping direction).\n", "These vectors define an orthogonal decomposition of the robot's motion.\n", "The wheel actuators directly produce motion in the direction $u_\\|$,\n", "and the robot moves freely in the direction $u_\\perp$.\n", "\n", "
\n", "\"\"\n", "
Orthogonal coordinate frame for a single omni-wheel.
\n", "
\n", "\n", "The vectors $u_\\|$ and $u_\\perp$\n", "are defined in the local coordinate frame of the robot, but since our robot\n", "does not rotate, we can define them directly in the world coordinate frame.\n", "Let $\\theta$ denote the angle from the world $x$-axis to the axle axis of the wheel.\n", "The vectors $u_\\|$ and $u_\\perp$ are given by\n", "\n", "$$ u_\\| =\\left[ \\begin{array}{c} -\\sin \\theta \\\\ \\cos \\theta \\end{array}\\right]\n", "\\;\\;\\;\\;\\;\\;\\; \\rm{and} \\;\\;\\;\\;\\;\\;\\;\n", "u_\\perp =\\left[ \\begin{array}{c} \\cos \\theta \\\\ \\sin \\theta \\end{array}\\right]\n", "$$" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "When an object moves with a purely translational motion (i.e., there is no rotation), every point\n", "on the object moves with the same velocity.\n", "Suppose that the robot, and therefore this specific wheel,\n", "moves with the **translational velocity** $v=(v_x, v_y)$, as shown in the figure below. \n", "We can decompose the velocity $v$ into components that are parallel and perpendicular to the\n", "steering direction by projecting $v$ onto the vectors $u_\\|$ and $u_\\perp$.\n", "\n", "
\n", "\"\"\n", "
Wheel velocity v.
\n", "
\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "In particular, we can write\n", "\n", "$$\n", "\\begin{aligned}\n", "v &= (v \\cdot u_\\| )u_\\| + (v \\cdot u_\\perp) u_\\perp \\\\\n", "&=\n", "(- v_x \\sin \\theta + v_y \\cos \\theta) u_\\|\n", "+\n", "(v_x \\cos \\theta + v_y \\sin \\theta) u_\\perp \\\\\n", "&= v_{\\parallel}u_\\| + v_{\\perp}u_\\perp\\\\\n", "\\end{aligned}\n", "$$\n", "\n", "which gives\n", "\n", "$$\n", "\\begin{aligned}\n", "v^i_{\\parallel} &= - v_x \\sin \\theta^i + v_y \\cos \\theta^i \\\\\n", "v^i_{\\perp} &= v_x \\cos \\theta^i + v_y \\sin \\theta^i\n", "\\end{aligned}\n", "$$\n", "\n", "Note that in the above equation there is some possible confusion in the notation:\n", "$u_\\|$ and $u_\\perp$ are unit vectors that denote directions of motion,\n", "while $v_{\\parallel}$ and $v_{\\perp}$ are scalar quantities (the speed in the directions\n", "of the unit vectors $u_\\|$ and $u_\\perp$, respectively).\n", "\n", "In code:" ] }, { "cell_type": "code", "execution_count": 5, "metadata": {}, "outputs": [], "source": [ "def wheel_velocity(vx:float, vy:float, i:int):\n", " \"\"\"Calulate parallel and perpendicular velocities at wheel i\"\"\"\n", " _, _, theta = wheel_pose(i)\n", " para = - vx * np.sin(theta) + vy * np.cos(theta)\n", " perp = vx * np.cos(theta) + vy * np.sin(theta)\n", " return para, perp\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Below we use this to show how the desired velocity (in blue) translates graphically to parallel (purple) and perpendicular (green) velocity components at the wheel sites:" ] }, { "cell_type": "code", "execution_count": 6, "metadata": { "tags": [ "hide-input" ] }, "outputs": [ { "data": { "image/png": "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", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#| caption: Velocity decomposition for the omni wheels.\n", "#| label: fig:omni_wheel_velocity\n", "vx, vy = 0.3, 0.1 # change these !\n", "\n", "fig, ax = plt.subplots(figsize=(12,8))\n", "\n", "circle = Circle((0, 0), R, alpha=0.4)\n", "ax.add_artist(circle)\n", "\n", "wheels = []\n", "for i in range(3):\n", " px, py, theta = wheel_pose(i)\n", " wheel = Rectangle((-w/2, -r), w, 2*r)\n", " wheel.set_transform(Affine2D().rotate(theta).translate(px, py))\n", " wheels.append(wheel)\n", "ax.add_collection(PatchCollection(wheels))\n", "\n", "\n", "plt.arrow(0, 0, vx, vy, head_width=0.05, color=\"dodgerblue\")\n", "for i in range(3):\n", " px, py, theta = wheel_pose(i)\n", " para, perp = wheel_velocity(vx, vy, i)\n", " plt.arrow(px, py, vx, vy, head_width=0.05, color=\"dodgerblue\")\n", " plt.arrow(px, py, np.cos(theta)*perp, np.sin(theta)*perp, head_width=0.05, color=\"yellowgreen\")\n", " plt.arrow(px, py, -np.sin(theta)*para, np.cos(theta)*para, head_width=0.05, color=\"purple\")\n", "\n", "ax.axis('equal'); plt.show()\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## The Jacobian Matrix\n", "\n", "As mentioned above, the motion *perpendicular* to the wheel is not resisted by the rollers: they will roll freely\n", "at exactly the right speed to accommodate any movement in this direction. Because this allows the wheel to \"slide\", we also call this the **sliding direction**.\n", "\n", "On the other hand, the contact of each wheel must move exactly opposite to the parallel or **driving direction** of the velocity, because it cannot slide in that direction. As a consequence, if the radius of each wheel is $r$, the wheel's angular velocity $\\omega^i$ (i.e., the angular rate at which the wheel spins about its axle)\n", "must satisfy\n", "\n", "$$\n", "\\omega^i = \\frac{v^i_\\parallel}{r} = \n", "\\frac{1}{r} (-\\sin \\theta^i, \\cos \\theta^i) \\begin{pmatrix}v_x \\\\ v_y \\end{pmatrix}\n", "$$\n", "\n", "\n", "Because we have three wheels, we can stack three instances of the above equation\n", "to obtain a matrix equation\n", "that maps a desired robot velocity $v=(v_x,v_y)$ to the appropriate commanded wheel velocities:\n", "\n", "$$\n", "\\begin{pmatrix}\\omega^1 \\\\ \\omega^2 \\\\ \\omega^3 \\end{pmatrix} \n", "= \\frac{1}{r} \\begin{pmatrix}- \\sin\\theta^1 & \\cos\\theta^1 \\\\ - \\sin\\theta^2 & \\cos\\theta^2 \\\\ - \\sin\\theta^3 & \\cos\\theta^3 \\end{pmatrix}\n", "\\begin{pmatrix}v_x \\\\ v_y \\end{pmatrix}\n", "$$\n", "\n", "in which the $3\\times2$ matrix is called the **Jacobian matrix**.\n", "\n", "For the three regularly arranged omni wheels with $\\theta^1=0$, $\\theta^2=2\\pi/3$, and $\\theta^3=4\\pi/3$ this becomes\n", "\n", "$$\n", "\\begin{pmatrix}\\omega^1 \\\\ \\omega^2 \\\\ \\omega^3 \\end{pmatrix} \n", "= \\frac{1}{r} \\begin{pmatrix}0 & 1 \\\\ -0.866 & -0.5 \\\\ 0.866 & -0.5 \\end{pmatrix}\n", "\\begin{pmatrix}v_x \\\\ v_y \\end{pmatrix}.\n", "$$" ] }, { "cell_type": "code", "execution_count": 7, "metadata": {}, "outputs": [], "source": [ "def jacobian_matrix():\n", " \"\"\"Compute matrix converting from velocity to wheel velocities.\"\"\"\n", " rows = []\n", " for i in range(num_wheels):\n", " _, _, theta = wheel_pose(i)\n", " rows.append([-np.sin(theta), np.cos(theta)])\n", " return np.array(rows)/r\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "We can verify that doing the matrix-velocity multiplication yields the same result as using the `wheel_velocity` function:" ] }, { "cell_type": "code", "execution_count": 8, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "wheel 0: 0.5\n", "wheel 1: -1.549038105676658\n", "wheel 2: 1.0490381056766573\n", "\n", "Using matrix method:\n", "[ 0.5 -1.54903811 1.04903811]\n" ] } ], "source": [ "for i in range(3):\n", " para, perp = wheel_velocity(vx, vy, i)\n", " print(f\"wheel {i}: {para/r}\")\n", "\n", "print(\"\\nUsing matrix method:\")\n", "print(jacobian_matrix() @ gtsam.Point2(vx, vy))\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Omni-directional Movement in Practice" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "> Expressing motion relative to a reference coordinate frame.\n", "\n", "To summarize, given a velocity, $v$, in the robot's body coordinates,\n", "we compute the corresponding vector of angular wheel velocities using the Jacobian mapping, $\\omega = Jv$.\n", "The above exposition can be directly generalized to an arbitrary number of wheels, mounted in arbitrary locations. Some care needs to be taken that the chosen configuration is not singular, which would result in the robot being able to move only in one particular direction (or not at all!).\n", "\n", "In general, we would like to be able to specify the robot's direction of motion relative\n", "to arbitrary coordinate frames, e.g., to a fixed warehouse coordinate frame,\n", "or a *world coordinate frame*.\n", "In this chapter we have assumed that the robot orientation is aligned with the warehouse orientation, so conveniently velocity vectors in either frame have the same coordinates.\n", "However, if we were to include the robot's orientation in the state representation, we would need to rotate the desired world velocity into the body coordinate frame. We will see how to do this later in this book.\n", "\n", "If we *do* care about orientation, omni wheels can actually be used to *rotate* the robot as well as to induce pure translational motion. Think about applying the same constant angular velocity to all three wheels: the robot will now simply rotate in place. To represent this mathematically, we could add a *third* column to the Jacobian matrix that maps a desired angular velocity into wheel velocities. This would allow us to command any combination of linear and angular velocity to the robot.\n", "\n", "Finally, there is a more general type of wheel, the \"mecanum wheel\", for which the rollers are *not* aligned with the wheel rim, but are rotated by some (constant) amount. That complicates the math a little bit, but in the end we will again obtain a Jacobian matrix that maps robot velocity to wheel angular velocities. We will not discuss this further." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## A Gaussian Dynamic Bayes Net\n", "\n", "> Modeling stochastic action in continuous spaces can again be done using DBNs.\n", "\n", "Modeling with continuous densities can be done with *continuous* dynamic Bayes nets (DBNs). \n", "Omni wheels are notoriously flaky in the execution, especially on uneven ground or carpet.\n", "Hence, it is important to model the uncertainty associated with commanded movements.\n", "If we are model our robot as a discrete-time system,\n", "$u_k = v \\Delta T$ is the displacement that occurs when the robot\n", "moves with constant velocity $v$ for time $\\Delta T$.\n", "Since the velocity can be in any direction, we have $u_k\\in\\mathbb{R}^2$.\n", "In the absence of uncertainty, our motion model would simply\n", "be $x_{k+1} = x_k + u_k$." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "\n", "Given the uncertainty inherent to the use of omni-wheels, we will instead develop a probabilistic\n", "motion model.\n", "Recall that we created a DBN with discrete actions, states, and measurements in the previous chapter. Here we do the same, except with *continuous* densities, specifying a DBN that encodes the joint density $p(X|U)$ on the continuous states $X\\doteq\\{x_k\\}_{k=1}^N$,\n", "\n", "$$\n", "p(X|U) = p(x_1) \\prod_{k=2}^{N} p(x_{k}|x_{k-1}, u_{k-1})\n", "$$\n", "\n", "where we assume that the **control variables** $U\\doteq\\{u_k\\}_{k=1}^{N-1}$ are *given* to us." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Let us assume we *know* that the robot starts out in the warehouse at coordinates $\\mu_1 =(20,10)^T$, with some noise/error in position of magnitude on the order of plus or minus half a meter. We can encode this knowledge into a continuous Gaussian prior as\n", "\n", "$$p(x_1) = \\mathcal{N}(x_1;\\mu=\\mu_1,\\Sigma=P) \\propto \\exp\\{ - \\frac{1}{2} (x_1-\\mu_1)^TP^{-1}(x_1-\\mu_1) \\}$$\n", "\n", "with the covariance matrix $P=\\text{diag}(0.5^2,0.5^2)$." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "A Gaussian *motion model* is a bit trickier. \n", "Here we need a **conditional Gaussian density** that depends on the current state\n", "and the commanded motion.\n", "The usual way to incorporate uncertainty into a motion model is to assume that\n", "a random disturbance is added to the nominal motion of the robot.\n", "We can model this as\n", "\n", "$$x_{k+1} = x_k + u_k + w_k$$\n", "\n", "in which $w_k$ is a random vector whose probability distribution is typically based on empirical\n", "observations of the system. In our case, we will assume that this disturbance\n", "is Gaussian, $w_k \\sim N(\\mu,\\Sigma)$.\n", "In this case, it can be shown that the conditional distribution of $x_{k+1}$\n", "given $x_k$ and $u_k$ is given by a **conditional Gaussian density** of the form\n", "\n", "$$\n", "p(x_{k+1}|x_{k}, u_k) = \\mathcal{N}(x_{k_1}; x_{k} + u_k, \\Sigma)\n", "$$\n", "\n", "i.e., the conditional distribution for the next state is a Gaussian, with mean equal to the\n", "nominal (i.e., noise-free) next state $x_k + u_k$, and variance equal to the variance of the uncertainty \n", "in the motion model.\n", "\n", "It is easy to generalize this motion model to linear systems of the form\n", "\n", "$$\n", "x_{k+1} = A x_k + B u_k + w_k\n", "$$\n", "\n", "which is the general form for a linear time-invariant (LTI) system with additive noise.\n", "The matrix $A \\in \\mathbb{R}^{n \\times n}$ is called the system matrix,\n", "and the matrix $B$ maps control input $u_k$ to a vector in the state space.\n", "The motion model for this general LTI system is given by\n", "\n", "$$\n", "p(x_{k+1}|x_{k}, u_k) = \\mathcal{N}(x_{k+1};\\mu=A x_{k} + B u_k, \\Sigma=Q)\n", "$$\n", "\n", "where $Q$ is the traditional symbol used for motion model covariance. If we assume the robot executes action $u_k$ with a standard deviation of 0.2m, then we will have $Q=\\text{diag}(0.2^2,0.2^2)$. " ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Gaussian DBNs in Code\n" ] }, { "cell_type": "markdown", "metadata": { "slideshow": { "slide_type": "slide" } }, "source": [ "In GTSAM, a Gaussian density is specified using the class `GaussianDensity`, which corresponds to a negative log-probability given by \n", "\n", "$$\\frac{1}{2 \\sigma^2} \\|x - \\mu\\|^2.$$\n", "\n", "with a named constructor `FromMeanAndStddev` that takes $\\mu$ and $\\sigma$. For their part, Gaussian *conditional* densities are specified using the class `GaussianConditional`, which correspond to a negative log-probability given by \n", "\n", "$$\\frac{1}{2 \\sigma^2} \\|x - (A_1 p_1 + A_2 p_2 + b)\\|^2.$$\n", "\n", "i.e., the mean on $x$ is a linear function of the conditioning variables $p_1$ and $p_2$. Again, a named constructor `FromMeanAndStddev` is there to assist us. Details are given in the GTSAM 101 section at the end of this section, as always." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "All of the above is used in the following piece of code, which builds the dynamic Bayes net:" ] }, { "cell_type": "code", "execution_count": 9, "metadata": {}, "outputs": [], "source": [ "gaussianBayesNet = gtsam.GaussianBayesNet()\n", "A, B = np.eye(2), np.eye(2)\n", "motion_model_sigma = 0.2\n", "for k in reversed(indices[:-1]):\n", " gaussianBayesNet.push_back(gtsam.GaussianConditional.FromMeanAndStddev(\n", " x[k+1], A, x[k], B, u[k], [0, 0], motion_model_sigma))\n", "p_x1 = gtsam.GaussianDensity.FromMeanAndStddev(x[1], [20,10], 0.5)\n", "gaussianBayesNet.push_back(p_x1)\n" ] }, { "cell_type": "code", "execution_count": 10, "metadata": {}, "outputs": [ { "data": { "image/svg+xml": [ "\n", "\n", "\n", "\n", "\n", "\n", "\n", "\n", "\n", "var8430738502437568513\n", "\n", "u1\n", "\n", "\n", "\n", "var8646911284551352322\n", "\n", "x2\n", "\n", "\n", "\n", "var8430738502437568513->var8646911284551352322\n", "\n", "\n", "\n", "\n", "\n", "var8430738502437568514\n", "\n", "u2\n", "\n", "\n", "\n", "var8646911284551352323\n", "\n", "x3\n", "\n", "\n", "\n", "var8430738502437568514->var8646911284551352323\n", "\n", "\n", "\n", "\n", "\n", "var8430738502437568515\n", "\n", "u3\n", "\n", "\n", "\n", "var8646911284551352324\n", "\n", "x4\n", "\n", "\n", "\n", "var8430738502437568515->var8646911284551352324\n", "\n", "\n", "\n", "\n", "\n", "var8430738502437568516\n", "\n", "u4\n", "\n", "\n", "\n", "var8646911284551352325\n", "\n", "x5\n", "\n", "\n", "\n", "var8430738502437568516->var8646911284551352325\n", "\n", "\n", "\n", "\n", "\n", "var8646911284551352321\n", "\n", "x1\n", "\n", "\n", "\n", "var8646911284551352321->var8646911284551352322\n", "\n", "\n", "\n", "\n", "\n", "var8646911284551352322->var8646911284551352323\n", "\n", "\n", "\n", "\n", "\n", "var8646911284551352323->var8646911284551352324\n", "\n", "\n", "\n", "\n", "\n", "var8646911284551352324->var8646911284551352325\n", "\n", "\n", "\n", "\n", "\n" ], "text/plain": [ "" ] }, "execution_count": 10, "metadata": {}, "output_type": "execute_result" } ], "source": [ "#| caption: A Gaussian dynamic Bayes net.\n", "#| label: fig:gaussian_bayes_net\n", "position_hints = {'u': 2, 'x': 1}\n", "show(gaussianBayesNet, hints=position_hints, boxes=set(list(u.values())))\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Exercise\n", "\n", "Note that we used a constant motion model noise here, which is perhaps unrealistic: if a robot is commanded to go further, it could be expected to do a worse job at going exactly the distance it was supposed to go. How could you modify the above code to account for that?" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Simulating a Continuous Trajectory\n", "\n", "> Bayes nets are great for simulation.\n", "\n", "Let us now create a simulated trajectory in our example warehouse, by specifying a \"control tape\" and using the dynamic Bayes net created above to do the heavy lifting for us:" ] }, { "cell_type": "code", "execution_count": 11, "metadata": {}, "outputs": [ { "data": { "text/html": [ "
\n", "\n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", "
Variablevalue
u12 0
u22 0
u30 2
u40 2
\n", "
" ], "text/plain": [ "VectorValues: 4 elements\n", " u1: 2 0\n", " u2: 2 0\n", " u3: 0 2\n", " u4: 0 2" ] }, "execution_count": 11, "metadata": {}, "output_type": "execute_result" } ], "source": [ "control_tape = gtsam.VectorValues()\n", "for k, (ux,uy) in zip(indices[:-1], [(2,0), (2,0), (0,2), (0,2)]):\n", " control_tape.insert(u[k], gtsam.Point2(ux,uy))\n", "control_tape\n" ] }, { "cell_type": "code", "execution_count": 12, "metadata": {}, "outputs": [ { "data": { "text/html": [ "
\n", "\n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", " \n", "
Variablevalue
u12 0
u22 0
u30 2
u40 2
x120.6469 10.199
x222.8706 9.90054
x324.8089 10.1832
x425.1275 12.2733
x525.0941 14.5563
\n", "
" ], "text/plain": [ "VectorValues: 9 elements\n", " u1: 2 0\n", " u2: 2 0\n", " u3: 0 2\n", " u4: 0 2\n", " x1: 20.6469 10.199\n", " x2: 22.8706 9.90054\n", " x3: 24.8089 10.1832\n", " x4: 25.1275 12.2733\n", " x5: 25.0941 14.5563" ] }, "execution_count": 12, "metadata": {}, "output_type": "execute_result" } ], "source": [ "gaussianBayesNet.sample(control_tape)\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## GTSAM 101\n", "\n", "> The GTSAM concepts used in this section, explained." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "A `gtsam.GaussianDensity` class can be constructed via the following named constructor:\n", "\n", "```python\n", "FromMeanAndStddev(key: gtsam.Key, mean: np.array, sigma: float) -> gtsam.GaussianDensity\n", "```\n", "\n", "and a two similar named constructors exists for `gtsam.GaussianConditional`:\n", "\n", "```python\n", "- FromMeanAndStddev(key: gtsam.Key, A: np.array, parent: gtsam.Key, b: numpy.ndarray[numpy.float64[m, 1]], sigma: float) -> gtsam.GaussianConditional\n", " \n", "- FromMeanAndStddev(key: gtsam.Key, A1: np.array, parent1: gtsam.Key, A2: np.array, parent2: gtsam.Key, b: np.array, sigma: float) -> gtsam.GaussianConditional\n", "```\n", "\n", "Both classes support some other methods that can come in handy, as demonstrated here on the prior created above:" ] }, { "cell_type": "code", "execution_count": 13, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "GaussianDensity: density on [x1] \n", "mean: [20; 10];\n", "covariance: [\n", "\t0.25, 0;\n", "\t0, 0.25\n", "]\n", "isotropic dim=2 sigma=0.5\n", "\n", "unweighted error vector = [-1. 2.]\n", "weighted error vector = [-2. 4.]\n", "error 0.5 w'*w = 10.0\n" ] } ], "source": [ "print(p_x1) # printing\n", "\n", "values = gtsam.VectorValues()\n", "values.insert(x[1], [19,12])\n", "\n", "e = p_x1.unweighted_error(values)\n", "print(f\"unweighted error vector = {e}\")\n", "\n", "w = p_x1.error_vector(values)\n", "print(f\"weighted error vector = {w}\")\n", "\n", "E = p_x1.error(values)\n", "print(f\"error 0.5 w'*w = {E}\")\n", "assert E == 0.5 * w.dot(w) # check 10 == (4+16)/2\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "In the above, all error functions take an instance of `gtsam.VectorValues`, which is simply a map from GTSAM keys to values as vectors. This is the equivalent of `gtsam.DiscreteValues` from the previous sections." ] } ], "metadata": { "colab": { "include_colab_link": true, "name": "S42_logistics_actions.ipynb", "provenance": [] }, "kernelspec": { "display_name": "Python 3.8.12 ('gtbook')", "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.9.18" }, "latex_metadata": { "affiliation": "Georgia Institute of Technology", "author": "Frank Dellaert and Seth Hutchinson", "title": "Introduction to Robotics" }, "vscode": { "interpreter": { "hash": "9f7376ced4243bb13dfcffa8a3ba834e0602aa8334cd3a1d8ba8d285f4628083" } } }, "nbformat": 4, "nbformat_minor": 1 }