{
 "cells": [
  {
   "cell_type": "markdown",
   "id": "0e827775",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "# 2-link Pendulum\n",
    "This notebook walks you through every step to manually create a simple two-link pendulum multibody simulation. While the majority of the **kdFlex** software is in C++, Python bindings for the C++ classes are available as Python extensions. This example illustrates the use of the **kdFlex** Python extensions.\n",
    "\n",
    "In this tutorial we will:\n",
    "- Create the multibody\n",
    "- Setup the **kdFlex** Scene \n",
    "- Add visual geometries\n",
    "- Setup the state propagator\n",
    "- Attach models and callbacks\n",
    "- Set initial state\n",
    "- Register a timed event\n",
    "- Run the simulation\n",
    "- Clean up the simulation\n",
    "\n",
    "![](../resources/nb_images/two_link_pendulum_flipped.PNG)\n",
    "\n",
    "For a more in-depth descriptions of **kdflex** concepts see [usage](usage_page).\n",
    " "
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 1,
   "id": "b7e2551c",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [],
   "source": [
    "import numpy as np\n",
    "import atexit\n",
    "from typing import cast\n",
    "from math import pi\n",
    "import Karana.Core as kc\n",
    "import Karana.Math as km\n",
    "import Karana.Integrators as ki\n",
    "import Karana.Frame as kf\n",
    "import Karana.Dynamics as kd\n",
    "import Karana.Scene as ks\n",
    "import Karana.Models as kmdl\n",
    "from Karana.KUtils.Sim import Sim"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "0ef45212",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "## Create the Multibody\n",
    "\n",
    "Here, we create an instance of {py:class}`Karana.Sim.Sim`. This will internally create a {py:class}`Karana.Frame.FrameContainer` and {py:class}`Karana.Dynamics.Multibody`.\n",
    "\n",
    "In kdFlex, a {py:class}`Karana.Frame.Frame` is a fundamental concept that serves as a node in a directed tree of frames, forming the foundational layer for all objects in a simulation. The primary purpose of a frame is to track the pose, which includes both the location and orientation, of physical points of interest. You can read more about frames and the frame layer [here](frames_layer_sec).\n",
    "\n",
    "Frames are managed by a {py:class}`Karana.Frame.FrameContainer`.  We first create a root frame that will be an anchor for the rest of the frames in our system.\n",
    "\n",
    "A [multibody](treembody_sec) in kdFlex serves as the system-level container for all {py:class}`Karana.Dynamics.PhysicalBody` and their connections ({py:class}`Karana.Dynamics.PhysicalHinge`) in a simulation. Each multibody automatically includes a `virtual root`` that acts as an anchor for the other bodies in the system.\n",
    "- Physical bodies are extensions of frames with spatial properties like mass and inertia.\n",
    "- Each hinge is a container composed of {py:class}`Karana.Dynamics.PhysicalSubhinge`, which are the basic units of articulation (pin, linear, screw, etc.). These are analogous to joints in a body.\n",
    "\n",
    "Once the body is defined, we call {py:meth}`Karana.Core.LockingBase.ensureHealthy` to finalize setup, {py:meth}`Karana.Dynamics.SubTree.resetData` to set not ready (null/NaN) values to 0, and {py:func}`Karana.Core.allReady` to verify the multibody."
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 2,
   "id": "2c0408d3",
   "metadata": {},
   "outputs": [],
   "source": [
    "sim = Sim()"
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 3,
   "id": "a5b75454",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [],
   "source": [
    "def populateMbody(sim: Sim):\n",
    "    \"\"\"Populate the Multibody.\n",
    "\n",
    "    Parameters\n",
    "    ----------\n",
    "    sim : Sim\n",
    "        The Simulation whose Multibody will be populated.\n",
    "    \"\"\"\n",
    "    mb = sim.mb\n",
    "\n",
    "    # Let's add the first pendulum body. A rigid body consists of mass properties and its\n",
    "    # connection to other bodies. First we create the PhysicalBody itself.\n",
    "    bd1 = kd.PhysicalBody(\"bd1\", mb)\n",
    "\n",
    "    # Now, we add mass properties. These are added via the SpatialInertia, which takes\n",
    "    # the mass, center-of-mass offset, and 3x3 inertia matrix as arguments.\n",
    "    spI = km.SpatialInertia(2.0, np.zeros(3), np.diag([3, 2, 1]))\n",
    "    bd1.setSpatialInertia(spI)\n",
    "\n",
    "    # Now, let's connect this body to the rest of the world. We do this via a hinge.\n",
    "    # Below, we create a pin hinge. We set it's location relative to the body frame\n",
    "    # with the setBodyToJointTransform method. We also set the axis of the pin hinge.\n",
    "    bd1_hge = kd.PhysicalHinge(cast(kd.PhysicalBody, mb.virtualRoot()), bd1, kd.HingeType.REVOLUTE)\n",
    "    b2j = km.HomTran(np.array([0, 0, 0.5]))\n",
    "    bd1.setBodyToJointTransform(b2j)\n",
    "\n",
    "    bd1_subhge = cast(kd.PinSubhinge, bd1_hge.subhinge(0))\n",
    "    bd1_subhge.setUnitAxis(np.array([0, 1, 0]))\n",
    "\n",
    "    # Now, let's create another body similar to the first. This will be our second pendulum\n",
    "    # link.\n",
    "    bd2 = kd.PhysicalBody(\"bd2\", mb)\n",
    "    bd2.setSpatialInertia(spI)\n",
    "\n",
    "    bd2_hge = kd.PhysicalHinge(bd1, bd2, kd.HingeType.REVOLUTE)\n",
    "    b2j2 = km.HomTran(np.array([0, 0, 1]))\n",
    "    bd2.setBodyToJointTransform(b2j2)\n",
    "    ib2j = km.HomTran(np.array([0, 0, -0.5]))\n",
    "    bd2_hge.onode().setBodyToNodeTransform(ib2j)\n",
    "\n",
    "    bd2_subhge = cast(kd.PinSubhinge, bd2_hge.subhinge(0))\n",
    "    bd2_subhge.setUnitAxis(np.array([0, 1, 0]))\n",
    "\n",
    "    # Once all bodies are created, we make the Multibody healthy. This sets up internal\n",
    "    # variables for use in dynamics computations.\n",
    "    mb.ensureHealthy()\n",
    "\n",
    "    # Initially, our state uses not ready values.So we need to initialize our state.\n",
    "    # For now, we will just set all coordinates, gravity, etc to 0 with the use of the resetData helper\n",
    "    # method so we can do a readiness check.\n",
    "    mb.resetData()\n",
    "\n",
    "    # When creating a simulation, a common mistake is forgetting to initialize some values. These\n",
    "    # are particularly tricky to debug, as they don't trigger error messages or warnings. The\n",
    "    # allReady check can be used to check that all classes that derive from Base are ready.\n",
    "    # Nearly all classes in kdflex start out with known not ready values, e.g., NaN, and have\n",
    "    # an isReady method to check them. The allReady method loops over all of these and\n",
    "    # checks their state.\n",
    "    assert kc.allReady()"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "28b778b9",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "In this cell we create the multibody by calling the `createMbody` we defined in the previous cell. We also obtain the two pendulum bodies and assign them to variables"
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 4,
   "id": "d4a29bd7",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [],
   "source": [
    "# Initialization\n",
    "populateMbody(sim)\n",
    "\n",
    "# get the first body\n",
    "bd1 = cast(kd.PhysicalBody, sim.mb.getBody(\"bd1\"))\n",
    "\n",
    "# get the second body\n",
    "bd2 = cast(kd.PhysicalBody, sim.mb.getBody(\"bd2\"))"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "93b78eb2",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "## Setup the kdFlex Scene\n",
    "The [Scene Layer](scene_layer_sec) in kdFlex is responsible for working with the 3D geometries of bodies in our simulation. Here, we setup the [visualization](visualization_sec) of our scene by creating a graphics scene and a webserver to view it. In python, we use the helper method `setupGraphics` to take care of setting up the scene and webserver for us.\n",
    "\n",
    "`setupGraphics` returns 2 arguments: a cleanup function and a {py:class}`Karana.Scene.WebScene` that allows us to interface with the browser visualization. Using the returned webscene, we programmatically set the camera position and orientation."
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 5,
   "id": "9026806d",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [
    {
     "data": {
      "text/html": [
       "\n",
       "        <div style=\"height:300px; resize:vertical; overflow: auto;\">\n",
       "          <iframe src=\"http://newton:35429\" style=\"width:100%; height:100%; border:0; display:block;\"></iframe>\n",
       "        </div>\n",
       "        "
      ],
      "text/plain": [
       "<IPython.core.display.HTML object>"
      ]
     },
     "metadata": {},
     "output_type": "display_data"
    }
   ],
   "source": [
    "# call setupGraphics helper method\n",
    "_, web_scene = sim.setupGraphics(port=0, axes=0.5)\n",
    "\n",
    "# position the viewpoint camera of the visualization\n",
    "web_scene.defaultCamera().pointCameraAt([0.0, 5.0, -1.0], [0, 0, -1], [0, 0, 1])"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "0a96e95c",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "Our scene layer can have many client scenes, which are managed by a {py:class}`Karana.Scene.ProxyScene` that also acts as a bridge to our Frame layers. `setupGraphics` creates and attaches a ProxyScene to our Multibody behind the scenes, which we save to a variable now for convenience."
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 6,
   "id": "aeec108b",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [],
   "source": [
    "proxy_scene = sim.mb.getScene()"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "f7b114f7",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "## Add Visual Geometries\n",
    "\n",
    "We then add visual geometries to the pendulum bodies to make the simulation look nicer. These visual geometries do not affect the dynamics of the simulation and are purely for visual effect. To do this we attach {py:class}`Karana.Scene.ProxyScene`Part bodies to our ProxyScene. We then create primitive shapes and colored materials, which we add to the first and second bodies."
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 7,
   "id": "06e9a395",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [],
   "source": [
    "# create an box geometry for the first pendulum's root attachment\n",
    "box_geom = ks.BoxGeometry(0.25, 0.25, 0.25)\n",
    "\n",
    "# create an rectangle (box) geometry to be the pendulum arms\n",
    "body_geom = ks.BoxGeometry(0.05, 0.05, 1)\n",
    "\n",
    "# create a cylinder geometry to be used for the end of the pendulum\n",
    "cylinder_geom = ks.CylinderGeometry(0.1, 0.1)\n",
    "\n",
    "# create visual materials to color the bodies\n",
    "mat_info = ks.PhysicalMaterialInfo()\n",
    "mat_info.color = ks.Color.BLACK\n",
    "black = ks.PhysicalMaterial(mat_info)\n",
    "mat_info.color = ks.Color.FIREBRICK\n",
    "brown = ks.PhysicalMaterial(mat_info)\n",
    "mat_info.color = ks.Color.GOLD\n",
    "gold = ks.PhysicalMaterial(mat_info)\n",
    "\n",
    "# attach geometry to bodies\n",
    "bd1_body = ks.ProxyScenePart(\"bd1_body\", scene=proxy_scene, geometry=body_geom, material=brown)\n",
    "bd1_body.attachTo(bd1)\n",
    "\n",
    "bd1_pivot = ks.ProxyScenePart(\n",
    "    \"bd1_pivot\", scene=proxy_scene, geometry=cylinder_geom, material=brown\n",
    ")\n",
    "bd1_pivot.attachTo(bd1)\n",
    "bd1_pivot.setTranslation([0, 0, -0.5])\n",
    "\n",
    "bd2_body = ks.ProxyScenePart(\"bd2_body\", scene=proxy_scene, geometry=body_geom, material=brown)\n",
    "bd2_body.setTranslation([0, 0, 0.5])\n",
    "bd2_body.attachTo(bd2)\n",
    "\n",
    "bd2_end = ks.ProxyScenePart(\"bd2_end\", scene=proxy_scene, geometry=cylinder_geom, material=gold)\n",
    "bd2_end.attachTo(bd2)\n",
    "bd2_end.setTranslation([0, 0, 0])\n",
    "bd2_end.setScale(2.0)\n",
    "\n",
    "# create an unattached object for the top of the pendulum (implicitly attached to the root frame)\n",
    "root_scene_node = ks.ProxySceneNode(\"root_scene_node\", scene=proxy_scene)\n",
    "root_part = ks.ProxyScenePart(\"obstacle_part\", scene=proxy_scene, geometry=box_geom, material=black)\n",
    "\n",
    "# clean up unused variables\n",
    "del (\n",
    "    mat_info,\n",
    "    black,\n",
    "    brown,\n",
    "    gold,\n",
    "    bd1_body,\n",
    "    bd1_pivot,\n",
    "    bd2_body,\n",
    "    bd2_end,\n",
    "    box_geom,\n",
    "    cylinder_geom,\n",
    "    body_geom,\n",
    "    root_scene_node,\n",
    "    root_part,\n",
    ")"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "e2ffa804",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "# Setup the Integrator\n",
    "\n",
    "Oftentimes, a simulation consists of more than just dynamics. \n",
    "It may contain sensors, actuators, gravity, aerodynamics, etc. In general, we call these external interactions \"models\".\n",
    "The {py:class}`Karana.Dynamics.StatePropagator` provides a way to manage these models by registering and running them at the appropriate times during the Simulation.\n",
    "\n",
    "See [Models](system_level_models_sec) for more concepts and information.\n",
    "\n",
    "The {py:class}`Karana.KUtils.Sim.Sim` class also sets up a {py:class}`Karana.Dynamics.StatePropagator` for us and default integrator. Below, we modify that integrator to be RK4."
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 8,
   "id": "b9270355",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [],
   "source": [
    "# Change the integrator type to rk4\n",
    "sim.sp.setIntegrator(ki.IntegratorType.RK4)"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "ce60ba46",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "## Set Initial State\n",
    "\n",
    "Before we begin our simulation, we set the initial state for our multibody and statepropagator. \n",
    "\n",
    "When accessing or modifying [generalized coordinates](coords_sec) for a subhinge, it is recommended to directly set the subhinge's values rather than for the entire multibody in order to avoid ambiguity."
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 9,
   "id": "6fcdaf32",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [],
   "source": [
    "# Modify the initial multibody state.\n",
    "# Here we will set the first pendulum position to pi/4 radians and its velocity to 0.0\n",
    "bd1.parentHinge().subhinge(0).setQ(pi / 4)\n",
    "bd1.parentHinge().subhinge(0).setU(0.0)\n",
    "\n",
    "# Initialize state. Note that in kdflex there are two states, one for multibody and one for integrator.\n",
    "# Here we get the multibody state vector we updated above and then feed it to the integrator.\n",
    "sim.sp.hardReset()\n",
    "t_init = np.timedelta64(0, \"ns\")\n",
    "x_init = sim.sp.assembleState()\n",
    "sim.sp.setTime(t_init)\n",
    "sim.sp.setState(x_init)\n",
    "sim.sp.ensureHealthy()\n",
    "\n",
    "# Syncs graphics\n",
    "proxy_scene.update()"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "b2339c78",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "## Register Models\n",
    "\n",
    "To simulate a model, you can either use a {py:class}`Karana.Dynamics.KModel` or directly attach a callback function to {py:meth}`Karana.Dynamics.StatePropagator.SpFunctions`.\n",
    "\n",
    "Here, we demonstrate using a KModel. You can implement this class yourself or use provided models like {py:class}`Karana.Models.Gravity`, {py:class}`Karana.Models.UpdateProxyScene`, and {py:class}`Karana.Models.SyncRealTime`. Gravity must be set via a model rather than calling {py:meth}`Karana.Dynamics.Multibody.setUniformGravAccel` once since forces are zero-ed out between derivative calls."
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 10,
   "id": "e5671002",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [],
   "source": [
    "# Create a UniformGravity model, and set it's gravitational acceleration.\n",
    "# This model contains a preDeriv method that will set the multibody's gravitational\n",
    "# acceleration appropriately before each derivative call.\n",
    "ug = kmdl.Gravity(\"grav_model\", sim.sp, kmdl.UniformGravity(\"uniform_gravity\"), sim.mb)\n",
    "ug.getGravityInterface().setGravity(np.array([0, 0, -9.81]), 0.0, kmdl.OutputUpdateType.PRE_HOP)\n",
    "del ug\n",
    "\n",
    "# typically the simulation runs as fast as possible, which is hard to visualize\n",
    "# so we can use a SyncRealTime model to synchronize the simulation speed with real time.\n",
    "sync_rt = kmdl.SyncRealTime(\"sync_real_time\", sim.sp, 1.0)\n",
    "del sync_rt"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "f0e7de52",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "## Register a Timed Event\n",
    "\n",
    "To set the length of each simulation step, we create a timed event and register it to our state propagator here. Here, we set its period to 0.1 seconds, which means our UniformGravity, UpdateProxyScene, and SyncRealTime models are also triggered every 0.1 seconds. See [timed events](timed_events_sec) for more information."
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 11,
   "id": "1e1498e0",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [],
   "source": [
    "integrator = sim.sp.getIntegrator()\n",
    "\n",
    "\n",
    "def fn(t):\n",
    "    \"\"\"Print out the time and state.\n",
    "\n",
    "    Parameters\n",
    "    ----------\n",
    "    t : float\n",
    "        The current time.\n",
    "    \"\"\"\n",
    "    print(f\"t = {float(integrator.getTime()) / 1e9}s; x = {integrator.getX()}\")\n",
    "\n",
    "\n",
    "h = np.timedelta64(int(1e8), \"ns\")\n",
    "t = kd.TimedEvent(\"hop_size\", h, fn, False)\n",
    "t.period = h\n",
    "\n",
    "# register the timed event\n",
    "sim.sp.registerTimedEvent(t)\n",
    "del t"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "06e5af80",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "## Run the Simulation\n",
    "\n",
    "Now, run the simulation for 10 seconds."
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 12,
   "id": "f92e5b77",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [
    {
     "name": "stdout",
     "output_type": "stream",
     "text": [
      "t = 0.0s; x = [0.78539816 0.         0.         0.        ]\n",
      "t = 0.1s; x = [ 0.76566551  0.01227844 -0.39290407  0.2433583 ]\n",
      "t = 0.2s; x = [ 0.70752486  0.04776757 -0.76448294  0.45937449]\n",
      "t = 0.3s; x = [ 0.61426291  0.1021731  -1.09122509  0.61593417]\n",
      "t = 0.4s; x = [ 0.4916302   0.16776013 -1.34771743  0.67723754]\n",
      "t = 0.5s; x = [ 0.34786321  0.23339845 -1.51055492  0.61330071]\n",
      "t = 0.6s; x = [ 0.19318611  0.28582313 -1.56437937  0.4134401 ]\n",
      "t = 0.7s; x = [ 0.03873567  0.31205453 -1.50690816  0.09458845]\n",
      "t = 0.8s; x = [-0.10488321  0.30215441 -1.35119386 -0.30036288]\n",
      "t = 0.9s; x = [-0.22912493  0.25142619 -1.12498943 -0.71120207]\n",
      "t = 1.0s; x = [-0.32879004  0.16159124 -0.86631057 -1.07187795]\n",
      "t = 1.1s; x = [-0.40260795  0.0406797  -0.61368587 -1.32500497]\n",
      "t = 1.2s; x = [-0.4526259  -0.09871819 -0.39285307 -1.43954542]\n",
      "t = 1.3s; x = [-0.48241717 -0.24276363 -0.20816994 -1.42192279]\n",
      "t = 1.4s; x = [-0.49505914 -0.37983805 -0.04717697 -1.30689499]\n",
      "t = 1.5s; x = [-0.49211685 -0.50221276  0.1055822  -1.13347916]\n",
      "t = 1.6s; x = [-0.47395383 -0.60542956  0.25752346 -0.92615807]\n",
      "t = 1.7s; x = [-0.44075037 -0.68651519  0.40492174 -0.69038419]\n",
      "t = 1.8s; x = [-0.3935423  -0.74227355  0.53492008 -0.41741037]\n",
      "t = 1.9s; x = [-0.3349576  -0.76824332  0.62919127 -0.09199839]\n",
      "t = 2.0s; x = [-0.26955472 -0.75844362  0.6682549   0.29969942]\n",
      "t = 2.1s; x = [-0.20366818 -0.70591411  0.63721559  0.76195388]\n",
      "t = 2.2s; x = [-0.14455396 -0.60416481  0.53422551  1.27898084]\n",
      "t = 2.3s; x = [-0.09851732 -0.44992877  0.38225298  1.79895139]\n",
      "t = 2.4s; x = [-0.06783426 -0.24774197  0.23965912  2.21584788]\n",
      "t = 2.5s; x = [-0.04747814 -0.01512943  0.18832901  2.38512086]\n",
      "t = 2.6s; x = [-0.02539768  0.21793931  0.27497437  2.22322947]\n",
      "t = 2.7s; x = [0.01094937 0.42046559 0.46165413 1.79494129]\n",
      "t = 2.8s; x = [0.06747453 0.57283789 0.66514139 1.24316919]\n",
      "t = 2.9s; x = [0.14228333 0.66890406 0.8193984  0.68336579]\n",
      "t = 3.0s; x = [0.22864104 0.71141954 0.89359505 0.17914214]\n",
      "t = 3.1s; x = [ 0.31817574  0.70751925  0.88384087 -0.24261638]\n",
      "t = 3.2s; x = [ 0.4029682   0.66584522  0.80128117 -0.57665245]\n",
      "t = 3.3s; x = [ 0.47656252  0.59491327  0.66276181 -0.82936327]\n",
      "t = 3.4s; x = [ 0.53420211  0.50233767  0.48462532 -1.01122431]\n",
      "t = 3.5s; x = [ 0.57257808  0.39475724  0.27905083 -1.13029309]\n",
      "t = 3.6s; x = [ 0.58931512  0.27833935  0.05243518 -1.18737735]\n",
      "t = 3.7s; x = [ 0.58240516  0.15960437 -0.19392512 -1.17485367]\n",
      "t = 3.8s; x = [ 0.54985365  0.04609424 -0.46021614 -1.08114561]\n",
      "t = 3.9s; x = [ 0.48981674 -0.05367644 -0.7422232  -0.9000989 ]\n",
      "t = 4.0s; x = [ 0.4013204  -0.13126031 -1.02620075 -0.64043574]\n",
      "t = 4.1s; x = [ 0.28530354 -0.18003065 -1.28792263 -0.32994276]\n",
      "t = 4.2s; x = [ 0.1454991  -0.19700412 -1.49673544 -0.012714  ]\n",
      "t = 4.3s; x = [-0.01126525 -0.18408271 -1.6226746   0.25947666]\n",
      "t = 4.4s; x = [-0.17551891 -0.14819771 -1.64398809  0.44018299]\n",
      "t = 4.5s; x = [-0.33627766 -0.10005889 -1.55281143  0.50230293]\n",
      "t = 4.6s; x = [-0.48255899 -0.05173705 -1.35690243  0.44612043]\n",
      "t = 4.7s; x = [-0.60481524 -0.01401666 -1.07627665  0.29549213]\n",
      "t = 4.8s; x = [-0.69583641  0.00535715 -0.73652262  0.08503495]\n",
      "t = 4.9s; x = [-0.75098827  0.00210928 -0.3628387  -0.15189707]\n",
      "t = 5.0s; x = [-0.76801804 -0.02498042  0.02244076 -0.38759865]\n",
      "t = 5.1s; x = [-0.74678993 -0.07454631  0.39899475 -0.59726173]\n",
      "t = 5.2s; x = [-0.68919252 -0.14266965  0.74631769 -0.75393239]\n",
      "t = 5.3s; x = [-0.59923468 -0.22252688  1.04249439 -0.82667971]\n",
      "t = 5.4s; x = [-0.48314629 -0.30417432  1.2654361  -0.78536384]\n",
      "t = 5.5s; x = [-0.34923978 -0.37509849  1.39621148 -0.61045743]\n",
      "t = 5.6s; x = [-0.20740372 -0.42175725  1.42283002 -0.30200098]\n",
      "t = 5.7s; x = [-0.06822974 -0.43176718  1.34383753  0.11670328]\n",
      "t = 5.8s; x = [ 0.05823831 -0.39622215  1.17232622  0.59968965]\n",
      "t = 5.9s; x = [ 0.1641496  -0.31186614  0.93936487  1.08038904]\n",
      "t = 6.0s; x = [ 0.24563101 -0.18295009  0.69235267  1.47685119]\n",
      "t = 6.1s; x = [ 0.30387058 -0.02200721  0.48173466  1.71016542]\n",
      "t = 6.2s; x = [0.34422046 0.15222286 0.33619021 1.74163558]\n",
      "t = 6.3s; x = [0.37302037 0.32041615 0.24645074 1.59879531]\n",
      "t = 6.4s; x = [0.3942477  0.46851097 0.17877884 1.35199956]\n",
      "t = 6.5s; x = [0.40845807 0.58958111 0.10231924 1.0669449 ]\n",
      "t = 6.6s; x = [0.4139398  0.68187745 0.0034855  0.77996149]\n",
      "t = 6.7s; x = [ 0.40849691  0.74580735 -0.11456662  0.49916143]\n",
      "t = 6.8s; x = [ 0.39084982  0.78159287 -0.23765005  0.21447141]\n",
      "t = 6.9s; x = [ 0.36145626  0.78795666 -0.34602247 -0.0925396 ]\n",
      "t = 7.0s; x = [ 0.32283263  0.76171012 -0.41901289 -0.44034739]\n",
      "t = 7.1s; x = [ 0.27940414  0.69815055 -0.44009291 -0.83929105]\n",
      "t = 7.2s; x = [ 0.23675426  0.59236371 -0.40406805 -1.28121146]\n",
      "t = 7.3s; x = [ 0.20000272  0.44178209 -0.3272378  -1.72451065]\n",
      "t = 7.4s; x = [ 0.17113888  0.25036811 -0.25657655 -2.07883052]\n",
      "t = 7.5s; x = [ 0.14615387  0.03325267 -0.26046085 -2.2187104 ]\n",
      "t = 7.6s; x = [ 0.11499404 -0.18329711 -0.38169243 -2.06380435]\n",
      "t = 7.7s; x = [ 0.06670038 -0.37089796 -0.59343998 -1.65574811]\n",
      "t = 7.8s; x = [-0.00430109 -0.51001364 -0.82343288 -1.11491278]\n",
      "t = 7.9s; x = [-0.09637788 -0.59322429 -1.00647135 -0.55284546]\n",
      "t = 8.0s; x = [-0.20278086 -0.62232312 -1.1063671  -0.04151055]\n",
      "t = 8.1s; x = [-0.31450582 -0.60455483 -1.11281676  0.38014768]\n",
      "t = 8.2s; x = [-0.42240454 -0.54986983 -1.03161183  0.69545447]\n",
      "t = 8.3s; x = [-0.5183339  -0.46909847 -0.87584982  0.90245324]\n",
      "t = 8.4s; x = [-0.59557614 -0.37276507 -0.66027652  1.00840458]\n",
      "t = 8.5s; x = [-0.64885128 -0.27040066 -0.39866406  1.0252103 ]\n",
      "t = 8.6s; x = [-0.67417731 -0.17027737 -0.1032151   0.96561266]\n",
      "t = 8.7s; x = [-0.66873634 -0.07945524  0.21480137  0.84092999]\n",
      "t = 8.8s; x = [-0.63085403 -0.00393025  0.54344998  0.6614458 ]\n",
      "t = 8.9s; x = [-0.56017512  0.05140568  0.8679123   0.43967649]\n",
      "t = 9.0s; x = [-0.4580531   0.08321975  1.16863829  0.19501264]\n",
      "t = 9.1s; x = [-0.32804707  0.09060614  1.42128165 -0.04322866]\n",
      "t = 9.2s; x = [-0.17628596  0.07603581  1.59952167 -0.23771066]\n",
      "t = 9.3s; x = [-0.01140046  0.04577477  1.68074317 -0.35181729]\n",
      "t = 9.4s; x = [ 0.15618747  0.00916699  1.65273202 -0.36270781]\n",
      "t = 9.5s; x = [ 0.31555156 -0.02328788  1.51790813 -0.27088779]\n",
      "t = 9.6s; x = [ 0.45671791 -0.0423044   1.29226831 -0.09895818]\n",
      "t = 9.7s; x = [ 0.57176484 -0.04152374  0.99975026  0.11928474]\n",
      "t = 9.8s; x = [ 0.65528269 -0.01800637  0.66572564  0.35083831]\n",
      "t = 9.9s; x = [0.70428461 0.02820962 0.31287207 0.569533  ]\n",
      "t = 10.0s; x = [ 0.71786758  0.09479957 -0.03973915  0.75528156]\n"
     ]
    }
   ],
   "source": [
    "# print the initial state\n",
    "print(f\"t = {float(integrator.getTime()) / 1e9}s; x = {integrator.getX()}\")\n",
    "\n",
    "# run the simulation\n",
    "sim.sp.advanceTo(10.0)\n",
    "\n",
    "# dump the state propagator info\n",
    "sim.sp.dump(\"sp\")"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "a4d77758",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "## Clean Up the Simulation\n",
    "\n",
    "Below, we cleanup our simulation. We first delete local variables to remove lingering connections to objects we want to call discard on. Failing to do this will result in a `use count` error. We then call `cleanup_graphics`, a callback function returned from `setupGraphics` that cleans up our scene layer and webserver. This just leaves {py:func}`Karana.Core.discard` to cleanup any remaining Karana objects. Finally while not required, you can call {py:func}`Karana.Core.allDestroyed` to verify that everything is destroyed."
   ]
  },
  {
   "cell_type": "code",
   "execution_count": 13,
   "id": "efb64e64",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "outputs": [
    {
     "data": {
      "text/plain": [
       "<function __main__.cleanup()>"
      ]
     },
     "execution_count": 13,
     "metadata": {},
     "output_type": "execute_result"
    }
   ],
   "source": [
    "# Cleanup\n",
    "def cleanup():\n",
    "    \"\"\"Cleanup the simulation.\"\"\"\n",
    "    global integrator, proxy_scene, web_scene, bd1, bd2, sim\n",
    "    del integrator, proxy_scene, web_scene, bd1, bd2, sim\n",
    "\n",
    "\n",
    "atexit.register(cleanup)"
   ]
  },
  {
   "cell_type": "markdown",
   "id": "5411c95c",
   "metadata": {
    "jupyter": {
     "outputs_hidden": false
    }
   },
   "source": [
    "## Summary\n",
    "Congratulations! You now understand all the fundamentals of setting up a kdFlex simulation. We covered creating a multibody, setting up a scene environment, adding visual geometries, creating a state propagator, initializing state, adding models, registering timed events, running the simulation, and cleanup. \n",
    "\n",
    "## Further Readings\n",
    "[Procedurally generate a n-link pendulum](../example_n_link_pendulum/notebook.ipynb)  \n",
    "[Simulate collisions with a 2-link pendulum](../example_pendulum_collision/notebook.ipynb)  \n",
    "[Import and export multibodies](../example_import_export/notebook.ipynb)  \n",
    "[Log data to a H5 file](../example_data_logging/notebook.ipynb)  \n",
    "[Save visualizations to PNG files](../example_visualization/notebook.ipynb)  \n",
    "[Model planetary bodies using spice frames](../example_spice_frames/notebook.ipynb)"
   ]
  }
 ],
 "metadata": {
  "kernelspec": {
   "display_name": "Python 3 (ipykernel)",
   "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.3"
  },
  "name": "notebook.ipynb"
 },
 "nbformat": 4,
 "nbformat_minor": 5
}
