diff --git a/.gitignore b/.gitignore index b1cb160..1237a90 100644 --- a/.gitignore +++ b/.gitignore @@ -1,7 +1,9 @@ +*Tutorial_1_Pinocchio # Byte-compiled / optimized / DLL files __pycache__/ *.py[cod] *$py.class +*.zip # C extensions *.so diff --git a/0_introduction_to_numerical_robotics.ipynb b/0_introduction_to_numerical_robotics.ipynb index 8f0c5d6..f7dbcdd 100644 --- a/0_introduction_to_numerical_robotics.ipynb +++ b/0_introduction_to_numerical_robotics.ipynb @@ -11,9 +11,17 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "NB: as for all the tutorials, a magic command %do_not_load is introduced to hide the solutions to some questions. Change it for %load if you want to see (and execute) the solution.\n" + ] + } + ], "source": [ "import magic_donotload" ] @@ -29,7 +37,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ @@ -52,7 +60,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 4, "metadata": {}, "outputs": [], "source": [ @@ -68,23 +76,23 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "You can open the visualizer by visiting the following URL:\n", + "http://127.0.0.1:7003/static/\n" + ] + } + ], "source": [ "viz = MeshcatVisualizer(robot)\n", "viz.display(robot.q0)" ] }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "hasattr(viz.viewer, 'jupyter_cell') and viz.viewer.jupyter_cell()" - ] - }, { "cell_type": "markdown", "metadata": {}, @@ -94,7 +102,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 25, "metadata": {}, "outputs": [], "source": [ @@ -110,7 +118,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 26, "metadata": {}, "outputs": [], "source": [ @@ -142,7 +150,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 27, "metadata": {}, "outputs": [], "source": [ @@ -161,7 +169,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 28, "metadata": {}, "outputs": [], "source": [ @@ -187,29 +195,13 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 29, "metadata": {}, "outputs": [], "source": [ "def dist(q):\n", " '''Return the distance between the end effector end the target (2d).'''\n", - " return 0.\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Solution" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp0/generated/simple_path_planning_dist" + " return norm(endef(q)-target.position)\n" ] }, { @@ -222,34 +214,24 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 30, "metadata": {}, "outputs": [], "source": [ "def qrand(check=False):\n", - " '''Return a random configuration. If `check` is True, this configuration is not is collision.'''\n", - " pass" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The solution if needed:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp0/generated/simple_path_planning_qrand" + " '''\n", + " Return a random configuration. If check is True, this\n", + " configuration is not is collision\n", + " '''\n", + " while True:\n", + " q = np.random.rand(2)*6.4-3.2 # sample between -3.2 and +3.2.\n", + " if not check or not coll(q):\n", + " return q" ] }, { "cell_type": "code", - "execution_count": null, + "execution_count": 73, "metadata": {}, "outputs": [], "source": [ @@ -273,20 +255,23 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 94, "metadata": {}, "outputs": [], "source": [ "# Random descent: crawling from one free configuration to the target with random\n", "# steps.\n", "def randomDescent(q0 = None):\n", - " '''\n", - " Make a random walk of 0.1 step toward target\n", - " Return the list of configurations visited\n", - " '''\n", " q = qrand(check=True) if q0 is None else q0\n", " hist = [ q.copy() ]\n", - " # DO the walk\n", + " for i in range(100):\n", + " dq = qrand()*.1 # Choose a random step ...\n", + " qtry = q+dq # ... apply\n", + " if dist(q)>dist(q+dq) and not coll(q+dq): # If distance decrease without collision ...\n", + " q = q+dq # ... keep the step\n", + " hist.append(q.copy()) # ... keep a trace of it\n", + " viz.display(q) # ... display it\n", + " time.sleep(5e-2) # ... and sleep for a short while\n", " return hist" ] }, @@ -308,18 +293,34 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp0/generated/simple_path_planning_random_descent" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 99, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "[array([-1.9901098 , -0.88158628]),\n", + " array([-1.86961804, -0.94539836]),\n", + " array([-1.66687348, -1.21144783]),\n", + " array([-1.54102748, -1.37886033]),\n", + " array([-1.51664155, -1.47802967]),\n", + " array([-1.42867921, -1.52481326]),\n", + " array([-1.34918062, -1.82031051]),\n", + " array([-1.22681096, -1.89091155]),\n", + " array([-1.1269922 , -2.17161378]),\n", + " array([-1.02462327, -2.3027111 ]),\n", + " array([-0.93736221, -2.41341269]),\n", + " array([-0.93087496, -2.34533513]),\n", + " array([-0.87556467, -2.55022467]),\n", + " array([-0.89866193, -2.28751962]),\n", + " array([-0.87462912, -2.37970058])]" + ] + }, + "execution_count": 99, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "randomDescent()" ] @@ -334,7 +335,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 16, "metadata": {}, "outputs": [], "source": [ @@ -356,7 +357,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 18, "metadata": {}, "outputs": [], "source": [ @@ -396,9 +397,20 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 19, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "hcol,hfree = sampleSpace(5000)\n", "plotConfigurationSpace(hcol,hfree)\n" @@ -414,35 +426,57 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "traj = np.array([])\n", - "qinit = np.array([-1.1, -3. ])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here is a solution:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp0/generated/simple_path_planning_traj" + "execution_count": 20, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "We found a good traj!\n" + ] + } + ], + "source": [ + "qinit = np.array([-1.1, -3. ])\n", + "for i in range(100):\n", + " traj = randomDescent(qinit)\n", + " if dist(traj[-1])<5e-2:\n", + " print('We found a good traj!')\n", + " break\n", + "traj = np.array(traj)\n", + "### Chose trajectory end to be in [-pi,pi]\n", + "qend = (traj[-1]+np.pi) % (2*np.pi) - np.pi\n", + "### Take the entire trajectory it modulo 2 pi\n", + "traj += (qend-traj[-1])" ] }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 21, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "[]" + ] + }, + "execution_count": 21, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "# Add yourr traj to the plot, be carefull !\n", "plotConfigurationSpace(hcol,hfree)\n", @@ -468,7 +502,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 22, "metadata": {}, "outputs": [], "source": [ @@ -477,15 +511,22 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 23, "metadata": {}, "outputs": [], "source": [ "def cost(q):\n", - " pass\n", + " \"\"\"\n", + " Cost function: distance to the target.\n", + " \"\"\"\n", + " return dist(q) ** 2\n", " \n", "def constraint(q):\n", - " pass\n", + " \"\"\"\n", + " Constraint function: distance to the obstacle should be strictly positive.\n", + " \"\"\"\n", + " min_collision_dist = 0.01 # [m]\n", + " return collisionDistance(q) - min_collision_dist\n", " \n", "def callback(q):\n", " '''\n", @@ -497,25 +538,12 @@ "def optimize():\n", " '''\n", " Optimize from an initial random configuration to discover a collision-free\n", - " configuration as close as possible to the target.\n", - " USE fmin_slsqp, see doc online\n", - " '''" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here is a valid solution:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp0/generated/simple_path_planning_optim" + " configuration as close as possible to the target. \n", + " '''\n", + " return fmin_slsqp(x0=qrand(check=True),\n", + " func=cost,\n", + " f_ieqcons=constraint,callback=callback,\n", + " full_output=1)" ] }, { @@ -534,28 +562,46 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# Your solution" + "execution_count": 24, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Optimization terminated successfully (Exit mode 0)\n", + " Current function value: 1.886924840184197e-07\n", + " Iterations: 6\n", + " Function evaluations: 18\n", + " Gradient evaluations: 6\n", + "Finally successful!\n" + ] + } + ], + "source": [ + "while True:\n", + " res=optimize()\n", + " q=res[0]\n", + " viz.display(q)\n", + " if res[4]=='Optimization terminated successfully' and res[1]<1e-6:\n", + " print('Finally successful!')\n", + " break\n", + " print(\"Failed ... let's try again! \")" ] }, { - "cell_type": "markdown", + "cell_type": "code", + "execution_count": null, "metadata": {}, - "source": [ - "And the solution if you need it:" - ] + "outputs": [], + "source": [] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], - "source": [ - "%do_not_load tp0/generated/simple_path_planning_useit" - ] + "source": [] } ], "metadata": { @@ -574,7 +620,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.10.13" + "version": "3.10.14" } }, "nbformat": 4, diff --git a/1_forward_geom.ipynb b/1_forward_geom.ipynb deleted file mode 100644 index 1835b2c..0000000 --- a/1_forward_geom.ipynb +++ /dev/null @@ -1,899 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Direct and inverse geometry of 2d robots" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "This notebook the main concept of kinematic tree, direct geometry and inverse geometry, but without the kinematic tree of Pinocchio. We only use the basic geometries of the our 3d viewer for displaying the simple robot that is used in this tutorial." - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "NB: as for all the tutorials, a magic command %do_not_load is introduced to hide the solutions to some questions. Change it for %load if you want to see (and execute) the solution.\n" - ] - } - ], - "source": [ - "import magic_donotload" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Set up\n", - "We will need NumPy, SciPy, and MeshCat Viewer for vizualizing the robot.\n", - "Scipy is a collection of scientific tools for Python. It contains, in particular, a set of optimizers that we are going to use for solving the inverse-geometry problem." - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "import time\n", - "import numpy as np\n", - "from scipy.optimize import fmin_bfgs,fmin_slsqp\n", - "from utils.meshcat_viewer_wrapper import MeshcatVisualizer,translation2d,planar\n", - "from numpy.linalg import norm,inv,pinv,svd,eig\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "\n", - "## Displaying objects\n", - "Let's first learn how to open a 3D viewer, in which we will build our simulator. We will use the viewer MeshCat which directly displays in a browser. Open it as follows:" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "You can open the visualizer by visiting the following URL:\n", - "http://127.0.0.1:7000/static/\n" - ] - }, - { - "data": { - "text/html": [ - "\n", - "
\n", - " \n", - "
\n", - " " - ], - "text/plain": [ - "" - ] - }, - "execution_count": 3, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "viz = MeshcatVisualizer()\n", - "viz.viewer.jupyter_cell()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The following object is a client of the viewer, i.e. it will be use to pass display command to the viewer. The first commands are to create objects:" - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [], - "source": [ - "ballID = 'world/ball'; viz.addSphere(ballID,.2,[1,0,0,1])\n", - "cylID = 'world/cyl'; viz.addCylinder(cylID,length=1,radius=.1,color=[0,0,1,1])\n", - "boxID = 'world/box'; viz.addBox(boxID,[.5,.2,.4],[1,1,0,1])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "\n", - "You can re-set objects under the same name, which will simply replace your object by another one. If you want to erase your world and all your objects, just run:\n" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [], - "source": [ - "viz.delete(ballID)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Placing objects can be done using the set_transform command, and specifying a displacement as list of 7 values." - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [], - "source": [ - "viz.applyConfiguration(cylID,[.1,.2,.3,1,0,0,0])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "In a first time, we will work in 2D. Here is a shortcut to place an object from x,y,theta 2d placement, so-called *planar*. An example of a shorter positioning of a 2D object using this shortcut is:" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [], - "source": [ - "viz.applyConfiguration(boxID,planar(0.1, 0.2, np.pi / 3))\n", - "viz.applyConfiguration(cylID,planar(0.1, 0.2, 5*np.pi / 6))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Creating a 2 dof robot\n", - "This robot will have:\n", - "- 2 rotating joints (that are spheres), named shoulder and elbow\n", - "- With 2 links of length 1 (that are cylinders) to connect them\n", - "- A fixed joint (also a sphere) at the output of the last link.\n", - "\n", - "First, let's first remove the previous objects and create the 5 geometry objects for the robot (plus one for the target)." - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "metadata": {}, - "outputs": [], - "source": [ - "viz.delete(ballID)\n", - "viz.delete(cylID)\n", - "viz.delete(boxID)" - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": {}, - "outputs": [], - "source": [ - "viz.addSphere('joint1',.1,[1,0,0,1])\n", - "viz.addSphere('joint2',.1,[1,0,0,1])\n", - "viz.addSphere('joint3',.1,[1,0,0,1])\n", - "viz.addCylinder('arm1',.75,.05,[.65,.65,.65,1])\n", - "viz.addCylinder('arm2',.75,.05,[.65,.65,.65,1])\n", - "viz.addSphere('target',.05,[0,.8,.1,1])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The frame attach to each link is position in the barycenter of the object." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Given a configuration vector q of dimension 2 compute the position of the centers of each object, and display correctly the robot.\n", - "\n", - "First compute a random configuration vector, each variable is in $[-\\pi,\\pi]$:" - ] - }, - { - "cell_type": "code", - "execution_count": 10, - "metadata": {}, - "outputs": [], - "source": [ - "q = np.random.rand(2) * 2 * np.pi - np.pi" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Use geometry with the right frame to compute the placement of all link given the configuration. In other words: code the forward kinematic." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![Schema](media/FK.png)" - ] - }, - { - "cell_type": "code", - "execution_count": 11, - "metadata": {}, - "outputs": [], - "source": [ - "def display(q):\n", - " '''Display the robot in Gepetto Viewer. '''\n", - " assert (q.shape == (2,))\n", - " t0 = q[0]\n", - " t1 = q[1]\n", - " # viz.applyConfiguration('name',planar(x, y, t))\n", - " viz.applyConfiguration('joint1',planar(0, 0, 0))\n", - " viz.applyConfiguration('arm1' ,planar(0, 0, 0))\n", - " viz.applyConfiguration('joint2',planar(0, 0, 0))\n", - " viz.applyConfiguration('arm2' ,planar(0, 0, 0))\n", - " viz.applyConfiguration('joint3',planar(0, 0, 0))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "And here is the solution if you need it." - ] - }, - { - "cell_type": "code", - "execution_count": 14, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp1/generated/configuration_reduced_display" - ] - }, - { - "cell_type": "code", - "execution_count": 15, - "metadata": {}, - "outputs": [], - "source": [ - "display(q) # Display the robot in the viewer" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The end effector (located in the center of the last sphere) is already computed in the previous method. Let's build a dedicated method to return the same value. Write a function `endeffector(q)`, which takes the 2 joints values and returns the 2d position of the robot end effector." - ] - }, - { - "cell_type": "code", - "execution_count": 16, - "metadata": {}, - "outputs": [], - "source": [ - "def endeffector(q):\n", - " x,y = 0,0 # Fill me\n", - " return np.array([x,y])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Below is the solution, should you need it." - ] - }, - { - "cell_type": "code", - "execution_count": 19, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp1/generated/configuration_reduced_endeffector" - ] - }, - { - "cell_type": "code", - "execution_count": 20, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([-1.5549768, -0.4896798])" - ] - }, - "execution_count": 20, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "endeffector(q)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "From now, we will try to (pseudo) invert the function *endeffector*, by seeking for a configuration *q* such that the end effector reaches a given position. You can first try to reach the position (0.5;0.5) either by trial-and-error, or by manually inverting the function (in the case of such a simple robot, inverting is easy)." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "\n", - "## Optimize the configuration " - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Optimization will be done with the BFGS solver of scipy, which simply takes an intial guess and a cost function. Here the cost will be the squared distance to a given target." - ] - }, - { - "cell_type": "code", - "execution_count": 21, - "metadata": {}, - "outputs": [], - "source": [ - "target = np.array([.5, .5])\n", - "viz.applyConfiguration('target',translation2d(target[0],target[1]))\n", - " \n", - "def cost(q):\n", - " eff = endeffector(q)\n", - " return norm(eff - target)**2\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "In SciPy, BFGS also accepts a callback function, that we will use to display in the viewer the current value of the decision variable." - ] - }, - { - "cell_type": "code", - "execution_count": 22, - "metadata": {}, - "outputs": [], - "source": [ - "def callback(q):\n", - " display(q)\n", - " time.sleep(.5)\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "And that is it, let's call BFGS. Use Scipy documentation if needed" - ] - }, - { - "cell_type": "code", - "execution_count": 23, - "metadata": {}, - "outputs": [], - "source": [ - "# Your code" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "And the solution if needed" - ] - }, - { - "cell_type": "code", - "execution_count": 26, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp1/generated/configuration_reduced_optim" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## What configuration to optimize?\n", - "It seems logical to optimize over the angles $q_1,q_2$.\n", - "However, other representations of the configuration are possible. Consider for example the explicit representation, where the placement of each body of interest are stored. For example, the 3 sphere of our robot. We get $x,y,\\theta$, for each one, so 9 parameters in total. In addition, each body position and orientation can be subject to constraints. In our case, the second and third sphere position are constrained by the position and orientation of the previous sphere. In addition, the orientation of the last sphere is fixed by the one of the previous sphere. There are 7 constraints in total. And recover $9-7=2$ degrees of freedom.\n", - "\n", - "What are the pros and cons of this representation ?\n", - "- (+) The end effector position is now a trivial function of the representation, hence the cost function is very simple.\n", - "- (-) The number of variables is higher\n", - "- (-) The trade-off is that we have to explicitly satisfy the constraints. \n", - "\n", - "Let's start by defining the configuration." - ] - }, - { - "cell_type": "code", - "execution_count": 27, - "metadata": {}, - "outputs": [], - "source": [ - "x1, y1, th1, x2, y2, th2, x3, y3, th3 = q0 = np.zeros(9)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![Schema2](media/FK.png)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### From configuration to cartesian positions\n", - "An advantage of the extended configuration is that the mapping from configuration to cartesian positions is typically much more straightforward. For example, the end-effector position is now ... just the last part of the configuration vector:" - ] - }, - { - "cell_type": "code", - "execution_count": 28, - "metadata": {}, - "outputs": [], - "source": [ - "def endeffector_9(ps):\n", - " assert (ps.shape == (9, ))\n", - " x1, y1, t1, x2, y2, t2, x3, y3, t3 = ps\n", - " return np.array([x3, y3])\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We can similarly redefined the display function, where each body is directly placed depending on the corresponding part of the configuration." - ] - }, - { - "cell_type": "code", - "execution_count": 29, - "metadata": {}, - "outputs": [], - "source": [ - "def display_9(q):\n", - " '''Display the robot in Gepetto Viewer. '''\n", - " assert (ps.shape == (9, ))\n", - " x1, y1, t1, x2, y2, t2, x3, y3, t3 = ps\n", - " viz.applyConfiguration('joint1',planar(0, 0, 0))\n", - " viz.applyConfiguration('arm1' ,planar(0, 0, 0))\n", - " viz.applyConfiguration('joint2',planar(0, 0, 0))\n", - " viz.applyConfiguration('arm2' ,planar(0, 0, 0))\n", - " viz.applyConfiguration('joint3',planar(0, 0, 0))\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here is the solution, should you need it:" - ] - }, - { - "cell_type": "code", - "execution_count": 34, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp1/generated/configuration_extended_display" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "If defining a task to reach a target, like in the previous section, the cost function is also immediate to write." - ] - }, - { - "cell_type": "code", - "execution_count": 35, - "metadata": {}, - "outputs": [], - "source": [ - "def cost_9(ps):\n", - " eff = endeffector_9(ps)\n", - " return norm(eff - target)**2\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Working under constraints" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "But, now, a random configuration vector is likely not a valid one. Let's try: sample a random vector and display it! The result is not satisfactory." - ] - }, - { - "cell_type": "code", - "execution_count": 36, - "metadata": {}, - "outputs": [], - "source": [ - "qrand9 = np.random.rand(9)\n", - "display_9(qrand9)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Any vector $q$ needs to respect a set of algebraic constraints so that it properly reprents a proper robot configuration. Let's write that function explicitely, as a map from the configuration space to a vactor of values, which should be 0 to respect the constraints. Here we have 7 constraints. So write a constraint function taking q in input and output a 7d vector that we want to see nullified." - ] - }, - { - "cell_type": "code", - "execution_count": 37, - "metadata": {}, - "outputs": [], - "source": [ - "def constraint_9(q):\n", - " constraints = np.zeros(7) # Fill me\n", - " return constraints" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "As usual, here is the solution, should you need it." - ] - }, - { - "cell_type": "code", - "execution_count": 48, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp1/generated/configuration_extended_constraint" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "For example, the configuration with the 9-vector set to 0 is not satisfying the constraints." - ] - }, - { - "cell_type": "code", - "execution_count": 49, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "0.5000000000000001 [0. 0. 1. 0. 1. 0. 0.]\n" - ] - } - ], - "source": [ - "print(cost_9(q0), constraint_9(q0))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We also introduce a callback function which displays the candidate configuration in the viewer." - ] - }, - { - "cell_type": "code", - "execution_count": 50, - "metadata": {}, - "outputs": [], - "source": [ - "def callback_9(ps):\n", - " display_9(ps)\n", - " time.sleep(.5)\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Solve with a penalty cost\n", - "The BFGS solver defined above cannot be used directly to optimize over equality constraints. A dirty trick is to add the constraint as a penalty, i.e. a high-weigth term in the cost function: $penalty(x) = cost(x) + 10*||constraint(x)||^2$ . Here, we are in a good case where the optimum corresponds to the 0 of both the constraint and the cost. The penalty with any weight would lead to the optimum and perfect constraint satisfaction. Yet the solver suffers to reach the optimum, because of the way we have described the constraint." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Define a new function *penalty*, corresponding to the previous cost function plus a huge weight multiplying the (squared) norm of the constraint." - ] - }, - { - "cell_type": "code", - "execution_count": 51, - "metadata": {}, - "outputs": [], - "source": [ - "def penalty(ps):\n", - " return 0.\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "And the solution:" - ] - }, - { - "cell_type": "code", - "execution_count": 56, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp1/generated/configuration_extended_penalty" - ] - }, - { - "cell_type": "code", - "execution_count": 57, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Optimization terminated successfully.\n", - " Current function value: 0.000000\n", - " Iterations: 35\n", - " Function evaluations: 430\n", - " Gradient evaluations: 43\n" - ] - } - ], - "source": [ - "qopt = fmin_bfgs(penalty, q0, callback=callback_9)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Solve with a constrained solver\n", - "Alternatively, the solver S-LS-QP (sequential least-square quadratic-program) optimizes over equality constraints." - ] - }, - { - "cell_type": "code", - "execution_count": 58, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - " NIT FC OBJFUN GNORM\n", - " 1 11 2.250000E+00 1.414214E+00\n", - " 2 21 1.937259E+00 3.000000E+00\n", - " 3 31 2.001991E+00 2.783709E+00\n", - " 4 42 1.871897E+00 2.719952E+00\n", - " 5 53 1.764294E+00 2.672066E+00\n", - " 6 64 2.678464E+00 2.633901E+00\n", - " 7 75 9.962758E+01 2.615277E+00\n", - " 8 87 1.565139E+00 2.598603E+00\n", - " 9 97 2.044343E+00 2.502111E+00\n", - " 10 108 1.572166E+00 2.465374E+00\n", - " 11 119 1.407605E+00 2.410660E+00\n", - " 12 130 1.256751E+00 2.341692E+00\n", - " 13 140 1.151781E+00 2.242099E+00\n", - " 14 150 7.797116E-01 2.146422E+00\n", - " 15 160 2.007960E-01 1.766026E+00\n", - " 16 170 9.012763E+00 8.962054E-01\n", - " 17 181 7.270016E-02 4.670489E-01\n", - " 18 191 4.785649E-02 5.392593E-01\n", - " 19 201 1.604073E-02 4.375225E-01\n", - " 20 212 6.385112E-03 2.711592E-01\n", - " 21 222 2.517331E-03 1.598138E-01\n", - " 22 232 1.977869E-04 1.003460E-01\n", - " 23 242 5.278316E-06 2.812737E-02\n", - " 24 252 1.829150E-08 4.594934E-03\n", - " 25 262 1.113548E-10 2.704871E-04\n", - "Optimization terminated successfully (Exit mode 0)\n", - " Current function value: 1.1135482465804356e-10\n", - " Iterations: 25\n", - " Function evaluations: 262\n", - " Gradient evaluations: 25\n" - ] - } - ], - "source": [ - "qopt = fmin_slsqp(cost_9, q0, callback=callback_9, f_eqcons=constraint_9, iprint=2, full_output=1)[0]" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "When properly defining the constraint, the solver converges quickly. It is difficult to say a-priori whether it is better to optimize with the q (and consequently a dense cost and no constraint) or with the x-y-theta (and consequently a sparse cost and constraints). Here, we empirically observe no significant difference. " - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Modeling complex kinematics" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "A side effect of working with extended configurations is that more complex constraints can also be taken into account by the same way. This is particularly useful to model close-kinematic chains, that we will investigate in more details in the next notebook. " - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here is an example of a complex kinematics: the human foremarm is composed of two main bonex, wich enable sophisticated wrist rotations." - ] - }, - { - "attachments": { - "image.png": { - "image/png": "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" - } - }, - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![image.png](attachment:image.png)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "From https://musculoskeletalkey.com/elbow-10/" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Proper mechanical models of this bones and joints involve close-kinematic constraints, see for example the explicit schema below." - ] - }, - { - "attachments": { - "image.png": { - "image/png": "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" - } - }, - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![image.png](attachment:image.png)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "From (Laitenberger, M., Raison, M., Périé, D., & Begon, M. (2015). Refinement of the upper limb joint kinematics and dynamics using a subject-specific closed-loop forearm model. Multibody System Dynamics, 33(4), 413-438)." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "This can be seen as a more sophisticated version of the classical *parallelogram* structure, which enables stiff linkages of light R2 robots, has depicted below:" - ] - }, - { - "attachments": { - "image.png": { - "image/png": "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" - } - }, - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![image.png](attachment:image.png)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "This robot has 4 moving links, with 4 joints, enabling a total of 2 degrees of freedom. It can be reprented with an extended configuration of dimension 12 (x,y,theta of each center of rotation). " - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "**Implement the display and constraint functions, allow to optimize and visualize the search for a configuration where the end-effector of the R2 robot reaches an arbitrary 2d target.**" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "You can view it as two double pendulum and add a constraint or verify the geometric properties we have !" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "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.9.18" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/2_inv_geom.ipynb b/2_inv_geom.ipynb index 1453237..6461a40 100644 --- a/2_inv_geom.ipynb +++ b/2_inv_geom.ipynb @@ -782,7 +782,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.9.18" + "version": "3.10.14" } }, "nbformat": 4, diff --git a/3_invkine.ipynb b/3_invkine.ipynb index b7dd8ba..34559bb 100644 --- a/3_invkine.ipynb +++ b/3_invkine.ipynb @@ -10,7 +10,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 2, "metadata": {}, "outputs": [], "source": [ @@ -27,7 +27,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ @@ -49,30 +49,23 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "You can open the visualizer by visiting the following URL:\n", + "http://127.0.0.1:7005/static/\n" + ] + } + ], "source": [ "robot = loadTiago()\n", "viz = MeshcatVisualizer(robot)" ] }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Click on the link above to open the viewer in a separate window, or execute the following cell to embed the viewer here:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "viz.viewer.jupyter_cell()" - ] - }, { "cell_type": "markdown", "metadata": {}, @@ -103,7 +96,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 6, "metadata": {}, "outputs": [], "source": [ @@ -122,7 +115,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 7, "metadata": {}, "outputs": [], "source": [ @@ -150,7 +143,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 8, "metadata": {}, "outputs": [], "source": [ @@ -160,9 +153,33 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "Frame name: frametool paired to (parent joint/ previous frame)(9/52)\n", + "with relative placement wrt parent joint:\n", + " R =\n", + "1 0 0\n", + "0 1 0\n", + "0 0 1\n", + " p = 0 0 0.08\n", + "containing inertia:\n", + " m = 0\n", + " c = 0 0 0\n", + " I = \n", + "0 0 0\n", + "0 0 0\n", + "0 0 0" + ] + }, + "execution_count": 9, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "robot.model.frames[IDX_TOOL]" ] @@ -185,9 +202,28 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 10, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Tool placement: R =\n", + "-0.359761 -0.8039 -0.473621\n", + " 0.895704 -0.439726 0.0659926\n", + "-0.261315 -0.400483 0.878253\n", + " p = -0.654046 1.44758 0.486462\n", + "\n", + "Basis placement: R =\n", + "0.0921162 -0.995748 0\n", + " 0.995748 0.0921162 0\n", + " 0 0 1\n", + " p = -0.417443 1.59017 0.15\n", + "\n" + ] + } + ], "source": [ "pin.framesForwardKinematics(robot.model, robot.data, q)\n", "\n", @@ -239,9 +275,20 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 11, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "(6, 15)" + ] + }, + "execution_count": 11, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "Jtool = pin.computeFrameJacobian(robot.model, robot.data, q, IDX_TOOL)\n", "Jtool.shape" @@ -256,7 +303,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 12, "metadata": {}, "outputs": [], "source": [ @@ -273,7 +320,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 13, "metadata": {}, "outputs": [], "source": [ @@ -289,7 +336,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 14, "metadata": {}, "outputs": [], "source": [ @@ -306,7 +353,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 15, "metadata": {}, "outputs": [], "source": [ @@ -323,7 +370,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 16, "metadata": {}, "outputs": [], "source": [ @@ -403,9 +450,24 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 17, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Full Jacobian in the tool frame:\n", + "With a Jac: [-1.02883837 0.04516153 -0.20577555 0.23029874 -0.45619144 0.24750407]\n", + "With a log: [-1.02884838 0.04517495 -0.2057577 0.23033352 -0.45626052 0.24745734]\n", + "\n", + "Origin velocity in the world frame:\n", + "With a Jac: [ 0.43129056 -0.95497341 0.07004114]\n", + "With a log: [ 0.43127492 -0.95498711 0.07005405]\n", + "With fdiff: [ 0.43129263 -0.95498036 0.07003697]\n" + ] + } + ], "source": [ "# Sample between -0.001 and 0.001\n", "EPS = 1e-4\n", @@ -464,9 +526,20 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 18, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "With spatial Jacobian: [ 0.71742713 -0.65159933 -0.44800695 0.16665653 0.42321206 0.33988756]\n", + "With adjoint * body Jacobian: [ 0.71742714 -0.65159933 -0.44800696 0.16665653 0.42321206 0.33988756]\n", + "o_Jtool3 from body Jacobian: [ 0.43132598 -0.95495992 0.07000696]\n", + "Local-world-aligned Jacobian: [ 0.43129056 -0.95497341 0.07004114]\n" + ] + } + ], "source": [ "# 0_w_tool and tool_w_tool\n", "tool_Jtool = pin.computeFrameJacobian(robot.model,robot.data,q,IDX_TOOL, pin.LOCAL)\n", @@ -498,7 +571,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 19, "metadata": {}, "outputs": [], "source": [ @@ -529,7 +602,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 20, "metadata": {}, "outputs": [], "source": [ @@ -548,41 +621,38 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 22, "metadata": {}, "outputs": [], "source": [ "q = q0.copy()\n", "herr = [] # Log the value of the error between tool and goal.\n", + "# Loop on an inverse kinematics for 200 iterations.\n", + "for i in range(200): # Integrate over 2 second of robot life\n", "\n", - "for i in range(500): # Integrate over 2 second of robot life\n", + " # Run the algorithms that outputs values in robot.data\n", + " pin.framesForwardKinematics(robot.model,robot.data,q)\n", + " pin.computeJointJacobians(robot.model,robot.data,q)\n", + "\n", + " # Placement from world frame o to frame f oMtool\n", + " oMtool = robot.data.oMf[IDX_TOOL]\n", + "\n", + " # 3D jacobian in world frame\n", + " o_Jtool3 = pin.computeFrameJacobian(robot.model,robot.data,q,IDX_TOOL,pin.LOCAL_WORLD_ALIGNED)[:3,:]\n", + "\n", + " # vector from tool to goal, in world frame\n", + " o_TG = oMtool.translation-oMgoal.translation\n", " \n", - " # REPLACE WITH YOUR CODE\n", - " o_TG = np.zeros(3) \n", - " q = q0 \n", + " # Control law by least square\n", + " vq = -pinv(o_Jtool3)@o_TG\n", "\n", + " q = pin.integrate(robot.model,q, vq * DT)\n", " viz.display(q)\n", " time.sleep(1e-3)\n", "\n", " herr.append(o_TG) \n" ] }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "And the solution if you need it" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp3/generated/inverse_kinematics_3d_loop" - ] - }, { "cell_type": "markdown", "metadata": {}, @@ -592,9 +662,20 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 23, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "plt.plot(herr)\n", "plt.xlabel('control cycle (iter)')\n", @@ -624,7 +705,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 24, "metadata": {}, "outputs": [], "source": [ @@ -650,27 +731,35 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# Your code" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "And the solution:" - ] - }, - { - "cell_type": "code", - "execution_count": null, + "execution_count": 27, "metadata": {}, "outputs": [], "source": [ - "%do_not_load tp3/generated/inverse_kinematics_6d_loop" + "q = q0.copy()\n", + "herr = []\n", + "for i in range(200): # Integrate over 2 second of robot life\n", + "\n", + " # Run the algorithms that outputs values in robot.data\n", + " pin.framesForwardKinematics(robot.model,robot.data,q)\n", + " pin.computeJointJacobians(robot.model,robot.data,q)\n", + "\n", + " # Placement from world frame o to frame f oMtool \n", + " oMtool = robot.data.oMf[IDX_TOOL]\n", + "\n", + " # 6D error between the two frame\n", + " tool_nu = pin.log(oMtool.inverse()*oMgoal).vector\n", + "\n", + " # Get corresponding jacobian\n", + " tool_Jtool = pin.computeFrameJacobian(robot.model, robot.data, q, IDX_TOOL)\n", + "\n", + " # Control law by least square\n", + " vq = pinv(tool_Jtool)@tool_nu\n", + "\n", + " q = pin.integrate(robot.model,q, vq * DT)\n", + " viz.display(q)\n", + " time.sleep(1e-3)\n", + "\n", + " herr.append(tool_nu)" ] }, { @@ -683,9 +772,30 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 28, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "Text(0, 0.5, 'error (rad)')" + ] + }, + "execution_count": 28, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAjcAAAGwCAYAAABVdURTAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjguNCwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8fJSN1AAAACXBIWXMAAA9hAAAPYQGoP6dpAACHf0lEQVR4nO3deXwU5eE/8M9e2d3c931zE+6AGBHkqFFEAbEtWOtdLK330SK1XrUWf9pa2yqKF4ontV5Y+Iqg3IflSDgChCshd0LuY5M9n98fs7vZTTYhCUk2u/m8X695zewzxz7DZJ2PzzwzIxNCCBARERF5Cbm7K0BERETUmxhuiIiIyKsw3BAREZFXYbghIiIir8JwQ0RERF6F4YaIiIi8CsMNEREReRWluyvQ3ywWC0pKShAQEACZTObu6hAREVEXCCHQ0NCA2NhYyOWdt80MunBTUlKChIQEd1eDiIiIeqCwsBDx8fGdLjPowk1AQAAA6R8nMDDQzbUhIiKirqivr0dCQoL9PN6ZQRdubJeiAgMDGW6IiIg8TFe6lLBDMREREXkVhhsiIiLyKgw3RERE5FUYbnrR+rPrkVeX5+5qEBERDWqDrkNxXylsKMQze56BEAI/H/FzLBu/DCGaEHdXi4iIaNBhy00vuiL2CpiECR+f/BjzvpiHNcfWQG/Wu7taREREg4pMCCHcXYn+VF9fj6CgINTV1fXJreD7Svfhbwf+hpPVJwEAcf5xeGjSQ7gm+Ro+EZmIiKiHunP+ZrjpA2aLGd+c+wb/OvQvVDRXAADGhY/D76b8DhMiJ/TJdxIREXkzhptO9Ee4sdEZdVh7fC3ePfYumk3NAICrk67Gw5MeRkIgXwFBRETUVQw3nejPcGNzQXcBr2W/hi/PfAmLsEApV+IXI3+Be8bdgyB1UL/UgYiIyJMx3HTCHeHG5lTNKfztwN+wp2QPACDQJxBLxy7FkpFLoFFq+rUuREREnoThphPuDDc2u4t3468H/ooztWcAAJG+kfjt+N9iwdAFUMp5dz4REVFbDDedGAjhBmjtdLwqexVKm0oBAMmBybhv4n24OulqyGW8S5+IiMiG4aYTAyXc2BjMBvw7999488ibqNHXAABGh43Gg5MeREZMBm8fJyIiAsNNpwZauLFpMjZhbc5avJfzHnQmHQBgavRUPDjpQYyNGOvm2hEREbkXw00nBmq4saluqcZbR97Cutx1MFqMAIA5iXPwwMQHkBqc6ubaERERuQfDTScGerixKWkswarsVfjm3DewCAvkMjmuT70evx73ayQGJrq7ekRERP2K4aYTnhJubM7WnsW/sv6F7wu+BwAoZArcMOQG3DPuHiQE8EGAREQ0ODDcdMLTwo3NscpjWJW9CjuLdwIAlDIl5g+dj3vG3YM4/zg3146IiKhvMdx0wlPDjc2RC0ewKnsVdpfsBiCFnAVDF+Cecfcg1j/WzbUjIiLqGww3nfD0cGOTXZGNVdmrsLd0LwBAKVdi0dBFWDpuKaL9ot1cOyIiot7FcNMJbwk3NofKD2HV4VX4sfRHAIBKrsKiYYvwq7G/YsghIiKvwXDTCW8LNzYHyg5g1eFV2F+2H4AUchYMXYC7xtzFjsdEROTxGG464a3hxmZ/2X6syl6FA+UHAEh3V81NmYtfjf0VhgQPcXPtiIiIeobhphPeHm5sDpUfwptH38Tu4t32sp8k/gRLxy3F6LDRbqwZERFR9zHcdGKwhBubnKocvH3kbWwp2GIvmxY3DfeMvQeToia5sWZERERd153zt9tfPb1q1SqkpKRAo9EgPT0dO3fu7NJ6u3fvhlKpxIQJE/q2gh4uLSwNf5/1d3y14Ctcn3o9FDIFdhfvxu3f3o47vr0De4r3YJDlWyIi8nJubblZt24dbr31VqxatQrTpk3D6tWr8fbbb+P48eNITOz4FQN1dXWYNGkShg4divLycmRnZ3f5Owdby01bhQ2FePfYu/j6zNf2d1elhaXhzjF34ieJP4FCrnBzDYmIiNrzmMtSU6dOxaRJk/D666/by0aNGoWFCxdi5cqVHa63ZMkSDBs2DAqFAl999VWn4Uav10Ov19s/19fXIyEhYdCGG5vypnK8l/Me/nPqP2gxtwAA4v3jcVvabVg4dCG0Sq2ba0hERNTKIy5LGQwGHDx4EJmZmU7lmZmZ2LNnT4frrVmzBmfPnsXTTz/dpe9ZuXIlgoKC7ENCAm+LBoAovygsv2w5Nv10E5aNX4ZgdTCKGovwlx//gsz/ZOK17NdQ3VLt7moSERF1m9vCTWVlJcxmM6KiopzKo6KiUFZW5nKd06dP4/HHH8dHH30EpVLZpe9ZsWIF6urq7ENhYeEl192bhGpCce+Ee7Hppk34w9Q/IN4/HrX6Wrxx+A1k/icTz+19Dufrz7u7mkRERF3m9g7FMpnM6bMQol0ZAJjNZvziF7/As88+i+HDh3d5+2q1GoGBgU4Dteer8sXNI2/Gf2/8L/561V8xJmwM9GY9/n3q37jhyxvw8NaHcfjCYXdXk4iI6KK61vzRB8LDw6FQKNq10lRUVLRrzQGAhoYGHDhwAFlZWbjvvvsAABaLBUIIKJVKfPfdd5g9e3a/1N2bKeQKXJN8DTKTMnGg/ADey3kPO4p2YEvBFmwp2IJJkZNw2+jbMDNhJjsfExHRgOS2cOPj44P09HRs3rwZN954o7188+bNWLBgQbvlAwMDcfToUaeyVatW4YcffsB//vMfpKSk9HmdBxOZTIYp0VMwJXoKztaexXs57+G/5/6LQxWHcKjiEOL843DzyJtx47AbEejD1jAiIho4BsSt4G+88QYyMjLw5ptv4q233kJOTg6SkpKwYsUKFBcXY+3atS7Xf+aZZy56t1Rbg/1W8EtRoavAJyc/wX9O/Qe1+loAgFapxYIhC3DLqFuQHJTs1voREZH36s75220tNwCwePFiVFVV4U9/+hNKS0sxZswYbNy4EUlJSQCA0tJSFBQUuLOK5CDSNxIPTnoQvx73a2w4twEfnvgQZ2rP4NPcT/Fp7qeYHjcdvxz1S2TEZrjsN0VERNQf+PoF6jEhBH4s+xEfHf8I24u2Q0D6U0oNSsUto27BDUNu4PNyiIioV3jMQ/zcgeGmbxTUF+Djkx/jqzNfocnYBAAI9AnETcNuws9G/AwJAXy+EBER9RzDTScYbvpWo6ERX535Ch+d+AhFjUUAABlkmBY3DUtGLMGVcVfyLisiIuo2hptOMNz0D7PFjJ3FO/Fp7qfYXbzbXh7rF4ufjfgZbhx6I8K0YW6sIREReRKGm04w3PS/gvoCfHbqM3x55kvU6esAAEq5EplJmVgycgkmRExgB2QiIuoUw00nGG7cp8XUgk35m7Audx2OVrY+s2h4yHAsHrEY81LnwU/l58YaEhHRQMVw0wmGm4EhpzIH63LXYWPeRujN0lvb/VR+mJsyFz8d9lOMDhvN1hwiIrJjuOkEw83AUqevw/qz67Eud53TCzpHho7EomGLMC91Hp+ATEREDDedYbgZmCzCggNlB/Cf0//BlvNbYLQYAQAahQaZyZm4adhNmBg5ka05RESDFMNNJxhuBr7allr899x/8fnpz3Gm9oy9PCUoBTcNuwk3DLkBoZpQN9aQiIj6G8NNJxhuPIcQAkcqj+DzU5/j2/xv0WxqBiDdaTU7YTYWDVuEy2Mu53NziIgGAYabTjDceKZGQyP+L///8Pmpz5FTlWMvj9RG4voh12PBkAVIDU51Yw2JiKgvMdx0guHG852sPokvTn+BjXkb7c/NAYBx4eOwYOgCXJN8DYLUQW6sIRER9TaGm04w3HgPg9mAHUU78PWZr7GzeCfMwgwA8JH7YFbiLCwYsgAZsRlQypVurikREV0qhptOMNx4p8rmSmw4twFfn/0ap2tO28sjtBG4fsj1mJ86H0NDhrqxhkREdCkYbjrBcOPdhBA4WX0SX5/9GhvObUCtvtY+b0TICMxLnYe5KXMR7RftvkoSEVG39Uu4KSwsRH5+PnQ6HSIiIpCWlga1Wt2jCvcnhpvBw2g2SpetzkqXrUwWEwDpLeVToqdgXuo8/CTpJ3xIIBGRB+izcHP+/Hm88cYb+OSTT1BYWAjHVX18fDB9+nTcc889uOmmmyCXy3u+B32I4WZwqm2pxXfnv8OGcxtwqOKQvVwlV+Gq+KswL3UepsdPh1ox8AM6EdFg1Cfh5sEHH8SaNWuQmZmJ+fPn47LLLkNcXBy0Wi2qq6tx7Ngx7Ny5E5988gmUSiXWrFmDKVOm9MoO9SaGGyppLMHGvI3YcG6D00MCA1QBuDr5asxLmYf0qHQ+P4eIaADpk3Dzu9/9Dr///e8RERFx0WU3btwInU6Hn/70p12rcT9iuCEbIQRO1ZzChnMbsDFvI8p15fZ5YZowXJ10Na5JvgYTIycy6BARuRk7FHeC4YZcsQgLDpYfxIZzG7D5/GbUG+rt8yK0EchMzsQ1yddgfMR4yGUD85IrEZE3Y7jpBMMNXYzRbMS+0n3YlL8JPxT8gAZjg31epG8kMpMycW3KtRgXPo4v8iQi6id9Hm6qqqrw1FNPYevWraioqIDFYnGaX11d3d1N9huGG+oOg9mAfaX78G3et9hauBWNxkb7vBi/GHvQSQtLY9AhIupDfR5u5s6di7Nnz+Luu+9GVFRUu/+o33777d3dZL9huKGe0pv12FO8B5vOb8LWgq3QmXT2eXH+cbg66WrMSZyDcRHjeOmKiKiX9Xm4CQgIwK5duzB+/PgeV9JdGG6oN7SYWrC7eDc25W/CtqJt9jeWA0C4NhyzEmZhTuIcXBZ9GVQKlRtrSkTkHbpz/u7RS3dGjhyJ5ubmiy9I5KU0Sg3mJM3BnKQ5aDY1Y2fRTnxf8D12FO1AZXMlPjv1GT479RkCVAGYkTADcxLnYFrsNPiqfN1ddSIir9ejlpv9+/fj8ccfx1NPPYUxY8ZApXL+P9OB3CLClhvqS0azET+W/YjvC77H1oKtqGqpss9TK9TIiM3AnMQ5mBk/E8GaYPdVlIjIw/T5ZanTp0/j5ptvRlZWllO5EAIymQxms7m7m+w3DDfUX8wWM45UHsH357/H9wXfo6ixyD5PIVNgctRkzE6cjZkJMxHrH+vGmhIRDXx9Hm4uu+wyKJVKPPjggy47FF911VXd3WS/Ybghd7A9MPD7AinonKo55TR/WMgwzIyfiRnxMzA2fCwfGkhE1EafhxtfX19kZWVhxIgRPa6ku/RluLFYBORy3g5MF1dYX4gfCn/ADwU/IPtCNiyi9XEKoZpQXBl3Ja6KvwpXxF4Bfx9/N9aUiGhg6PNwM2PGDDz11FP4yU9+0uNKuktfhRuzReCql7ZiZHQgrhoRgZnDI5AQys6jdHG1LbXYVbIL2wu3Y3fxbqeHBirlSkyOmoyZCVKrTkJAghtrSkTkPn0ebj777DM888wz+N3vfoexY8e261A8bty47m6y3/RVuMkurMXC13Y7lQ2J8MPMEZGYOSICU5JDoVHxUgN1zmgxIrsiG9sKt2FH0Q7k1+c7zR8SNAQzEmZgRtwMjI8cD5Wct5kT0eDQ5+FGLm//gDKZTDaoOxRbLALHS+ux/dQFbMutwKGCWpgtrf+0WpUCGUPCMHNEBGYOj0RiGFt16OLy6/KxvWg7dhTtwMHygzCL1t+Wv8ofl8dcjmlx0zAtdhpi/GPcWFMior7V5+Hm/Pnznc5PSkrq7ib7TX91KK5rNmL3mUpsy63A9lMXUF6vd5qfGu6HGcMjMHNEBC5PDWOrDl1UvaEee4r3YFvRNuwp3oMafY3T/NSgVEyLm4YrY69EenQ61Aq1m2pKRNT7+OLMTrjjbikhBE6UNthbdQ6er4HJoVVHrZTjspRQXDk0HFcOC8eo6EB2TKZOWYQFJ6pOYFfxLuwu2Y3DFw47dUrWKDSYHD0ZV8ZdiWmx05AUmMR3XxGRR+uTcLN3715kZGR0qQJNTU3Iz89HWlpal5bvTwPhVvD6FiP2nKm0hp0LKK1rcZof5ueDK4aGY/rQcEwbFo64YK1b6kmeo05fhx9Lf8Tukt3YVbwLFboKp/lx/nG4Mu5KZMRkYErMFAT68DEIRORZ+iTcDBs2DMnJyVi6dCmuu+46+Pu3vz31+PHj+PDDD7FmzRq8+OKLuPXWW3u2B31oIIQbR0IInK5oxK7Tldh1phL7zlVBZ3Dus5Qa7odp1ladjCFhCNSwEyl1TAiB07Wnsbt4N3YX78bBioMwWUz2+XKZHGlhabg85nJcHnM5xkeO5yUsIhrw+iTcGI1GrF69Gq+++irOnj2L4cOHIzY2FhqNBjU1NTh58iSampqwaNEirFixAmPGjOmVneltAy3ctGUwWZBdWItdpy9g15lKHC6qc+qYLJcB4xOCceXQcEwbGo6JicFQK9lfhzqmM+rwv7L/YXfxbuwr3dfuDiyNQoOJkRNxeawUdkaGjuRbzYlowOnzPjeHDh3Czp07kZ+fj+bmZoSHh2PixImYNWsWQkNDe1zx/jDQw01b9S1G7DtbhV1npJadcxeanOarlXKkJ4UgIzUMGUPCMC4+GD5KnpioY2VNZfix9EfsK92HfaX7UNlc6TQ/WB2My6Ivw9SYqciIyUB8QDz76xCR27FDcSc8Ldy0VVzbjN2nK7HzTCX2nq1CZaPzXVhalQKTk0NweWoYLk8Nw7j4IKgUDDvkmhACZ2vP4seyH7GvZB/2l+9Hk9E5QMf6xWJK9BRMjp6MKdFTEOcf56baEtFgxnDTCU8PN46EEDh7oRF7z1Zh77kq7DtXjeomg9Myfj4KTE4ORcaQMGSkhiEtNhBKhh3qgNFiRE5ljr1V5/CFw079dQAp7NiCzuSoyYjzj2PLDhH1OYabTnhTuGnLYpE6J+89W4m956rwY141anVGp2UC1EqkJ4dgSnIopiSHYlx8EJ+xQx3SGXXIrsjG/vL92F+2HzmVOTAJ57AT4xdjDzqToycj3p+XsYio93lUuFm1ahVeeukllJaWIi0tDa+88gqmT5/uctkvvvgCr7/+OrKzs6HX65GWloZnnnkG11xzTZe/z5vDTVsWi8DJsgZrq04VfjxXhfoW5xOTj0KOcfFBmJISisuSQzEpKQRBWt6NRa45hp0DZQdwrPJYu7AT7ReNKVFTkB6VjolRE5ESmMKwQ0SXzGPCzbp163Drrbdi1apVmDZtGlavXo23334bx48fR2JiYrvlH3roIcTGxmLWrFkIDg7GmjVr8Ne//hU//vgjJk6c2KXvHEzhpi2zReBEaT3+l1eNA+er8b+8mnZ9dmQyYERUAC5LCcXkZCnwRAdp3FRjGuh0Rh2yL2TjQNkB7C/b7zLsBKuDMSFyAiZFTsLEyIlIC0uDSsEATUTd06fhxmg0IjMzE6tXr8bw4cMvqaJTp07FpEmT8Prrr9vLRo0ahYULF2LlypVd2kZaWhoWL16Mp556qkvLD+Zw05YQAvlVOuzPr8b+vGocOF+DvMqmdsslhGoxJSkUU1JCMSU5BEMi/Pl/4uSSzqjD4QuHsb9sP7IqsnC08ij0ZucArVaoMSZ8DCZFTsKEyAmYEDmBDxUkoovqzvlb2d2Nq1QqHDt27JJPbgaDAQcPHsTjjz/uVJ6ZmYk9e/Z0aRsWiwUNDQ2d3n6u1+uh17f+x7W+vr5nFfZCMpkMKeF+SAn3w88nJwAAKhpacCC/Rgo8+dU4XlKPwupmFFYX44usYgBAkFaFiYnBmJQYgomJwZiQEIwAPliQAPiqfJERm4GMWOlp5kazEcerjyOrPAtZFdJQo6/BwfKDOFh+EAAggwxDQ4baW3YmRU7iS0CJ6JL06LLUo48+CpVKhRdeeKHHX1xSUoK4uDjs3r0bV1xxhb38L3/5C95//33k5uZedBsvvfQSXnjhBZw4cQKRkZEul3nmmWfw7LPPtitny03XNLQYkVVQaw87WQW10JssTsvIZMDwyAB74JmUFIzUcH++H4vaEUIgvz4fWRVZOFR+CNkXsnG+vv2LeKN8ozAhcgLGho/F+IjxGBU2ik9RJhrk+rzPzf3334+1a9di6NChmDx5Mvz8/Jzmv/zyyxfdhi3c7Nmzx+mdVc8//zw++OADnDx5stP1P/nkE/zqV7/C119/jZ/85CcdLueq5SYhIYHhpocMJgtOltXj0PkaHCqoRVZhDQqrm9stF6hRYkJiCCYlBmNiYggmJASzozK5VNlcieyKbByqOITsimycqDrRrt+OUq7EyJCRGBsxFuMixmF8+Hg+XJBokOnzcDNr1qyONyiT4YcffrjoNgwGA3x9ffHZZ5/hxhtvtJc/+OCDyM7Oxvbt2ztcd926dbjzzjvx2WefYd68ed2qO/vc9L6KhhZkF9TiUEEtDhXU4EhRLVqMlnbLDYv0x8TEYIxPCMb4+GAMjwrg05SpHZ1Rh2OVx3Ck8giOXDiCwxcOo7qlut1yIeoQKeyEj8O4iHEYEz4GAT4BbqgxEfUHj7lbaurUqUhPT8eqVavsZaNHj8aCBQs67FD8ySef4K677sInn3yChQsXdvs7GW76ntFsQW5ZAw4V1CDLGnjOV+naLeejlGNUTCDGxwdhXHwwxscHITXCHwpeziIHQgiUNJXgyAUp7BypPIITVSdgtDg/w0kGGVKDUjEuYhzGRozF2PCxGBI8BCo5WwyJvEG/hpuioiLIZDLExXX/key2W8HfeOMNZGRk4M0338Rbb72FnJwcJCUlYcWKFSguLsbatWsBSMHmtttuwz/+8Q8sWrTIvh2tVougoKAufSfDjXtUNeqRZb2MdaSoDkeK6lDXbGy3nJ+PAmlxQQ6BJxgJoVpefiAnBrMBudW5OFIptewcuXAExY3F7ZbzkftgROgIjA4bjbSwNKSFpyE1KBVKebfvpSAiN+vzcGOxWPDnP/8Zf/vb39DY2AgACAgIwKOPPoonnngCcnnXLzWsWrUKL774IkpLSzFmzBj8/e9/x4wZMwAAd9xxB/Lz87Ft2zYAwMyZM11errr99tvx3nvvden7GG4GBiEECqp1OFxUhyOFtThSVIdjJXXQGcztlg32VWFsXBDGxwdjXHwQxsQFISZIw8BDTqqaq3C08qi9hed41XE0GBvaLadRaDAydCTSwtOkwBOWhqTAJCjkfFI30UDW5+FmxYoVeOedd/Dss89i2rRpEEJg9+7deOaZZ7B06VI8//zzPa58X2O4GbjMFoEzFY04XFSLo0V1OFJUixOlDTCY2/ffCfFVIS02CGlxgdI4NhApYX68Q4vshBAobChETlUOcipzkFOVg+NVx6Eztb9E6qv0xaiwUUgLS7O38iQGJkIuY58wooGiz8NNbGws3njjDcyfP9+p/Ouvv8Zvf/tbFBe3bx4eKBhuPIveZEZuWYO9hedocR3OVDTCZGn/Z+vno8ComECkxQYiLU4KPMMi2WmZWlmEBfn1+ciplIJOTlUOTlafRLOp/R1/WqUWI0JGYGToSGkIG4mhwUN5SzqRm/R5uNFoNDhy5Ei7JxTn5uZiwoQJaG5u/x+KgYLhxvO1GM04Vd6AnJJ65JTU4VhxPU6W1bu8Q8tHIcfwaH+kxdhaeQIxIjoQ/mr2uSCJyWJCXl2evWUnpyoHudW57Z6sDABKmRIpwSkYGTLSHnpGhI5AkLprff6IqOf6PNxMnToVU6dOxT//+U+n8vvvvx/79+/Hvn37urvJfsNw451MZgvyKptwrKQOOcX1yCmpx7GSOjS0eVGoTWKoL0ZGB2BkTCBGWceJob68U4sASIEnvy4fJ2tO4mTVSWlcfRJ1+jqXy8f6xba28FgDT4xfDPuFEfWiPg8327dvx7x585CYmIiMjAzIZDLs2bMHhYWF2LhxY4dv9R4IGG4GDyEEimqa7a07OSV1OFHagLL6FpfLa1UKDI8OkMKONfCMjA5AsK9PP9ecBiIhBMp15ThZfRInqk8gtzoXJ6tPurxLCwD8Vf4YGjwUw0KGSUOwNGYrD1HP9Mut4CUlJXjttddw8uRJCCEwevRo/Pa3v0VsbGyPKt1fGG6opsmAk2UNOFlWj5Ol0ji3vMHlZS0AiAnSOIWdYZEBSI3wg0bFu2sIqDfUI7c6F7nVufbQc7b2bLunLNtE+kZiWMgwDA8ejqEhQzEseBhSg1PZl4foIjzmreDuwHBDrpgtAvlVTfawc8I6Lqpx3X9MLgOSwvwwLNIfw6MCMCzKn6GH7IxmI/Lr83G65jRO156WxjWnUdJU4nJ5hUyBxMBEe+uOLfzEBcTxji0iqz5vuYmIiMCePXswbNiwHlfSXRhuqDvqW4w4VdaAE2UNOFFaj9PlDThV3ujyAYSAFHqSw/zsYWdYlBR+UsIZeghoNDTiTO0ZnKo55RR86g31LpfXKrVIDkzGkOAhSA1KRWpwKlKDUpEQkMAHEdKg0+fhpjfeCu4uDDd0qYQQuNCgx+mKRpyyhh0p9DSgvoMOzI6hZ3hUAIZG+mNIhD9Swv3gxzu3BjUhBC40X7C37tgCz9naszBYDC7XUcqVSA5Mdgo8qUGpSA5K5uUt8loe8VZwd2G4ob5iCz2nyqXQc7ri4qEHkPr0DInwR2qEn9M4OlDDhxIOYiaLCYUNhThXdw7nas/hXN05nK09i/z6fJfP5QEAuUyOeP94p9AzJHgIUoJS4Kfyc7kOkafwiLeCuwvDDfW39qGnAWcqGnHuQhOqmlz/nzkg3b2VGuGH1Ah/DHEch/tD68NLXIOVRVhQ2lRqDzy28HO27iwaDO1fN2ETqY1EUlASkgOTkRTYOo4LiOPLRckj9Gm4MZvN2LVrF8aOHYvQ0NBLqqg7MNzQQFKrM+DshSacvSCFHWnciPNVOpdPYbaJDdJgSKQ/UsP9kBzuh+QwaRwfooVKwQ6og5EQAlUtVThbe9beypNXl4dzdedQ2VzZ4XpKmRLxAfFICkyyD8mByUgOSkaENoLP6qEBo1+eUHzixAmkpKT0uJLuwnBDnsBotqCwWoezF5pw7kKjU/ip0bnuzAwACrkM8SFaJIX5ISXMVxqH+yEpzBcJob4MPoNUnb4O5+vP43z9eeTX59unz9ef7/ASF9Daodkx+CQGJiIxIBHB6mAGH+pXfR5upkyZghdeeAFz5szpcSXdheGGPF11kwHnbGGnshHnK3XIr2pCflVTh8/qAaTgExestbb0+Fpbe6RxfIgv38E1CFmEBRW6Cqfgk18nhZ/ixmKYhbnDdf1V/kgISHAaEgMTkRCQgEjfSN7CTr2uz8PNd999h+XLl+O5555Denp6uw7FAzk0MNyQtxJCoLxeLwWdyibkV+lwvqoJeZVNOF+lQ7Ox4xOVXAbEBGmREKpFYqgvEkJ8kRjmi/gQXySG+iLc34f/lz7IGM1GFDUWSaGnLt/e4lPYUIhyXXmn6/rIfRAfEN8u/CQEJCDOPw4qBfv4UPf1ebiRy1sTueN/8IQQkMlkMJs7/o+ouzHc0GAkhEBFg94aehyDjzTWGTr/zWpVCiSEapEQIl3eSgiVQo+tjLezDy4tphYUNxajoL4AhQ2FTkNJY0mHT2cGpDu6YvxiEO8fj1j/WMT6xyLOP84+RPhGsNWHXOqXd0t15qqrruruJvsNww2RM9vdXIU1OhRWN6OgWofCah0KqnUoqmlGSV0zLvZfiTA/H4fQIwWe+BBfxIVoEROk4QMMBxGTxYTSplIUNhSiqKGoNQA1Sp876+MDACq5CjF+MYjzj0OsfyziA+IR6xdrnw7ThLEVcZDql3dLeSqGG6LuMZgsKKm1hp4aa+ixhqCCal2HT2t2FO6vRlyIFvHBWsQGaxAXrEVciC9igzWID/ZFoFbJE9YgIIRAZXMlChsKUdxYbB9KGktQ3FiMsqayTvv5AIBaoZbCT0Ac4vziEBcghaA4vzhE+0UjTBvGlh8v1S/hZufOnVi9ejXOnTuHzz77DHFxcfjggw+QkpKCK6+8skcV7w8MN0S9q67ZiMJqHYqswcfW+lNc24zimuZO+/rY+KuVDqFHi9hgLeKCtYi3TkcGaKDgAw29nsliQoWuwmXwKW4sRnlTOQQ6P2Up5UpE+0Yj2i8aMX4xiPZzno7xi4G/j38/7RH1pu6cv3t0ofzzzz/HrbfeiltuuQWHDh2CXq8HADQ0NOAvf/kLNm7c2JPNEpEHCtKqEBQXhDFxQe3mCSFQqzOiuLZZusRV22wPPSV10riqyYBGvcn6kMNGl9+hlMsQHaRBTJAG0UHSpa7oQA1ig1s/h/urGYA8nFKutPfDmYIp7eYbzUaU6crsoaeooQglTSX2AFTZXAmTxYSixiIUNRZ1+D0BqgBE+UUhxi/GZQCK8o1ip2cP16OWm4kTJ+Lhhx/GbbfdhoCAABw+fBipqanIzs7Gtddei7Kysr6oa69gyw3RwNJsMKO4tk3wqW1GkXW6rL4F5k4eaGijkMsQFaC2hiCtQxhqDUWRAWo+68eLGS1GXNBdQFlTGUqbSlHaVIqypjL7UNpU2uFLSh3JIEO4NhxRvlGI8I1ApG8konyjEOkb6TTNFqD+1ectN7m5uZgxY0a78sDAQNTW1vZkk0Q0SGl9FBga6Y+hka5PFGaLQHl9C0pqpaBTVteC0jrbuBlldS0ob9DDbBEoqWtBSV0LgFqX25LJgAh/NWKCNIgKlIJPZIAakYHSOMo6DvH14Xu9PJBKrrK3/HREZ9TZg45jCCpvKreXGSwGXGi+gAvNF4Cqjr/PV+lrDzyOg2MQCteG8w3ubtCjf/GYmBicOXMGycnJTuW7du1Campqb9SLiAiA1CITGyz1vemI2SJQ2ai3hp5mh/BjHdc3o7xOD4PZgooGPSoa9ADqOtyeSiFDhH/70BMVqEFEoBpRARpEBqoRyhDkcXxVvtJLRYNdn6uEEKhuqUZZUxnKdeW4oLuAcl05KnQVTkODsQE6k0568GF9foffJ5fJEaYJa9cCFK4NdxpCNaEMQb2oR/+Sv/71r/Hggw/i3XffhUwmQ0lJCfbu3YvHHnsMTz31VG/XkYioUwq5DFGBUmsMEoJdLmOxCFTrDA6hpxkVDXqU17dYx3pU1LegqskAo9mxFahjSrkMEU4tP2pEBkjT4f5qRASoER6gRri/D9RK3g7vCWQyGcK0YQjThiENaR0upzPq7EHHMfxcaG4NQ5W6SpiEyd4KdLzqeMffCxlCNCEI14YjQhuBMG2YfTpcG44wbZh92k/lx7sLL6LHd0s98cQT+Pvf/46WFunHr1ar8dhjj+G5557r1Qr2Nva5IaLOGEwWVDbqnYLPhfoWKfw02MZ6VDXpL/r8H0cBGiUi/KXQEx7gI43tgw/CA9T2+Xzru3ewCAuqW6qlsNPUGoQuNF9AZXMlqpqrpHFLFSyi41entKVRaJzCTtvpUE2offBV+fbhHvavfnvOjU6nw/Hjx2GxWDB69Gj4+w/8zlUMN0TUG4xmC6oaDQ4tP9K4wjqubNSjskGPykYDDOaun7gAwM9HYW3xsQYfeyhSI9zPB6F+Pgjz90GonxrBWhUvjXk4s8WMGn2NPew4hp+2003Gpm5tW6vUOoWdUE0oQjQh9ukwTRhCta3lKvnAvUuMD/HrBMMNEfUnIQTqW0yobNTjQpvQU9kofb7QaLCW6aE3dS8IyWVAsK8UeEL9fBDm1zrdWqZ2+syXpHounVGHqpYqp+BjGy7oLqCmpQbVLdWoaqmC3qzv9vYDfQJbg4+1FcgxDNmGYHUwgtXBUMj7r5WR4aYTDDdENFAJIdCgN7ULP5UN1gDUqEdVox7VTQZUNxlQ39LxO5w6E6BWItTfByG+DmHIX5oOsQalYF8Vgn2lz4EaJZS8hd6jCCHQbGpGVUsVqluqUd1cLY07GGpaai76dOi2ZJAhUB2IEHUIQjQhCFYH28cR2gj8cvQve3WfGG46wXBDRN7CaLagpsmAKmvYsQ3SZz1qmoyoatI7zevCI4NcCtQorWFHhSDrOFgrBaBgXxVCfB0DkQrBWh8EaJS8ZOYhLMKCen29vdXHMfTYpquapfIafQ3q9B3fbQgA4dpwbP351l6tY58/54aIiNxPpZBLd2oFarq0vMUiUN9itIehqkYDanSt09VNelQ1GVDXbESNzoDaJiMa9FLrUH2LCfUtJhRUd71+cpn0BOsQXx8E2QKQ1iEAWYNSoEaJIK0KgVoVAjUqBGlVvHTWz+QyOYI1wQjWBCMVF3+ki8liQp2+DrX6WtS01KBGXyONW2pQq691+xOeGW6IiAYJuVxmbWnxwZCIrq1jNFtQ12xErc6IWp0BtTop+NgDkM46r9mAmiajvVxnMMMigBqdETW6i79ctS2NSi4FHmvYkYJPawiyzQvUKp1CUaBWhQA1W4z6mlKutN8yPxAx3BARUYdUCrn9bq3u0JvMqLMGm1qdATU6I+qaDdbPtjIpJNU3m1DfIgWjBms/ohajBS1G6flD3SWTSf2K2oUgjQoBGhX8NUoEapTwVysRoFEhQKN0KJM++/oo+CwZD8ZwQ0REvU6tVCAyUNHlS2Y2ZotAY0tr2Klvto5bpBBkm3aeZ7JP600WCNF6Ga2oprlH9ZfL4Bx+1EprCJI+B2iUCLDOb50nBSjHz3x4o3sw3BAR0YChkMsQ5KtCkK8KCT1Yv8VobheE6q1BqL7FhIYWExpajGjUS9O2IGX/rDfBbBGwOASkS+GjlMNfrYSfWgE/HyX81FKrkFSmhJ+PQho7TPurlfBVK+Gvts5zWE+tlLNFqQsYboiIyGtoVApoVApEBvRsfSEEmo1ma+gxWUOPEY22YNTmc6O+TTiyljVaO2IbTBZUmwyo7t6z9zqklMvahyJrcJJCkTUg+bQGJK2PEr4qBXx9FND6KODro3SYVkCr8r5LcAw3REREVjKZzHryVyLyEp4WYrYINBmkwNNkDTs6vRmNeumzzmBCo96MJr0JTQaprElvtk836s3QGVrXbTFKD3c0WQTqrJfgepNWpYCf2hp4VEp78JFCkBSO2pb5dRCWfFVSyOpuP63exHBDRETUyxRymdSRWdM7t0TbwpI9BFlDUpPB3BqeHAJT2+lmgxk669BslIKTLTABQLNRKu8toX4+OPTk1b22ve5iuCEiIhrgejssAdJzj6SgY0azQWo1sk3rDCb7PKnM5DBths5ohk5vLTO2zreFKF83v/yV4YaIiGgQktv676h7Pwq4++UHfAQkERER9Sp3d1BmuCEiIiKvwnBDREREXsXt4WbVqlVISUmBRqNBeno6du7c2eny27dvR3p6OjQaDVJTU/HGG2/0U02JiIjIE7g13Kxbtw4PPfQQnnjiCWRlZWH69OmYO3cuCgoKXC6fl5eH6667DtOnT0dWVhb+8Ic/4IEHHsDnn3/ezzUnIiKigUom3NileerUqZg0aRJef/11e9moUaOwcOFCrFy5st3yy5cvx/r163HixAl72bJly3D48GHs3bu3S99ZX1+PoKAg1NXVITDwEp7QRERERP2mO+dvt7XcGAwGHDx4EJmZmU7lmZmZ2LNnj8t19u7d2275a665BgcOHIDR6PppjXq9HvX19U4DEREReS+3hZvKykqYzWZERUU5lUdFRaGsrMzlOmVlZS6XN5lMqKysdLnOypUrERQUZB8SEnryKjYiIiLyFG7vUNz2XnghRKf3x7ta3lW5zYoVK1BXV2cfCgsLL7HGRERENJC57QnF4eHhUCgU7VppKioq2rXO2ERHR7tcXqlUIiwszOU6arUaarX7Xt5FRETUZRYLYDECFpN1MANmx8/WsrbLWEwOy5kd5hmdP5vbfHY5tP1Os8O22m7f9rlNmW8YcNtXbvtndFu48fHxQXp6OjZv3owbb7zRXr5582YsWLDA5ToZGRn45ptvnMq+++47TJ48GSpV771vg4iIPIjFApgN0snXdlI2GzqYNjosaz1hmw0dTNu212bsctrUyXY7CBoWU5v5JgDufW1Br/F33UjRX9z6bqlHHnkEt956KyZPnoyMjAy8+eabKCgowLJlywBIl5SKi4uxdu1aANKdUa+++ioeeeQRLF26FHv37sU777yDTz75xJ27QUTknYSw/l+8vjUgmGzT1sFkm9a3BgeTbVrfZh1j67ZMBuftuCozOWyzs2AhLBffF08nVwEKFSBXAnKFdayUyp0+KwGF0vmz02Bdtje3ZRvLHD4rNW7953JruFm8eDGqqqrwpz/9CaWlpRgzZgw2btyIpKQkAEBpaanTM29SUlKwceNGPPzww3jttdcQGxuLf/7zn7jpppvctQtERL3PYpZO7KYW60m+pfWzSe8wtHSwjIt1zPr2y3QUJBzLPLUlQeFjDQRK52m5Svpsn7Z+tp3wHaft811NO27XGhQUPh1Mq9oEgrafL7aM27vHehy3PufGHficGyLqMrMRMDZLg6kZMLZYx7ayFuexU1kHgcLxc0fBxeL60RYDgkINKNWtQcA22Msc5jmV+QBKH+d1XJU5bdtxuqOQ4aJMrgDc/OJG6n3dOX+7teWGiKjbzEbA0GQNE7rWaVv4MOrahA6dNZS4Kmu7TpvwIszu3ltAJpea+JVq57HCx0X5xZaxfda0hg57uLAGCaW6TQBxKJMrGRrIIzDcEFHvspitoUMHGJus42aHaV0P5juUuatVQ6kFVNZBqWk/rdQAKl9ApWkNEE6BwhY4XISQzpZR8D/TRN3FXw3RYGYyAIZG69AE6BvbfG6Qxoam1nJ9o/NnY7NzEDHr+6fuMgXg49caMlS+bYKGqyCitYYP67jdOg7hxHEdpZotFkQehOGGyJOYjUBLPaCvl4KHPXw0OISTtp/bhheH+WZDH1ZWJoUFH19raHCYtocSv07md7SOdVrhw8BBRC4x3BD1B7PRGkbqreGkwWGoc/5sn9923CD1C+kLCjWg9pdCg0+ANG772V5mG/ysY982QcWhNYXhg4jcgOGG6GIsZmsoqWsdmmudP7fUOYeRtgHG1Ny7dVL5AeoA69A2cFjn2cNH28/+DsHFWqbgQzCJyHsw3JD3s1ikyzBtw0hHIcU+1LaGlt6i8gXUgQ7BJADQBLYpazOtafPZx5+dTImIOsH/QpLnMBulMNJcDTTXtB90Lspt4aQ3nmCq8gU0QQ5DsMN0oDS2h5PANuElQLq8w1BCRNTn+F9a6n8mQ5sQcrGwUiuNDQ2X9r1KTZtw0lFQcSjTWsvVgdLtukRENOAx3NClsZitQaRKGpoqW6d11YDO4XOTdWxsuoQvlElhQxviPPiGti/ThjiHFpV733VCRET9g+GGWgkh3R5sDyTVbcJKpTWwOISY5hr07N0zMqlVRNtBKOkwrARJj1YnIiLqAMONt7OYrSGlAmi6ADRekMZNFc7TTZXSdE9vNdYEAb7hgG+YNPiFtU47lvuGSoM6iC+DIyKiPsFw44lMemtQsYWSCudpe4ipkFpXutuZVqEG/MKtQcQxsNjKXAQW3kpMREQDBMPNQCGE1MLSWAY0lAGN5W3GFa2tLfq67m9fGwr4RwJ+EdLgHymFFb9I58++4dKzT/jwNSIi8lAMN33NbJJCSUeBpbEMaCiXyrrzQkC5yhpUwl2Elgjnz77hvAWZiIgGDZ7xektTJbBvlTWolLWOmyrRrQ632lAgIBrwj2o/9o+0trSES51r2bpCRETUDsNNbzEbgZ1/cz1PppCCiavAYg8u1oHPUiEiIrokDDe9xS8CmLIUCIgC/KOdw4tvGG9fJiIi6icMN71FoQTm/dXdtSAiIhr0+KARIiIi8ioMN0RERORVGG6IiIjIqzDcEBERkVcZdB2KhZCeOVNfX+/mmhAREVFX2c7btvN4ZwZduGloaAAAJCQkuLkmRERE1F0NDQ0ICgrqdBmZ6EoE8iIWiwUlJSUICAiArJef8FtfX4+EhAQUFhYiMDCwV7c9UHj7Pnr7/gHcR2/g7fsHeP8+evv+Ab2/j0IINDQ0IDY2FnJ5571qBl3LjVwuR3x8fJ9+R2BgoNf+sdp4+z56+/4B3Edv4O37B3j/Pnr7/gG9u48Xa7GxYYdiIiIi8ioMN0RERORVGG56kVqtxtNPPw21Wu3uqvQZb99Hb98/gPvoDbx9/wDv30dv3z/Avfs46DoUExERkXdjyw0RERF5FYYbIiIi8ioMN0RERORVGG6IiIjIqzDcEBERkVdhuOklq1atQkpKCjQaDdLT07Fz5053V6nHVq5ciSlTpiAgIACRkZFYuHAhcnNznZa54447IJPJnIbLL7/cTTXunmeeeaZd3aOjo+3zhRB45plnEBsbC61Wi5kzZyInJ8eNNe6+5OTkdvsok8lw7733AvDM47djxw7ccMMNiI2NhUwmw1dffeU0vyvHTa/X4/7770d4eDj8/Pwwf/58FBUV9eNedKyz/TMajVi+fDnGjh0LPz8/xMbG4rbbbkNJSYnTNmbOnNnuuC5ZsqSf96RjFzuGXfm7HMjHELj4Prr6XcpkMrz00kv2ZQbycezK+WEg/BYZbnrBunXr8NBDD+GJJ55AVlYWpk+fjrlz56KgoMDdVeuR7du3495778W+ffuwefNmmEwmZGZmoqmpyWm5a6+9FqWlpfZh48aNbqpx96WlpTnV/ejRo/Z5L774Il5++WW8+uqr2L9/P6Kjo3H11VfbX7rqCfbv3++0f5s3bwYA/OxnP7Mv42nHr6mpCePHj8err77qcn5XjttDDz2EL7/8Ep9++il27dqFxsZGXH/99TCbzf21Gx3qbP90Oh0OHTqEJ598EocOHcIXX3yBU6dOYf78+e2WXbp0qdNxXb16dX9Uv0sudgyBi/9dDuRjCFx8Hx33rbS0FO+++y5kMhluuukmp+UG6nHsyvlhQPwWBV2yyy67TCxbtsypbOTIkeLxxx93U416V0VFhQAgtm/fbi+7/fbbxYIFC9xXqUvw9NNPi/Hjx7ucZ7FYRHR0tHjhhRfsZS0tLSIoKEi88cYb/VTD3vfggw+KIUOGCIvFIoTw7OMnhBAAxJdffmn/3JXjVltbK1Qqlfj000/tyxQXFwu5XC6+/fbbfqt7V7TdP1f+97//CQDi/Pnz9rKrrrpKPPjgg31buV7iah8v9nfpScdQiK4dxwULFojZs2c7lXnScWx7fhgov0W23Fwig8GAgwcPIjMz06k8MzMTe/bscVOtelddXR0AIDQ01Kl827ZtiIyMxPDhw7F06VJUVFS4o3o9cvr0acTGxiIlJQVLlizBuXPnAAB5eXkoKytzOp5qtRpXXXWVxx5Pg8GADz/8EHfddRdkMpm93JOPX1tdOW4HDx6E0Wh0WiY2NhZjxozxyGNbV1cHmUyG4OBgp/KPPvoI4eHhSEtLw2OPPeZRLY5A53+X3nYMy8vLsWHDBtx9993t5nnKcWx7fhgov8VB91bw3lZZWQmz2YyoqCin8qioKJSVlbmpVr1HCIFHHnkEV155JcaMGWMvnzt3Ln72s58hKSkJeXl5ePLJJzF79mwcPHhwwD9OfOrUqVi7di2GDx+O8vJy/PnPf8YVV1yBnJwc+zFzdTzPnz/vjupesq+++gq1tbW444477GWefPxc6cpxKysrg4+PD0JCQtot42m/1ZaWFjz++OP4xS9+4fS25VtuuQUpKSmIjo7GsWPHsGLFChw+fNh+WXKgu9jfpTcdQwB4//33ERAQgEWLFjmVe8pxdHV+GCi/RYabXuL4f8SAdNDblnmi++67D0eOHMGuXbucyhcvXmyfHjNmDCZPnoykpCRs2LCh3Q91oJk7d659euzYscjIyMCQIUPw/vvv2zsvetPxfOeddzB37lzExsbayzz5+HWmJ8fN046t0WjEkiVLYLFYsGrVKqd5S5cutU+PGTMGw4YNw+TJk3Ho0CFMmjSpv6vabT39u/S0Y2jz7rvv4pZbboFGo3Eq95Tj2NH5AXD/b5GXpS5ReHg4FApFu7RZUVHRLrl6mvvvvx/r16/H1q1bER8f3+myMTExSEpKwunTp/updr3Hz88PY8eOxenTp+13TXnL8Tx//jy2bNmCX/3qV50u58nHD0CXjlt0dDQMBgNqamo6XGagMxqN+PnPf468vDxs3rzZqdXGlUmTJkGlUnnscW37d+kNx9Bm586dyM3NvehvExiYx7Gj88NA+S0y3FwiHx8fpKent2su3Lx5M6644go31erSCCFw33334YsvvsAPP/yAlJSUi65TVVWFwsJCxMTE9EMNe5der8eJEycQExNjbwp2PJ4GgwHbt2/3yOO5Zs0aREZGYt68eZ0u58nHD0CXjlt6ejpUKpXTMqWlpTh27JhHHFtbsDl9+jS2bNmCsLCwi66Tk5MDo9Hosce17d+lpx9DR++88w7S09Mxfvz4iy47kI7jxc4PA+a32Cvdkge5Tz/9VKhUKvHOO++I48ePi4ceekj4+fmJ/Px8d1etR37zm9+IoKAgsW3bNlFaWmofdDqdEEKIhoYG8eijj4o9e/aIvLw8sXXrVpGRkSHi4uJEfX29m2t/cY8++qjYtm2bOHfunNi3b5+4/vrrRUBAgP14vfDCCyIoKEh88cUX4ujRo+Lmm28WMTExHrFvjsxms0hMTBTLly93KvfU49fQ0CCysrJEVlaWACBefvllkZWVZb9bqCvHbdmyZSI+Pl5s2bJFHDp0SMyePVuMHz9emEwmd+2WXWf7ZzQaxfz580V8fLzIzs52+l3q9XohhBBnzpwRzz77rNi/f7/Iy8sTGzZsECNHjhQTJ04cEPsnROf72NW/y4F8DIW4+N+pEELU1dUJX19f8frrr7dbf6Afx4udH4QYGL9Fhpte8tprr4mkpCTh4+MjJk2a5HTbtKcB4HJYs2aNEEIInU4nMjMzRUREhFCpVCIxMVHcfvvtoqCgwL0V76LFixeLmJgYoVKpRGxsrFi0aJHIycmxz7dYLOLpp58W0dHRQq1WixkzZoijR4+6scY9s2nTJgFA5ObmOpV76vHbunWry7/L22+/XQjRtePW3Nws7rvvPhEaGiq0Wq24/vrrB8x+d7Z/eXl5Hf4ut27dKoQQoqCgQMyYMUOEhoYKHx8fMWTIEPHAAw+Iqqoq9+6Yg872sat/lwP5GApx8b9TIYRYvXq10Gq1ora2tt36A/04Xuz8IMTA+C3KrJUlIiIi8grsc0NEREReheGGiIiIvArDDREREXkVhhsiIiLyKgw3RERE5FUYboiIiMirMNwQERGRV2G4IaIB4b333kNwcLDbvv+OO+7AwoULL3k7ubm5iI6ORkNDA4C+36+f/vSnePnll/ts+0SeiOGGiHosOTkZr7zyirurMaA88cQTuPfeexEQEABAetP1qVOn7POfeeYZTJgwode+76mnnsLzzz+P+vr6XtsmkadjuCGiPmU2m2GxWNxdjX5RVFSE9evX484777SXabVaREZG9vp3GY1GAMC4ceOQnJyMjz76qNe/g8hTKd1dgf5msVhQUlKCgIAAyGQyd1eHqM9YLBb84x//wPvvv4+ioiJERkbizjvvxO9+9zsA0puGly9fjv/973/w9fXF/Pnz8Ze//AX+/v4AgGXLlqGurg4ZGRn417/+BaPRiJtuugkvvPACVCoVrrvuOpw/fx4PP/wwHn74YQBAXV0dPvroIzz++ON466238OSTT+LMmTPIyspCUFAQli9fjm+//RZ6vR5XXnklXnzxRQwZMgQA0NzcDCFEpy0QxcXF+OMf/4gffvgBer0eI0aMwN/+9jdERERg3Lhx2Lp1KyZNmmRf/o033sC//vUvHDt2DDKZDCdOnMCTTz6JvXv3QgiBsWPH4vXXX0dqaioMBgOMRqP9+4UQ+Mc//oF3330XZWVlGDp0KH7/+993eulq7dq1GDNmDAIDA+3bsf17FBYW4qOPPsKzzz4LAPb//qxatQq33HIL6urq8OSTT+K///0v9Ho9Jk6ciJUrV2Ls2LEAgJUrV+K///0vli1bhpdeegnnz59HbW0tZDIZMjMz8cEHH+CWW27p9t8JkacQQqChoQGxsbGQyztvmxl075YqKipCQkKCu6tBREREPVBYWIj4+PhOlxl0LTe26+CFhYUIDAx0c22IiIioK+rr65GQkGA/j3dm0IUbW1NwYGAgww0REZGH6UqXEnYoJiIiIq/CcENEREReheGmF1nE4LjdlYiIaCBjuOklQgj8Zstv8MrBV6Az6txdHSIiokGL4aaX/Fj2I/aU7ME7x97Bgq8XYPP5zRhkd9kTERENCAw3vWRq9FT8c9Y/EesXi7KmMjyy7RH8ZstvcL7+vLurRkRENKgw3PQSmUyGWYmz8NXCr/Drcb+GSq7C7pLduPHrG/HPQ/9Es6nZ3VUkIiIaFNwabnbs2IEbbrgBsbGxkMlk+Oqrrzpdftu2bZDJZO2GkydP9k+Fu0Cr1OK+iffhywVfYlrsNBgtRrx19C0s+GoBvi/4npeqiIiI+phbw01TUxPGjx+PV199tVvr5ebmorS01D4MGzasj2rYc0mBSXj9J6/jlZmvIMYvBqVNpXho60P47fe/RUF9gburR0RE5LXc+oTiuXPnYu7cud1eLzIyEsHBwV1aVq/XQ6/X2z939lK+3iaTyTAnaQ4yYjPw9tG3sSZnDXYV78LCrxfi1tG34p5x98BP5ddv9SEiIhoMPLLPzcSJExETE4M5c+Zg69atnS67cuVKBAUF2Qd3vDTTV+WLByY9gC/mf4ErYq+A0WLEu8fexfVfXo+vz3zN5+MQERH1ogHzVnCZTIYvv/wSCxcu7HCZ3Nxc7NixA+np6dDr9fjggw/wxhtvYNu2bZgxY4bLdVy13CQkJKCurs4t75YSQmBb4Ta8dOAlFDYUAgDGhI3B41Mfx/iI8f1eHyIiIk9QX1+PoKCgLp2/PSrcuHLDDTdAJpNh/fr1XVq+O/84fclgNuDDEx9i9eHV0Jmkh/5dn3o9Hpr0EKL8otxWLyIiooGoO+dvj7ws5ejyyy/H6dOn3V2NbvNR+OCuMXdhw6INWDh0IQDgv+f+ixu+ugFvHnkTerO+8w0QERGRSx4fbrKyshATE+PuavRYuDYcz017Dp/M+wTjI8aj2dSMf2X9Cwu+WoCN5zayPw4REVE3ufVuqcbGRpw5c8b+OS8vD9nZ2QgNDUViYiJWrFiB4uJirF27FgDwyiuvIDk5GWlpaTAYDPjwww/x+eef4/PPP3fXLvSaMeFj8MHcD7AxbyNePvgyihuLsXzncnxw/AM8OvlRTI6e7O4qEhEReQS3hpsDBw5g1qxZ9s+PPPIIAOD222/He++9h9LSUhQUtD4TxmAw4LHHHkNxcTG0Wi3S0tKwYcMGXHfddf1e974gk8kwL3UeZifOxtqctXj32Ls4VnUMd266E7MSZuHh9IeREpTi7moSERENaAOmQ3F/GSgdiruisrkSr2e/js9Pfw6zMEMhU+Cnw3+K34z/DcK0Ye6uHhERUb/xyLul+osnhRubc7Xn8PeDf8e2om0AAD+VH+4eczd+OfqX0Cq17q0cERFRP2C46YQnhhub/WX78dcDf8XxquMAgCjfKDww6QFcn3o95DKP7xtORETUIYabTnhyuAEAi7Dg//L+D/849A+UNpUCAEaGjsSDkx7EtNhpkMlkbq4hERFR72O46YSnhxsbvVmPj098jLeOvIUGYwMAID0qHQ9OehATIye6uXZERES9i+GmE94SbmxqWmrw9tG38enJT2GwGAAAM+Jn4IGJD2BE6Ag3146IiKh3MNx0wtvCjU1ZUxneOPwGvjrzFczCDACYmzwX9068F0mBSW6uHRER0aVhuOmEt4Ybm/P15/Fa9mv4v7z/AwAoZAosHLoQy8YvQ7RftJtrR0RE1DMMN53w9nBjk1udi39m/RM7inYAAHzkPlgycgl+NfZXCNGEuLl2RERE3cNw04nBEm5ssiqy8I9D/8DB8oMApGfk/HLUL3Hr6FsRpA5yc+2IiIi6huGmE4Mt3ACAEAJ7SvbgH4f+gRPVJwAA/ip//HL0L/HLUb9kyCEiogGP4aYTgzHc2FiEBd8XfI/XD7+O0zWnATDkEBGRZ2C46cRgDjc2DDlERORpGG46wXDTiiGHiIg8BcNNJxhu2mPIISKigY7hphMMNx1zFXL8VH5YMmIJfjn6lwjXhru5hkRENFgx3HSC4ebiXIUctUKNG4feiDvH3IlY/1g315CIiAYbhptOMNx0nUVYsL1wO94++jaOVB4BAChlSlyXeh3uHnM3UoNT3VxDIiIaLBhuOsFw031CCOwv24+3jr6FfaX7AAAyyDAncQ5+NfZXSAtPc3MNiYjI2zHcdILh5tIcqzyGt4++je8LvreXZcRkYOm4pZgcNRkymcyNtSMiIm/FcNMJhpvecabmDN499i425m20v4V8XMQ43JV2F2YmzIRCrnBzDYmIyJsw3HSC4aZ3FTcWY82xNfjy9JcwWAwAgMSARNw2+jbMHzofWqXWzTUkIiJvwHDTCYabvlHZXImPT3yMdbnrUG+oBwAEq4OxeMRiLBm5hLeRExHRJWG46QTDTd/SGXX48syX+OD4ByhuLAYA+Mh9cMOQG3Bb2m1IDeIdVkRE1H0MN51guOkfZosZ3xd8j/dy3sPRyqP28pnxM3Fb2m3sfExERN3CcNMJhpv+JYRAVkUW3st5D9sKt0FA+nNLC0vDbaNvw9VJV0OlULm3kkRENOAx3HSC4cZ98uvy8cHxD/D12a+hN+sBABHaCPx8xM/x0+E/Zb8cIiLqEMNNJxhu3K+6pRrrctfh37n/RmVzJQBAJVdhbspc/GLUL5AWxocCEhGRM4abTjDcDBxGsxHfnf8OH5/42P56BwCYGDkRvxj1C8xJnAOVnJesiIiI4aZTDDcD05ELR/DxyY+xKX8TTBYTACDSNxJLRizBTcNvQqgm1M01JCIid+rXcKPX66FWqy9lE/2K4WZgu6C7gM9OfYZ1uetQ3VINQLqVfG7KXCwesRhjwsfwLisiokGoT8PNpk2b8Mknn2Dnzp0oKCiAxWKBr68vJk2ahMzMTNx5552IjY29pB3oSww3nsFgNmBT/iZ8dOIj5FTl2MtHhY7Cz0f8HNelXAdfla8ba0hERP2pT8LNV199heXLl6Ourg7XXXcdLrvsMsTFxUGr1aK6uhrHjh3Dzp07sXfvXtxxxx147rnnEBER0Ss71JsYbjyLEAJHKo9g3cl12JS/yf6KB3+VP24YcgN+PvznGBoy1M21JCKivtYn4eayyy7Dk08+iXnz5kEul3e4XHFxMf7xj38gKioKjz76aPdq3g8YbjxXTUsN1p9dj3/n/hsFDQX28kmRk/DzET/H1UlXw0fh48YaEhFRX/GYDsU7duzASy+9hIMHD6K0tBRffvklFi5c2Ok627dvxyOPPIKcnBzExsbi97//PZYtW9bl72S48XwWYcG+0n34LPczbC3can8reagmFAuHLsRPh/8UCQEJbq4lERH1pu6cvztugukHTU1NGD9+PF599dUuLZ+Xl4frrrsO06dPR1ZWFv7whz/ggQcewOeff97HNaWBRC6T44rYK/D3WX/Hpps24bcTfotI30hUt1Tj3WPvYt4X83DPd/fg27xvYTAb3F1dIiLqZ11uuXnkkUe6vNGXX365+xWRyS7acrN8+XKsX78eJ06csJctW7YMhw8fxt69e12uo9frodfr7Z/r6+uRkJDAlhsvY7KYsKNoB/6d+2/sLtltLw9SB+GG1Btw47AbMTxkuBtrSEREl6I7LTfKrm40KyvL6fPBgwdhNpsxYsQIAMCpU6egUCiQnp7egyp3zd69e5GZmelUds011+Cdd96B0WiEStX+gW8rV67Es88+22d1ooFBKVdiduJszE6cjaKGInx15it8deYrlOvK8eGJD/HhiQ8xNnwsFg1bhLkpc+Gn8nN3lYmIqI90Odxs3brVPv3yyy8jICAA77//PkJCQgAANTU1uPPOOzF9+vTer6VVWVkZoqKinMqioqJgMplQWVmJmJiYduusWLHCqdXJ1nLT64QAPv0FEDsRGL8ECE7s/e+gLokPiMd9E+/Db8b/BntK9uDLM19ia8FWHK08iqOVR/Hi/hdxTfI1WDRsESZETOBzc4iIvEyXw42jv/3tb/juu+/swQYAQkJC8Oc//xmZmZl9epdU2xOR7apaRycotVrdPw8ZLD0M5G6Uhq3PA8nTgQm3AKPnAz5sJXAHhVyB6fHTMT1+Oqqaq/DN2W/wxZkvkFeXZ2/ZSQlKwcKhC3F96vWI9I10d5WJiKgX9KhDcX19PcrLy9uVV1RUoKGh4ZIr1ZHo6GiUlZW1+06lUomwsLA++94uCR8O3PgmkHIVABmQvxP4ahnw1+HAV/cC+bsAi8W9dRzEwrRhuGPMHfh6wddYO3ctFgxZAK1Si7y6PPz94N9x9X+uxrLNy7Dh3AY0m5rdXV0iIroEPWq5ufHGG3HnnXfib3/7Gy6//HIAwL59+/C73/0OixYt6tUKOsrIyMA333zjVPbdd99h8uTJLvvb9CsfX2D8YmmoLQSOfApkfwxUnwOyP5SG4CRgwi+ky1Yhye6t7yAlk8kwMXIiJkZOxOOXPY5v87/F+rPrkVWRhd0lu7G7ZDf8VH7ITMrE/CHzMSlqEuQyt95USERE3dSj59zodDo89thjePfdd2E0GgEASqUSd999N1566SX4+XXtMkxjYyPOnDkDAJg4cSJefvllzJo1C6GhoUhMTMSKFStQXFyMtWvXApBuBR8zZgx+/etfY+nSpdi7dy+WLVuGTz75BDfddFOXvrNfn3MjBFD4I5D9EXDsS8Dg0KqVdCUw4WZg1HxAw7u23K2gvgDfnPsG35z9BsWNxfbyOP843DDkBsxPnY+EQD47h4jIXfrtIX5NTU04e/YshBAYOnRol0ONzbZt2zBr1qx25bfffjvee+893HHHHcjPz8e2bdvs87Zv346HH37Y/hC/5cuXe8ZD/Aw64OQGKeic2wbA+s+u1ADDrwXG/RwYejWg5BN23ckiLDhUfgjrz67Hd+e/Q5OxyT5vUuQkXD/kemQmZSJIHeTGWhIRDT4e84RidxgQTyiuKwIOfwocWQdUnmot1wQDaQuBsT8HEjOATl5zQX2v2dSMHwp+wPqz67GvdB8sQuozpZQrcWXclZiXMg9XJVwFrVLr5poSEXm/fgk3+/fvx2effYaCggIYDM5Pgf3iiy96ssl+MSDCjY0Q0l1WRz8Djv4HaHToLB2UAIy5SWrRiUpzXx0JAFDeVI4NeRuw4dwGnKppDaS+Sl/MTpyNeanzMDVmKlRyN/f9IiLyUn0ebj799FPcdtttyMzMxObNm5GZmYnTp0+jrKwMN954I9asWdPjyve1ARVuHFnM0h1WRz4DTqwH9PWt8yLTgHE/k8IOn5/jdqdrTuP/8v4PG/M2OvXPCdWEIjMpE/NS52F8xHg+P4eIqBf1ebgZN24cfv3rX+Pee+9FQEAADh8+jJSUFPz6179GTEzMgH4i8IANN46MzcCpTVKLzqlNgMXYOi9uMpB2o3T5KijebVUk6RlLhy8cxsa8jdiUvwnVLdX2eXH+cZibMhfXJF+DESEjGHSIiC5Rn4cbPz8/5OTkIDk5GeHh4di6dSvGjh2LEydOYPbs2SgtLe1x5fuaR4QbR801wPGvpctW+btg74gMAAlTpaAzegEQGOu2KpL0bqsfS3/ExryN2HJ+C3QmnX1eYkAiMpMzkZmUiZGhIxl0iIh6oM/DTUJCAjZu3IixY8di/PjxePzxx3HzzTdj7969uPbaa1FXV9fjyvc1jws3jhrKpUtWOV8C5/fAKegkZrQGnYBot1WRgBZTC7YXbce3ed9iZ/FO6M2tL25NDEjE1UlX45rkaxh0iIi6oc/DzS9+8QtMnjwZjzzyCJ5//nn84x//wIIFC7B582ZMmjSJHYr7Q30JcNwadAr3OcyQAUnTpMtWoxcA/nylgDvpjDrsKNqBTfmb2gWdhIAEZCZlIjM5E6NCRzHoEBF1os/DTXV1NVpaWhAbGwuLxYK//vWv2LVrF4YOHYonn3zS6Z1TA43XhBtHdcXSpaucL4Gi/7WWy+RS0Bl1AzByHvvouJkt6Hx3/jvsKNrhFHTi/eORmZyJa5KvYdAhInKhT8ONyWTCRx99hGuuuQbR0Z53+cMrw42j2oLWoFN80Hle7ERg5PVS2IkY4Z76EQDnoLOzaCdazC32eXH+cZidOBuzE2ZjYuREKOQKN9aUiGhg6POWG19fX5w4cQJJSUk9rqS7eH24cVSTD5z4L3Dyv0DBPjj10Qkfbg061wOxkwC2FLiNzqjDjuId+C6/fdAJUYdgZsJMzE6cjctjLodGqXFjTYmI3KfPw82sWbPw4IMPYuHChT2to9sMqnDjqLFCev3Dyf8C57Y7314eGCddthp5vXQZS9Gj96lSL9AZddhbshffF3yP7UXbUW9ofd6RVqnFtNhpmJ04GzPiZ/AVEEQ0qPR5uPnss8/w+OOP4+GHH0Z6enq7d0qNGzeuu5vsN4M23DhqqQNObwZOfCONHd6fBG0IMHwuMPI6IHUWoPZ3Xz0HOaPFiEPlh/BDwQ/4ofAHlDW1PsFaIVNgcvRkzE6YjdmJsxHt53mXiImIuqPPw43cxTuPZDIZhBCQyWQwm83d3WS/Ybhpw9givcjz5DfAyY1Ac+uD6KDwAZKnAyPmAsOv4dOR3UgIgePVx6WgU/ADztSecZo/Omw0ZsbPxIyEGRgVOgpyGd9LRkTepc/Dzfnz5zudP5D74jDcdMJsAgr2SpevTv2f1GfHUWSaFHKGXwvETwbY0dVtCuoL7C062RXZEA79qSK0EZgePx0z4mcgIyYDvipfN9aUiKh38K3gnWC46SIhpDeW5/6f9AqIwn2A9a3YAADfMGBYphR2hswBNPy3dJfK5kpsL9yOHUU7sLd0L5pNzfZ5KrkKU6KnYEb8DMyIn4GEgAQ31pSIqOf6JNzs3bsXGRkZXapAU1MT8vPzkZY28N5mzXDTQ7pq4MwW4NS3wOktgN7hKdRypdQRefi1wLCrgbChvPvKTQxmAw6UHcCO4h3YXrgdRY1FTvNTg1LtQWdC5AS+xZyIPEafhJthw4YhOTkZS5cuxXXXXQd///YdTY8fP44PP/wQa9aswYsvvohbb721Z3vQhxhueoHZKN1afupbqVWn6rTz/OBEYOhPpCFlBqAOcE89BzkhBPLq87CjcAd2FO/AofJDMIvW/nABqgBcEXcFpsVOwxWxVyDKL8qNtSUi6lyfhBuj0YjVq1fj1VdfxdmzZzF8+HDExsZCo9GgpqYGJ0+eRFNTExYtWoQVK1ZgzJgxvbIzvY3hpg9UnW0NOgV7AbOhdZ5cKb33augcKexEjWGrjpvUG+qxp3gPdhTtwM7inajV1zrNHxo8VAo6cVcgPSodaoXaPRUlInKhz/vcHDp0CDt37kR+fj6am5sRHh6OiRMnYtasWQgNDe1xxfsDw00fMzRJby8/s0Uaqs85z/ePkvroDJ0DDJkN+A7svxdvZbaYcbTyKHYV78Kekj04VnnMqVOyRqFBenQ6psVOw7TYaUgJSuErIYjIrdihuBMMN/2s6ixw9gcp6OTtAIw6h5kyIC5dCjmpM4H4KYDSx101HdRqW2qxr3Qfdpfsxp7iPahornCaH+0Xbb98dXns5Qj04W+HiPoXw00nGG7cyKSXLlud2QKc+QGoyHGer/KVOianXiWFncg0wMUzlahvCSFwpvYM9pTswe7i3ThYfhAGS+ulRrlMjjFhYzA1ZiqmxkzFhMgJvIRFRH2O4aYTDDcDSF0xcPZ76SGC57YDukrn+b7hUofk1JnSEDJwn5/kzZpNzThYfhC7i3djT8kenKtzvtSoVqgxIXICLo+5HFOjp2J02Gi+7JOIeh3DTScYbgYoiwWoOG4NOtuA83ucXwsBACHJrUEneQbgF9bv1SSgrKkM+0r34cfSH/Fj6Y+40HzBaX6AKgCToydjasxUXB5zOVKDUtlfh4guGcNNJxhuPITJABQfaG3VKdoPiDav9YgaAyRfKQ1J09g52Q2EEMiry7OHnf1l+9FgbHBaJlwbjsuiL8PlMZdjcvRkxPvHM+wQUbf1abgxGo3IzMzE6tWrMXz48EuqqDsw3HiolnqpNSdvuxR4Ko63XyYyzTnssGWn35ktZpyoPmEPO1kVWdCb9U7LRPlGYXL0ZEyOkoakwCSGHSK6qD5vuYmIiMCePXswbNiwHlfSXRhuvERjhXTL+fnd0vjCyfbLRKYBydMcwk54/9dzkNOb9ThccRg/lv2I/5X+D8eqjsFkMTktE64NtwedydGTeRmLiFzq83Dz6KOPQqVS4YUXXuhxJd2F4cZLNV5oDTr5u4ALJ9ovEzlaCjmJl0sPFgyK6/96DnLNpmYcvnAYB8oO4ED5ARy5cARGi9FpmVBNKNKj0pEelY7JUZMxLGQY33JORH0fbu6//36sXbsWQ4cOxeTJk+Hn5+c0/+WXX+7uJvsNw80g0VTpHHZcXcYKSrAGncuBhMuByFF803k/05v1OHLhCA6UH8DBsoM4fOEwWswtTssE+gRifMR4TIyciAmREzAmfAy0Sq2bakxE7tLn4WbWrFkdb1Amww8//NDdTfYbhptBqqkKOL9LeidWwV6g9Ej7DsrqICDhMiBxqtSyE5cOqHgS7U9GsxHHqo7ZW3ayKrKc3nIOAEqZEqPCRmFC5ARMjJyIiZETEa7lJUcib8e7pTrBcEMAAH2jdDdWwY9S2CnaDxganZeRq4CY8a2XsRIvZ7+dfma0GHGq+hSyKrKQVZGF7Irsdk9PBoCEgAR7y87EiIlIDU7lpSwiL9Ov4aaoqAgymQxxcZ7Rf4Hhhlwym4DyY0ChNewU7AMaStsvFzpEek1E/GRpiBoDKFT9X99BSgiBkqYSHCo/hOyKbGRdyMKZmjNO78UCnC9ljY8Yj7TwNPip/DrYKhF5gj4PNxaLBX/+85/xt7/9DY2N0v/tBgQE4NFHH8UTTzwB+QB+ZD7DDXWJEEBtQetlrMIfXffbUWqA2InSJaz4KdLAjsr9qt5QjyMXjthbdo5WHm13KUsukyM1KBXjIsZhbPhYjA0fi6HBQ/kkZSIP0ufhZsWKFXjnnXfw7LPPYtq0aRBCYPfu3XjmmWewdOlSPP/88z2ufF9juKEe01UDxYekS1jFB6RxS1375QJirC07U4C4yUDsBMCHrQb9pe2lrKOVR1Ha1L4VTqvUIi0sDWMjxmJcuBR6ovyi3FBjIuqKPg83sbGxeOONNzB//nyn8q+//hq//e1vUVxc3N1N9huGG+o1FgtQfRYosgadov1AeU77jsoyBRCVJgWeuHSppSd8BKBQuqfeg1BlcyWOXDiCo5VHcfTCURyrOoamtq/3ABDpGykFnQipdSctLA2+Kl831JiI2urzcKPRaHDkyJF2TyjOzc3FhAkT0Nzc3MGa7a1atQovvfQSSktLkZaWhldeeQXTp093uey2bdtc3ql14sQJjBw5skvfx3BDfcqgA0qzW8NO0QHXfXeUWiBmnBR0YicCMROA8GG8Fb2fmC1m5NXl4WjlURypPIKjF47idO1pWITFaTnb5azRYaMxOmw00sLSMCJ0BG9FJ3KDPg83U6dOxdSpU/HPf/7Tqfz+++/H/v37sW/fvi5tZ926dbj11luxatUqTJs2DatXr8bbb7+N48ePIzExsd3ytnCTm5vrtGMRERFQKLp2UmC4oX5XV9wadkqypfDT9s4sAFD5SXdn2QJP7ASpA/MA7sPmTXRGHXKqcuytO0cqj6BC1/7OLAYeIvfo83Czfft2zJs3D4mJicjIyIBMJsOePXtQWFiIjRs3dtjy0tbUqVMxadIkvP766/ayUaNGYeHChVi5cmW75W3hpqamBsHBwd2tNgCGGxoAbJezSrJah9LDgFHXflmfACnkxE6QWndiJgChqQw8/aS8qRzHq47jePVxHK86jpzKHFS1VLVbzhZ40sLS7KGHgYeod/XLreAlJSV47bXXcPLkSQghMHr0aPz2t79FbGxsl9Y3GAzw9fXFZ599hhtvvNFe/uCDDyI7Oxvbt29vt44t3CQnJ6OlpQWjR4/GH//4x04fKqjX66HXt764r76+HgkJCQw3NLBYzEDlKWvYyZbGZUcAU0v7ZVV+QPQYIHocED1WGiJHAypNv1d7sBFCoEJXYQ88OZU5OF513GXgUcgUSA1OxajQURgRMgIjQkdgRMgIBGuC+7/iRF6gO+Gm2z0aHd8Kfil3RVVWVsJsNiMqyvnuhKioKJSVlblcJyYmBm+++SbS09Oh1+vxwQcfYM6cOdi2bRtmzJjhcp2VK1fi2Wef7XE9ifqFXCG9/iFyFDDhF1KZ2SS9ENSxhafiOGBskm5NL/yxdX2ZAogY0Rp2bMHHN9Q9++OlZDIZovyiEOUXhVmJ0v9U2QJPTpUUdI5XHUdOVQ6qW6pxuuY0TtecdtpGtF80RoaMxIjQERgZOhIjQkYgLiCODx0k6kVueyt4SUkJ4uLisGfPHmRkZNjLn3/+eXzwwQc4edLFW55duOGGGyCTybB+/XqX89lyQ17FbAKqzkitOmVHgLKj0qskmqtdLx8YL3VctoWeqDQgOJmXtfqYEALlOumSVm5NLnKrc3Gy+iSKG13fSeqn8rO37tgCz9CQoVAr1P1cc6KBq09bbgDgtttuwzvvvHNJbwUPDw+HQqFo10pTUVHRrjWnM5dffjk+/PDDDuer1Wqo1fwPBHkJhRKIHCkN434ulQkB1JdIQccx9NTkA/VF0pC7sXUbKj/rNkZLQ9RoIDIN8I9wyy55I5lMhmi/aET7RWN24mx7eYOhAadqTuFk9Ul74DlTewZNxiYcqjiEQxWH7MsqZAqkBKVgWPAwDA0ZiqHBQzEsZBji/NnKQ3QxPQo3BoMBb7/9NjZv3tzjt4L7+PggPT0dmzdvdupzs3nzZixYsKDLdcnKykJMTEzXK0/kbWQy6anIQXHAiGtby1vqgLJj1tBzFCg7DFw4JV3WKj4oDY78IqxhJ816iSxNCkF8AGGvCfAJQHpUOtKj0u1lRosR+XX5rYGnRhrX6mtxpvYMztSeAfJbt6FVajEkaAiGhQzD0OChGBoyFMNDhiNMEwaZTNb/O0U0ALn1reC2W8HfeOMNZGRk4M0338Rbb72FnJwcJCUlYcWKFSguLsbatWsBAK+88gqSk5ORlpYGg8GADz/8EC+88AI+//xzLFq0qEvfybulaFAzm4Dqc0BFDlB+XOrDU54jtfLA1X8KZEBIsjXwjJZCT1SadIs6H0LYZ2z9eHJrcnGm9gxO15zGmdozOFd7DgaLweU6wepge+uO4zjAJ6Cfa0/UN/r0spTZbMYzzzyDsWPHIjT00jorLl68GFVVVfjTn/6E0tJSjBkzBhs3bkRSUhIAoLS0FAUFBfblDQYDHnvsMRQXF0Or1SItLQ0bNmzAddddd0n1IBo0FEogYrg0pLW2mMLQJHVedgw8FceBpgtATZ40nPxv6/JyFRA2VNpO+AipM3PECCBsGO/a6gWOHZdnxLfeLGGymFDQUIAzNWecQk9BQwFq9bU4UH4AB8oPOG0r2i8aQ4OHIjUoVRqCpXGQOqi/d4uo3/T4CcUnTpxASkpKX9SpT7HlhqgbGi9IIccx8FSclC5tuSKTA8FJrWEnfAQQMVJ6+rKGv7e+0mJqwbm6c9JlrJozOFV7CmdqzqBcV97hOqGaUKfAkxKUgtSgVET5RvHyFg1Iff6cmylTpuCFF17AnDlzelxJd2G4IbpEFovUSfnCKam1pzIXuGAdWmo7Xi8gtjX02IJP+HDAL1zqN0S9rt5Qj7O1Z3G65jTy6vJwru4cztWdQ1mT68dtANKdWymBKVLYcQg9CQEJUMp5KZLcp8/DzXfffYfly5fjueeeQ3p6ersOxQM5NDDcEPURIaTLWBdOtoadylwpBDV2fDKFJki6xGUfhkjj0CGA2r//6j+I6Iw6p7BzrlYaFzYUwtz2xa9WSrkSSQFJSA5KRlJgktPAzszUH/o83MgdnpHh+ActhIBMJoPZ7PrHMRAw3BC5QXOt9ARmW/CxTdcWwnVHZquAmDbBxzqEJAEKVX/VftAwmo0oaChoF3zy6/PRbOr4hcj+Kn8kBiYiKTAJyYHO4Ycdmqm39Mu7pTpz1VVXdXeT/YbhhmgAMbZId29VnbEOZ1undZUdrydTSHdxhQ2V+vOEpkjv3ApJAYISeCdXL7MIC8qaynCu7hzO1593GkoaSyA6CaihmlAkBya3Cz8JAQnQKNn5nLquX94t5akYbog8hK66TfBxCECuXjJqI1dKASc0VQo9ISmt45BkwMe333ZhMNCb9ShqKEJ+fT7O159HQX2BfbqyuZOACiBCG4GEgATEB8QjISDBPsQHxCNEHcJLXeSkX8LNzp07sXr1apw7dw6fffYZ4uLi8MEHHyAlJQVXXnlljyreHxhuiDyc7YnMjoGn+hxQnSc9r8es73z9gJjWwNM2/PBdXL2q0dCIgoYCnK8/7xx+6vLRYGzodF0/lZ9T2EkISEC8vzSO9otm5+ZBqM9fv/D555/j1ltvxS233IJDhw7Z393U0NCAv/zlL9i4ceNFtkBE1EOOT2RObXMJ3GIBGkqlsFOTZw081nF1HqCvk+Y3lAIFe9pvWxMEBCdKt7MHJ0nTIdZxcCKgZv+R7vD38cfosNEYHTbaqVwIgTp9HYoai1DYUNhuqNBVoMnYhJPVJ3Gyuv17BpUyJWL9Y+3BJ9Y/FrH+sYjzi0OsfyxCNaFs9RnketRyM3HiRDz88MO47bbbEBAQgMOHDyM1NRXZ2dm49tprO3yr90DAlhuiQUoIoLnGIfCccw4/nd3RZaMNbQ06IQ4BKDgJCE7gqyp6SYupBSWNJS6DT3FjMYwWY6fraxSa1sDjH8fw4yX6vOUmNzcXM2bMaFceGBiI2tranmySiKhvyWTSZSffUCA+vf18QxNQWyANNeeB2vPWz9Zxc4309vXmaqA02/V3+IY7t/QEJ0r9f4LipUHDpwJ3hUapkZ6kHJzabp5FWFChq3AKOyWNJShpLEFxYzEqdBVoMbfY7/ZyuX2FBjH+MU6BxzEEhWpC+XJSD9ejcBMTE4MzZ84gOTnZqXzXrl1ITW3/x0hENOD5+FlfGDrK9fyW+tbw4xh6bEFIXy/d4aWrbP9SUvt3BFiDTpw0Doxv8zkOUKr7bh+9gFwmt79xfUr0lHbzjWYjyprKUNxUbA88rsJPXl0e8uryXH6HSq5ClG8Uov2iEeMXY/++aL9oe3mgTyBbfwawHoWbX//613jwwQfx7rvvQiaToaSkBHv37sVjjz2Gp556qrfrSETkfppAIHqMNLjSXOvQ2mMLPQXS05zriqSWH0MDcOGENHTEL9JF+HEY/CIBOVsVOqJSqJAQmICEwASX812Fn9LGUikENZWgvKkcRosRRY1FKGos6vB7fJW+TqEn2jfa+bNfNLRKbV/tJl1Ej++WeuKJJ/D3v/8dLS0tAAC1Wo3HHnsMzz33XK9WsLexzw0RuYWhCagrbg07dcXS2PFzJw/Ks5MrAf9oICAaCIyRXmvhNLYOfLpzjxgtRlzQXUBZUxnKmspQ2lQqTevKUN5UjrKmMtToa7q0rSB1EGL8YhDpGykNWmkc4RuBKN8oRPpGIlgdzBagLuq359zodDocP34cFosFo0ePhr//wP8xMdwQ0YAkhPRsH6fwUwjUF7d+bigBhKVr21MHSiHHVfCxlflHAnJF3+6XF2o2NUtBR9cagGzBx/ZZZ+rkWUwOVHKVFHi0Ea0hqM0QoY2Ar4rPZ+JD/DrBcENEHstsAhrLW29nry+VAo/TuBQwNHZtezIF4B9lbQWKbZ32j5Sm/SOlViK/CEDp07f75kWEEGgwNtjDToWuAhd0F1CuK8eF5guo0FWgQleB6pbqLm8zQBWACN+IdqEnwjcC4dpwhGvCEaYN8+oQxHDTCYYbIvJ6+oaOg099CdBQJt363tVWIEC6Dd5V8LFN2+ZpgvmW9y4ymo1OYadCV4GK5tZpWyDq7L1ebfkqfaWwo5XCjm3aqUwTjlBtKFRyz3o/G8NNJxhuiIgAWMxAY4Vz8Gkstw4V1haicqCpArCYur5dhY818EQ5hKAowC9cagGyD+FSEGLn6E4JIdBkbEKFrqJdy0+FrgJVzVWobK5EZXMlWswt3dp2iDqkwwAUpglDmDYMoZpQBKuDB8QToRluOsFwQ0TUDRaLdKdXY7nU2uMYfJzCUBnQUte9bcsUDqEn3Dn42KZ9w1s/+/ixVagDQgjoTDp70LENjuHH9rmqpQpmYe7ytmWQIVgdjFBNKEK1odLYYQjThDmV+6v8+6STNMNNJxhuiIj6iLFFaulprLBe+nJoBdJVAk2VQNMFaehuEAIApbZN+HEIPr7hgG9Y64MafcOkTtUMQ+1YhAW1+toOA1BlcyWqW6pR3VKNmpaaTt/67opKrkKcfxy+ufGbXq13nz+hmIiIqB2VpvXJzBdjMrQJPA7Bx3FaVwk0XpBukzc1A3UF0tAVcqXUV8gWdrQhDgEozDovzDkUqYO8/lKZXCa3t7IMDxne6bJmixm1+lp72LENVc1VrdMtVahulqZ1Jh2MFuNFX5HR1xhuiIio/yl9pDu0AmO7tryhqU3wcRGKmqsBXQ2gqwKMTVJfoaYKaegqmbxNIAptDT7aUCkgaYOl/kK2aW0I4OPvla1ECrlC6oOjDevS8s2mZtS01HSrE3RfYLghIqKBz8dPGkKSu7a8scUadqqk5wfpqqyfq1s/28uqpFBkaJDuILO9RqM75Epr4AmWwk676RDXnzXBUouXl9AqtdD6u//JzAw3RETkfVQaQNWNliEAMOmlztO24OMqFLXUSq/aaK6xTtcAZoPUStSTUARIfYlcBR91oPTaD02QdTpI+myftpbzGUTtMNwQEREB0ktLA6yvtugqIQBjc2vQaRt8mms7ntdSJ7UUmZqBhmbpdvwe1VvbJgS5CkRBLsKRdewT4HX9jBhuiIiIekomA3x8paE7rUSAdJu9ocFF8LFO6+ult9Hr66Ug1GId28oNDdJ2TM1AY7N0V1rPdgJQB1gDUYDz4OMvhSF7mb91HNhmGeu0YmA8GJDhhoiIyB3k8tbLSyE9WN9ibg069tBT1yYQ1XUcjlrqALMegJDK9PWXvk9KrRSAAuOAX2+/9O31tBpu+2YiIiLqObnC2j+nJ8nIyqR3CD110qs7LjYYGq1hyKHMZH06su2WfaV7O0kz3BAREQ1WSjXgHyENl8JsdA473XllRx9guCEiIqJLo1C1Pg9oAPCu7tFEREQ06DHcEBERkVdhuCEiIiKvwnBDREREXoXhhoiIiLyK28PNqlWrkJKSAo1Gg/T0dOzcubPT5bdv34709HRoNBqkpqbijTfe6KeaEhERkSdwa7hZt24dHnroITzxxBPIysrC9OnTMXfuXBQUFLhcPi8vD9dddx2mT5+OrKws/OEPf8ADDzyAzz//vJ9rTkRERAOVTAgh3PXlU6dOxaRJk/D666/by0aNGoWFCxdi5cqV7ZZfvnw51q9fjxMnTtjLli1bhsOHD2Pv3r1d+s76+noEBQWhrq4OgYGBl74TRERE1Oe6c/52W8uNwWDAwYMHkZmZ6VSemZmJPXv2uFxn79697Za/5pprcODAARiNRpfr6PV61NfXOw1ERETkvdz2hOLKykqYzWZERUU5lUdFRaGsrMzlOmVlZS6XN5lMqKysRExMTLt1Vq5ciWeffbb3Kk5EROShhBCwCMAiBMwWAYv1s9kiYLEImIW1zAJp2rqMtGzr+rZ1hW1bQrRu2yKgVMiRnnQJ77y6RG5//YJMJnP6LIRoV3ax5V2V26xYsQKPPPKI/XN9fT0SEhJ6Wl0iIupHFouAyXoiNVmkk6zZImCyWGCxwGlstp6cTebW5W3rm9sM9jIhYLZYYLbAaWyytJ6ozdaTuxBCmi9s08IhAMAhLEjL2YOBsAUHWINDa1hwDhnWaQuc1nPcdrtAIoRDHaVzYmt9Ya+jEK3f2R+iAtX48Q8/6Z8vc8Ft4SY8PBwKhaJdK01FRUW71hmb6Ohol8srlUqEhYW5XEetVkOtVvdOpYmI3MB2YjLZBrPFOpZO8vaxvayjZdpM25ex2LdttggYzRbr2HGeVGYyt548HcODyxDRLmBYnOaZ22zLVQCh/ieTAXKZDAqZDHK547QMcus8mUwGhXWe9BlQyFunw/3ce951W7jx8fFBeno6Nm/ejBtvvNFevnnzZixYsMDlOhkZGfjmm2+cyr777jtMnjwZKpWqT+tLRJ7LdsKWhi5Om6zTFtfTJouAwcW00SyFB4N12hYSnEKDNVC0DRK2FglbKLHN40m+PZkMUFpPpkq5dOJVymVQyOVQyAGlXA65bSyTxgq5rN2gdPwsa522bc928rafyB2Wk8ngMC0to7Cf+NsvI20L9u23DQ0KF99nL7N+r1wGadohaDivJ60rk7Wpp3V9e91kMsjkruvW2dUTT+HWy1KPPPIIbr31VkyePBkZGRl48803UVBQgGXLlgGQLikVFxdj7dq1AKQ7o1599VU88sgjWLp0Kfbu3Yt33nkHn3zyiTt3g2jQM5ktMJgtMJikQW890TuWGUwW6Nt8dppvdlHmsB3byd5xWvosBYXOwoq3ZgPbiVmlkFvHthO23D5tm6dUyKG0nrDbLW+f52o9mX2eUi6DQiFzChUKhRyKdgGjTWBQyOzLuA4YUiBRyOVOy9vCR7vtWk/2RB1xa7hZvHgxqqqq8Kc//QmlpaUYM2YMNm7ciKSkJABAaWmp0zNvUlJSsHHjRjz88MN47bXXEBsbi3/+85+46aab3LULRG4jhPR/+3qTGS1GC/QmM/QmC/RGC1pMZuitZU7zTBbojdK0qyBh+6y3T5utAUO0n28y2z97WniwnTR9FHKolHL7Cd/HYVqllEN10WnpxOyjlEJB22mVwjFIOAYKOZQKGVRy55DhuIxS7mo96bPtRO8N/4dN1Bfc+pwbd+Bzbqi3CSFdgmgxWtBiNKPZYEaz0YwWa4iwjW3BosUhYOgd5zkGEaeA4iKkWOcPxF+vTAb4WIOCWim3T9sH+2cFfBSyNmVy+CgU9mm1sjUgSIPraaXCGlTaTLcNJY6tFkTkWbpz/nb73VJEfUUIAb3JYg8btsAhBRCL/bN9bJAChNNnU2tY0VvnNVvn6R3mDYSWC7U1DGhUCqhVcqiVitbPDvPsocNFkLCFDJXCOYyoXYYT53mOLR9sUSAid2K4IbeyWAR0RjN0BhN0ejN0BjOajSY0tZluNpjRZDCh2SCV26abDGY0G0zSsg4tJtLY0u/7I5cBvj5Ke6DQqBzDhQIaW+hQydsEj87nOYcV5zKNSgoZDBRERBKGG+oSWytIo96EJr3JOjbbp6XQYbKGDecgorOGD1fT/RVAfBStQUPro4BWpYBGJQUDrbVMYy3T2gYfKUw4Lm8f+zisq1JA46OARqmASsFWCyIid2O48WJmi0CTQQojUggxo7HFZA8oTQaHab0ZjXoTGltclzfpTX16O6pMBviqFND6KOGnlgKDr48CfmoltCrr2EcBX5UCvmqlNM9HWt7XR1pW2ya42AOLUg6lwq3viCUion7EcDMAWayhpKHFNhjR0GJCvXXsWGYbN1rDSpPejIYWKYw0G819Uj9b6PBXS0HE10cJPx9r6LCGEvu0ujV8+Pp0PK1R8bIKERH1DoabXtaTYOI4v77FiEa9qVfvglHKZU5hxDYtfb5YuRL+1nl+aiX8fJS804SIiAY0hpteUlzbjGtf2dGrwUQplyFAo0SARmUdt04HalQItH721ziHEj+1wimgqJVsFSEiosGD4aaX+KoUaGgx2T93FEwC7eHEcV7bZaQxL9UQERF1H8NNLwnSqrDlkasYTIiIiNyM4aaXyOUyDI30d3c1iIiIBj3eH0tEREReheGGiIiIvArDDREREXkVhhsiIiLyKoOuQ7GwPoSmvr7ezTUhIiKirrKdt0UXHiY36MJNQ0MDACAhIcHNNSEiIqLuamhoQFBQUKfLyERXIpAXsVgsKCkpQUBAQK8/h6a+vh4JCQkoLCxEYGBgr257oPD2ffT2/QO4j97A2/cP8P599Pb9A3p/H4UQaGhoQGxsLOTyznvVDLqWG7lcjvj4+D79jsDAQK/9Y7Xx9n309v0DuI/ewNv3D/D+ffT2/QN6dx8v1mJjww7FRERE5FUYboiIiMirMNz0IrVajaeffhpqtdrdVekz3r6P3r5/APfRG3j7/gHev4/evn+Ae/dx0HUoJiIiIu/GlhsiIiLyKgw3RERE5FUYboiIiMirMNwQERGRV2G46SWrVq1CSkoKNBoN0tPTsXPnTndXqcdWrlyJKVOmICAgAJGRkVi4cCFyc3Odlrnjjjsgk8mchssvv9xNNe6eZ555pl3do6Oj7fOFEHjmmWcQGxsLrVaLmTNnIicnx4017r7k5OR2+yiTyXDvvfcC8Mzjt2PHDtxwww2IjY2FTCbDV1995TS/K8dNr9fj/vvvR3h4OPz8/DB//nwUFRX14150rLP9MxqNWL58OcaOHQs/Pz/ExsbitttuQ0lJidM2Zs6c2e64LlmypJ/3pGMXO4Zd+bscyMcQuPg+uvpdymQyvPTSS/ZlBvJx7Mr5YSD8FhluesG6devw0EMP4YknnkBWVhamT5+OuXPnoqCgwN1V65Ht27fj3nvvxb59+7B582aYTCZkZmaiqanJablrr70WpaWl9mHjxo1uqnH3paWlOdX96NGj9nkvvvgiXn75Zbz66qvYv38/oqOjcfXVV9vfS+YJ9u/f77R/mzdvBgD87Gc/sy/jacevqakJ48ePx6uvvupyfleO20MPPYQvv/wSn376KXbt2oXGxkZcf/31MJvN/bUbHeps/3Q6HQ4dOoQnn3wShw4dwhdffIFTp05h/vz57ZZdunSp03FdvXp1f1S/Sy52DIGL/10O5GMIXHwfHfettLQU7777LmQyGW666San5QbqcezK+WFA/BYFXbLLLrtMLFu2zKls5MiR4vHHH3dTjXpXRUWFACC2b99uL7v99tvFggUL3FepS/D000+L8ePHu5xnsVhEdHS0eOGFF+xlLS0tIigoSLzxxhv9VMPe9+CDD4ohQ4YIi8UihPDs4yeEEADEl19+af/cleNWW1srVCqV+PTTT+3LFBcXC7lcLr799tt+q3tXtN0/V/73v/8JAOL8+fP2squuuko8+OCDfVu5XuJqHy/2d+lJx1CIrh3HBQsWiNmzZzuVedJxbHt+GCi/RbbcXCKDwYCDBw8iMzPTqTwzMxN79uxxU616V11dHQAgNDTUqXzbtm2IjIzE8OHDsXTpUlRUVLijej1y+vRpxMbGIiUlBUuWLMG5c+cAAHl5eSgrK3M6nmq1GldddZXHHk+DwYAPP/wQd911l9PLYj35+LXVleN28OBBGI1Gp2ViY2MxZswYjzy2dXV1kMlkCA4Odir/6KOPEB4ejrS0NDz22GMe1eIIdP536W3HsLy8HBs2bMDdd9/dbp6nHMe254eB8lscdC/O7G2VlZUwm82IiopyKo+KikJZWZmbatV7hBB45JFHcOWVV2LMmDH28rlz5+JnP/sZkpKSkJeXhyeffBKzZ8/GwYMHB/wTN6dOnYq1a9di+PDhKC8vx5///GdcccUVyMnJsR8zV8fz/Pnz7qjuJfvqq69QW1uLO+64w17mycfPla4ct7KyMvj4+CAkJKTdMp72W21pacHjjz+OX/ziF04vJLzllluQkpKC6OhoHDt2DCtWrMDhw4ftlyUHuov9XXrTMQSA999/HwEBAVi0aJFTuaccR1fnh4HyW2S46SWO/0cMSAe9bZknuu+++3DkyBHs2rXLqXzx4sX26TFjxmDy5MlISkrChg0b2v1QB5q5c+fap8eOHYuMjAwMGTIE77//vr3zojcdz3feeQdz585FbGysvcyTj19nenLcPO3YGo1GLFmyBBaLBatWrXKat3TpUvv0mDFjMGzYMEyePBmHDh3CpEmT+ruq3dbTv0tPO4Y27777Lm655RZoNBqnck85jh2dHwD3/xZ5WeoShYeHQ6FQtEubFRUV7ZKrp7n//vuxfv16bN26FfHx8Z0uGxMTg6SkJJw+fbqfatd7/Pz8MHbsWJw+fdp+15S3HM/z589jy5Yt+NWvftXpcp58/AB06bhFR0fDYDCgpqamw2UGOqPRiJ///OfIy8vD5s2bnVptXJk0aRJUKpXHHte2f5fecAxtdu7cidzc3Iv+NoGBeRw7Oj8MlN8iw80l8vHxQXp6ervmws2bN+OKK65wU60ujRAC9913H7744gv88MMPSElJueg6VVVVKCwsRExMTD/UsHfp9XqcOHECMTEx9qZgx+NpMBiwfft2jzyea9asQWRkJObNm9fpcp58/AB06bilp6dDpVI5LVNaWopjx455xLG1BZvTp09jy5YtCAsLu+g6OTk5MBqNHntc2/5devoxdPTOO+8gPT0d48ePv+iyA+k4Xuz8MGB+i73SLXmQ+/TTT4VKpRLvvPOOOH78uHjooYeEn5+fyM/Pd3fVeuQ3v/mNCAoKEtu2bROlpaX2QafTCSGEaGhoEI8++qjYs2ePyMvLE1u3bhUZGRkiLi5O1NfXu7n2F/foo4+Kbdu2iXPnzol9+/aJ66+/XgQEBNiP1wsvvCCCgoLEF198IY4ePSpuvvlmERMT4xH75shsNovExESxfPlyp3JPPX4NDQ0iKytLZGVlCQDi5ZdfFllZWfa7hbpy3JYtWybi4+PFli1bxKFDh8Ts2bPF+PHjhclkctdu2XW2f0ajUcyfP1/Ex8eL7Oxsp9+lXq8XQghx5swZ8eyzz4r9+/eLvLw8sWHDBjFy5EgxceLEAbF/QnS+j139uxzIx1CIi/+dCiFEXV2d8PX1Fa+//nq79Qf6cbzY+UGIgfFbZLjpJa+99ppISkoSPj4+YtKkSU63TXsaAC6HNWvWCCGE0Ol0IjMzU0RERAiVSiUSExPF7bffLgoKCtxb8S5avHixiImJESqVSsTGxopFixaJnJwc+3yLxSKefvppER0dLdRqtZgxY4Y4evSoG2vcM5s2bRIARG5urlO5px6/rVu3uvy7vP3224UQXTtuzc3N4r777hOhoaFCq9WK66+/fsDsd2f7l5eX1+HvcuvWrUIIIQoKCsSMGTNEaGio8PHxEUOGDBEPPPCAqKqqcu+OOehsH7v6dzmQj6EQF/87FUKI1atXC61WK2pra9utP9CP48XOD0IMjN+izFpZIiIiIq/APjdERETkVRhuiIiIyKsw3BAREZFXYbghIiIir8JwQ0RERF6F4YaIiIi8CsMNEREReRWGGyIiIvIqDDdENCC89957CA4Odtv333HHHVi4cOElbyc3NxfR0dFoaGgA0Pf79dOf/hQvv/xyn22fyBMx3BBRjyUnJ+OVV15xdzUGlCeeeAL33nsvAgICAACLFy/GqVOn7POfeeYZTJgwode+76mnnsLzzz+P+vr6XtsmkadjuCGiPmU2m2GxWNxdjX5RVFSE9evX484777SXabVaREZG9vp3GY1GAMC4ceOQnJyMjz76qNe/g8hTMdwQeSmLxYL/9//+H4YOHQq1Wo3ExEQ8//zz9vlHjx7F7NmzodVqERYWhnvuuQeNjY32+bbLNH/9618RExODsLAw3HvvvfaT6syZM3H+/Hk8/PDDkMlkkMlkAFovw/z3v//F6NGjoVarcf78edTU1OC2225DSEgIfH19MXfuXJw+fbpb+1RUVIQlS5YgNDQUfn5+mDx5Mn788Ufk5+dDLpfjwIEDTsv/61//QlJSEmyv0MvJycG8efMQGBiIgIAATJ8+HWfPnnX5XUIIvPjii0hNTYVWq8X48ePxn//8p9P6/fvf/8b48eMRHx9vL3O8LPXee+/h2WefxeHDh+3/Zu+99x4AoK6uDvfccw8iIyMRGBiI2bNn4/Dhw/bt2Fp83n33XaSmpkKtVtv3a/78+fjkk0+69W9J5M0Yboi81IoVK/D//t//w5NPPonjx4/j448/RlRUFABAp9Ph2muvRUhICPbv34/PPvsMW7ZswX333ee0ja1bt+Ls2bPYunUr3n//fbz33nv2k/EXX3yB+Ph4/OlPf0JpaSlKS0vt6+l0OqxcuRJvv/02cnJyEBkZiTvuuAMHDhzA+vXrsXfvXgghcN1119nD0sU0NjbiqquuQklJCdavX4/Dhw/j97//PSwWC5KTk/GTn/wEa9ascVpnzZo1uOOOOyCTyVBcXIwZM2ZAo9Hghx9+wMGDB3HXXXfBZDK5/L4//vGPWLNmDV5//XXk5OTg4Ycfxi9/+Uts3769wzru2LEDkydP7nD+4sWL8eijjyItLc3+b7Z48WIIITBv3jyUlZVh48aNOHjwICZNmoQ5c+agurravv6ZM2fw73//G59//jmys7Pt5Zdddhn+97//Qa/Xd+nfksjr9dr7xYlowKivrxdqtVq89dZbLue/+eabIiQkRDQ2NtrLNmzYIORyuSgrKxNCCHH77beLpKQkYTKZ7Mv87Gc/E4sXL7Z/TkpKEn//+9+dtr1mzRoBQGRnZ9vLTp06JQCI3bt328sqKyuFVqsV//73v+3rBQUFdbhPq1evFgEBAaKqqsrl/HXr1omQkBDR0tIihBAiOztbyGQykZeXJ4QQYsWKFSIlJUUYDAaX699+++1iwYIFQgghGhsbhUajEXv27HFa5u677xY333xzh3UcP368+NOf/uRU1na/nn76aTF+/HinZb7//nsRGBhor7vNkCFDxOrVq+3rqVQqUVFR0e57Dx8+LACI/Pz8DutGNJiw5YbIC504cQJ6vR5z5szpcP748ePh5+dnL5s2bRosFgtyc3PtZWlpaVAoFPbPMTExqKiouOj3+/j4YNy4cU7fp1QqMXXqVHtZWFgYRowYgRMnTnRpn7KzszFx4kSEhoa6nL9w4UIolUp8+eWXAIB3330Xs2bNQnJysn396dOnQ6VSXfS7jh8/jpaWFlx99dXw9/e3D2vXru3wMhYANDc3Q6PRdGl/HB08eBCNjY0ICwtz+r68vDyn70tKSkJERES79bVaLQCpxYyIAKW7K0BEvc92suuIEMLeR6Ytx/K2QUAmk3Wpc7BWq3XajrD2DelOPVxtszM+Pj649dZbsWbNGixatAgff/yx051cF1vfkW0fN2zYgLi4OKd5arW6w/XCw8NRU1PT5e9x/L6YmBhs27at3TzH28gdw6gj26UrV8GHaDBiyw2RFxo2bBi0Wi2+//57l/NHjx6N7OxsNDU12ct2794NuVyO4cOHd/l7fHx8YDabL7rc6NGjYTKZ8OOPP9rLqqqqcOrUKYwaNapL3zVu3DhkZ2c79UFp61e/+hW2bNmCVatWwWg0YtGiRU7r79y5s0t9fGwdoQsKCjB06FCnISEhocP1Jk6ciOPHj3e6bVf/ZpMmTUJZWRmUSmW77wsPD79ofY8dO4b4+PguLUs0GDDcEHkhjUaD5cuX4/e//739Usq+ffvwzjvvAABuueUWaDQa3H777Th27Bi2bt2K+++/H7feequ903FXJCcnY8eOHSguLkZlZWWHyw0bNgwLFizA0qVLsWvXLhw+fBi//OUvERcXhwULFnTpu26++WZER0dj4cKF2L17N86dO4fPP/8ce/futS8zatQoXH755Vi+fDluvvlmp9aa++67D/X19ViyZAkOHDiA06dP44MPPnC6DGcTEBCAxx57DA8//DDef/99nD17FllZWXjttdfw/vvvd1jHa665Bnv37u008CUnJyMvLw/Z2dmorKyEXq/HT37yE2RkZGDhwoXYtGkT8vPzsWfPHvzxj39sdweYKzt37kRmZuZFlyMaLBhuiLzUk08+iUcffRRPPfUURo0ahcWLF9v7y/j6+mLTpk2orq7GlClT8NOf/hRz5szBq6++2q3v+NOf/oT8/HwMGTLkopdE1qxZg/T0dFx//fXIyMiAEAIbN27sUh8YQGrx+O677xAZGYnrrrsOY8eOxQsvvODUJwgA7r77bhgMBtx1111O5WFhYfjhhx/sd12lp6fjrbfe6vD7n3vuOTz11FNYuXIlRo0ahWuuuQbffPMNUlJSOqzjddddB5VKhS1btnS4zE033YRrr70Ws2bNQkREBD755BPIZDJs3LgRM2bMwF133YXhw4djyZIlyM/Pv2jYbGlpwZdffomlS5d2uhzRYCITHV0MJyLyQM8//zw+/fRTHD161C3fv2rVKnz99dfYtGlTv3zfa6+9hq+//hrfffddv3wfkSdgh2Ii8gqNjY04ceIE/vWvf+G5555zWz3uuece1NTUoKGhwf4Khr6kUqnwr3/9q8+/h8iTsOWGiLzCHXfcgU8++QQLFy7Exx9/3O5yFRENHgw3RERE5FXYoZiIiIi8CsMNEREReRWGGyIiIvIqDDdERETkVRhuiIiIyKsw3BAREZFXYbghIiIir8JwQ0RERF7l/wP7AP0qficCXAAAAABJRU5ErkJggg==", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "plt.subplot(211)\n", "plt.plot([ e[:3] for e in herr])\n", @@ -712,9 +822,18 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 50, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "You can open the visualizer by visiting the following URL:\n", + "http://127.0.0.1:7002/static/\n" + ] + } + ], "source": [ "robot = loadTiago(addGazeFrame=True)\n", "viz = MeshcatVisualizer(robot)" @@ -722,7 +841,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 58, "metadata": {}, "outputs": [], "source": [ @@ -741,12 +860,11 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 59, "metadata": {}, "outputs": [], "source": [ - "viz.display(q0)\n", - "viz.viewer.jupyter_cell()" + "viz.display(q0)" ] }, { @@ -758,27 +876,35 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 60, "metadata": {}, "outputs": [], "source": [ - "# Your code" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here is the solution if you need it." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp3/generated/control_head_gaze_loop" + "q = q0.copy()\n", + "herr = [] # Log the value of the error between gaze and ball.\n", + "# Loop on an inverse kinematics for 200 iterations.\n", + "for i in range(200): # Integrate over 2 second of robot life\n", + "\n", + " # Run the algorithms that outputs values in robot.data\n", + " pin.framesForwardKinematics(robot.model,robot.data,q)\n", + " pin.computeJointJacobians(robot.model,robot.data,q)\n", + "\n", + " # Placement from world frame o to frame f oMgaze\n", + " oMgaze = robot.data.oMf[IDX_GAZE]\n", + "\n", + " # 6D jacobian in local frame\n", + " o_Jgaze3 = pin.computeFrameJacobian(robot.model, robot.data, q, IDX_GAZE,pin.LOCAL_WORLD_ALIGNED)[:3,:]\n", + "\n", + " # vector from gaze to ball, in world frame\n", + " o_GazeBall = oMgaze.translation-ball\n", + " \n", + " vq = -pinv(o_Jgaze3) @ o_GazeBall\n", + "\n", + " q = pin.integrate(robot.model,q, vq * DT)\n", + " viz.display(q)\n", + " time.sleep(1e-3)\n", + "\n", + " herr.append(o_GazeBall) " ] }, { @@ -820,38 +946,67 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 62, "metadata": {}, "outputs": [], "source": [ "q = q0.copy()\n", - "herr = [] # Log the value of the error between tool and goal\n", - "herr2 = [] # Log the value of the error between gaze and ball\n", + "herr = [] # Log the value of the error between tool and goal.\n", + "herr2 = [] # Log the value of the error between gaze and ball.\n", + "# Loop on an inverse kinematics for 200 iterations.\n", + "for i in range(200): # Integrate over 2 second of robot life\n", "\n", - "# Your code" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here is the solution:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp3/generated/control_head_multi" + " pin.framesForwardKinematics(robot.model,robot.data,q)\n", + " pin.computeJointJacobians(robot.model,robot.data,q)\n", + "\n", + " # Gaze task\n", + " oMgaze = robot.data.oMf[IDX_GAZE]\n", + " o_Jgaze3 = pin.computeFrameJacobian(robot.model, robot.data, q, IDX_GAZE,pin.LOCAL_WORLD_ALIGNED)[:3,:]\n", + " o_GazeBall = oMgaze.translation-ball\n", + "\n", + " # Tool task\n", + " oMtool = robot.data.oMf[IDX_TOOL]\n", + " o_Jtool3 = pin.computeFrameJacobian(robot.model,robot.data,q,IDX_TOOL,pin.LOCAL_WORLD_ALIGNED)[:3,:]\n", + " o_TG = oMtool.translation-oMgoal.translation\n", + " \n", + " vq = -pinv(o_Jtool3) @ o_TG\n", + " Ptool = np.eye(robot.nv)-pinv(o_Jtool3) @ o_Jtool3\n", + " vq += pinv(o_Jgaze3 @ Ptool) @ (-o_GazeBall - o_Jgaze3 @ vq)\n", + "\n", + " q = pin.integrate(robot.model,q, vq * DT)\n", + " viz.display(q)\n", + " time.sleep(1e-3)\n", + "\n", + " herr.append(o_TG)\n", + " herr2.append(o_GazeBall) " ] }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 64, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "Text(0, 0.5, 'error (rad)')" + ] + }, + "execution_count": 64, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "plt.subplot(311)\n", "plt.plot([ e[:3] for e in herr])\n", @@ -860,63 +1015,12 @@ "plt.subplot(312)\n", "plt.plot([ e[3:] for e in herr])\n", "plt.xlabel('control cycle (iter)')\n", - "plt.ylabel('error (rad)');\n", + "plt.ylabel('error (rad)')\n", "plt.subplot(313)\n", "plt.plot([ e for e in herr2])\n", "plt.xlabel('control cycle (iter)')\n", "plt.ylabel('error (rad)')" ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Extension to three tasks" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Note that the previous reasoning can be extended recursively and we have more than 2 tasks.\n", - "\n", - "A third task can be implemented as well by computing the nullspace of the two first tasks:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "Pgaze = Ptool - pinv(o_Jgaze3 @ Ptool) @ o_Jgaze3 @ Ptool" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Load an extra cube in the viewer to figure a table. First, control the robot hand to reach an arbitrary point on the table (don't worry about collisions). Then, implement a control law to control three tasks:\n", - "* The tool frame should be kept on the table (only the vertical component of the error matters, select the third row of the Jacobian and error accordingly).\n", - "* The gaze should reach the position of a ball positionned on the table.\n", - "* The center of the mobile base frame should reach a given goal on the floor. For this task, only the horizontal components (x- and y-) of the task matter, select only the first two rows of the Jacobian and error accordingly." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# Your code" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Congratulations! You just implemented a local optimal controller that can solve multiple tasks at once." - ] } ], "metadata": { @@ -935,7 +1039,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.9.18" + "version": "3.10.14" } }, "nbformat": 4, diff --git a/4_dynamics.ipynb b/4_dynamics.ipynb index a62eb4c..1ba0af9 100644 --- a/4_dynamics.ipynb +++ b/4_dynamics.ipynb @@ -10,9 +10,17 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "NB: as for all the tutorials, a magic command %do_not_load is introduced to hide the solutions to some questions. Change it for %load if you want to see (and execute) the solution.\n" + ] + } + ], "source": [ "import magic_donotload" ] @@ -27,7 +35,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 2, "metadata": {}, "outputs": [], "source": [ @@ -59,7 +67,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ @@ -80,7 +88,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 4, "metadata": {}, "outputs": [], "source": [ @@ -96,7 +104,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 5, "metadata": {}, "outputs": [], "source": [ @@ -126,26 +134,24 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 3, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "You can open the visualizer by visiting the following URL:\n", + "http://127.0.0.1:7011/static/\n" + ] + } + ], "source": [ "robot = RobotHand()\n", "viz = MeshcatVisualizer(robot)\n", "viz.display(robot.q0)\n" ] }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "scrolled": true - }, - "outputs": [], - "source": [ - "viz.viewer.jupyter_cell()" - ] - }, { "cell_type": "markdown", "metadata": {}, @@ -166,9 +172,38 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "data": { + "application/vnd.jupyter.widget-view+json": { + "model_id": "ef4b532cfc3d4d5dab08ed54225691c3", + "version_major": 2, + "version_minor": 0 + }, + "text/plain": [ + "interactive(children=(FloatSlider(value=0.7, description='thumb', max=1.5, min=-0.5, step=0.01), Output()), _d…" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "application/vnd.jupyter.widget-view+json": { + "model_id": "d8851ff64c8b4007b88700ee7f3560d7", + "version_major": 2, + "version_minor": 0 + }, + "text/plain": [ + "interactive(children=(FloatSlider(value=0.3, description='others', max=2.0), Output()), _dom_classes=('widget-…" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "try:\n", " q0 = robot.q0.copy()\n", @@ -194,7 +229,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 9, "metadata": {}, "outputs": [], "source": [ @@ -229,7 +264,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 10, "metadata": {}, "outputs": [], "source": [ @@ -239,7 +274,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 11, "metadata": {}, "outputs": [], "source": [ @@ -263,28 +298,12 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 12, "metadata": {}, "outputs": [], "source": [ "tauq = np.random.rand(robot.model.nv)\n", - "aq = np.random.rand(robot.model.nv) # Replace me" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here is the solution" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp4/generated/solution_pd_dyninv" + "aq = inv(M) @ (tauq - b)" ] }, { @@ -296,9 +315,17 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 13, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "1.163749946033556e-15\n" + ] + } + ], "source": [ "print(norm(pin.rnea(robot.model,robot.data,q,vq,aq)-tauq))" ] @@ -315,7 +342,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 14, "metadata": {}, "outputs": [], "source": [ @@ -325,28 +352,12 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "vq += np.random.rand(robot.model.nv) # Replace me\n", - "q = np.random.rand(robot.model.nq) # Replace me" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "And a solution.." - ] - }, - { - "cell_type": "code", - "execution_count": null, + "execution_count": 15, "metadata": {}, "outputs": [], "source": [ - "%do_not_load tp4/generated/solution_pd_integrate" + "vq += aq * dt\n", + "q = pin.integrate(robot.model, q, vq * dt)" ] }, { @@ -366,7 +377,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 19, "metadata": {}, "outputs": [], "source": [ @@ -384,26 +395,38 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 18, "metadata": {}, - "outputs": [], + "outputs": [ + { + "ename": "KeyboardInterrupt", + "evalue": "", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mKeyboardInterrupt\u001b[0m Traceback (most recent call last)", + "Cell \u001b[0;32mIn[18], line 21\u001b[0m\n\u001b[1;32m 19\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m it\u001b[38;5;241m%\u001b[39m\u001b[38;5;241m20\u001b[39m\u001b[38;5;241m==\u001b[39m\u001b[38;5;241m0\u001b[39m: \n\u001b[1;32m 20\u001b[0m viz\u001b[38;5;241m.\u001b[39mdisplay(q)\n\u001b[0;32m---> 21\u001b[0m \u001b[43mtime\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43msleep\u001b[49m\u001b[43m(\u001b[49m\u001b[38;5;241;43m20\u001b[39;49m\u001b[38;5;241;43m*\u001b[39;49m\u001b[43mdt\u001b[49m\u001b[43m)\u001b[49m\n", + "\u001b[0;31mKeyboardInterrupt\u001b[0m: " + ] + } + ], "source": [ "for it in range(N_steps):\n", " t = it*dt\n", "\n", " # Retrieve the dynamics quantity at time t\n", - " M = np.eye(robot.model.nv) # REPLACE ME\n", - " b = np.zeros(robot.model.nv) # REPLACE ME\n", + " M = pin.crba(robot.model, robot.data, q)\n", + " b = pin.nle(robot.model, robot.data, q, vq)\n", "\n", " # Compute the force that apply\n", " tauq = np.zeros(robot.model.nv)\n", "\n", " # Use generalized PFD to calculate aq\n", - " aq = np.zeros(robot.model.nv) # REPLACE ME\n", + " aq = inv(M) @ (tauq - b)\n", "\n", " # Double integration to update vs and q\n", - " vq = np.zeros(robot.model.nv) # REPLACE ME\n", - " q = np.zeros(robot.model.nq) # REPLACE ME\n", + " vq += aq * dt\n", + " q = pin.integrate(robot.model, q, vq * dt)\n", "\n", " # Visualization\n", " if it%20==0: \n", @@ -411,22 +434,6 @@ " time.sleep(20*dt)\n" ] }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here is the solution" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp4/generated/solution_pd_freefall" - ] - }, { "cell_type": "markdown", "metadata": {}, @@ -436,7 +443,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 20, "metadata": {}, "outputs": [], "source": [ @@ -448,27 +455,30 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 21, "metadata": {}, "outputs": [], "source": [ - "# Use the same loop templace as above" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "And here the solution" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp4/generated/solution_pd_frictionfall" + "for it in range(N_steps):\n", + " t = it*dt\n", + "\n", + " # Retrieve the dynamics quantity at time t\n", + " M = pin.crba(robot.model, robot.data, q)\n", + " b = pin.nle(robot.model, robot.data, q, vq)\n", + "\n", + " # Compute the force that apply\n", + " tauq = np.zeros(robot.model.nv)\n", + "\n", + " # Use generalized PFD to calculate aq\n", + " aq = inv(M) @ (tauq - Kf * vq - b)\n", + " # Double integration to update vs and q\n", + " vq += aq * dt\n", + " q = pin.integrate(robot.model, q, vq * dt)\n", + "\n", + " # Visualization\n", + " if it%20==0: \n", + " viz.display(q)\n", + " time.sleep(20*dt)" ] }, { @@ -498,7 +508,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 22, "metadata": {}, "outputs": [], "source": [ @@ -523,7 +533,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 5, "metadata": {}, "outputs": [], "source": [ @@ -540,47 +550,38 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 24, "metadata": {}, "outputs": [], "source": [ - "for it in range(N_steps):\n", - " t = it*dt\n", + "hq = [] ### For storing the logs of measured trajectory q\n", + "hqdes = [] ### For storing the logs of desired trajectory qdes\n", + "for i in range(10000):\n", + " t = i*dt\n", "\n", - " # Retrieve the dynamics quantity at time t\n", - " M = np.eye(robot.model.nv) # REPLACE ME\n", - " b = np.zeros(robot.model.nv) # REPLACE ME\n", + " # Compute the model.\n", + " M = pin.crba(robot.model, robot.data, q)\n", + " b = pin.nle(robot.model, robot.data, q, vq)\n", "\n", - " # Compute the force that apply\n", - " tauq = np.zeros(robot.model.nv)\n", + " # Compute the PD control.\n", + " tauq = -Kp*(q-qdes(t)) - Kv*(vq-qdes.velocity(t)) + qdes.acceleration(t)\n", "\n", - " # Use generalized PFD to calculate aq\n", - " aq = np.zeros(robot.model.nv) # REPLACE ME\n", + " # Simulated the resulting acceleration (forward dynamics\n", + " aq = inv(M) @ (tauq - b)\n", "\n", - " # Double integration to update vs and q\n", - " vq = np.zeros(robot.model.nv) # REPLACE ME\n", - " q = np.zeros(robot.model.nq) # REPLACE ME\n", + " # Integrate the acceleration.\n", + " vq += aq * dt\n", + " q = pin.integrate(robot.model, q, vq * dt)\n", "\n", - " # Visualization\n", - " if it%20==0: \n", + " # Display every TDISP iterations.\n", + " TDISP = 50e-3 # Display every 50ms\n", + " if not i % int(TDISP/dt): # Only display once in a while ...\n", " viz.display(q)\n", - " time.sleep(20*dt)\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here is the solution, should you need it." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp4/generated/solution_pd_loop" + " time.sleep(TDISP)\n", + "\n", + " # Log the history.\n", + " hq.append(q.copy())\n", + " hqdes.append(qdes.copy())\n" ] }, { @@ -599,7 +600,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 26, "metadata": {}, "outputs": [], "source": [ @@ -612,9 +613,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 27, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "plot_joint_profiles(11, hq, hqdes)" ] @@ -635,7 +647,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 9, "metadata": {}, "outputs": [], "source": [ @@ -678,7 +690,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 10, "metadata": {}, "outputs": [], "source": [ @@ -695,7 +707,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 11, "metadata": {}, "outputs": [], "source": [ @@ -765,7 +777,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 12, "metadata": {}, "outputs": [], "source": [ @@ -790,11 +802,92 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 15, "metadata": {}, "outputs": [], "source": [ - "# Start from the previous templates and add the contact simulation." + "hq_c = [] ### For storing the logs of measured trajectory q\n", + "hqdes_c = [] ### For storing the logs of desired trajectory qdes\n", + "\n", + "tracked_collisions_id = set() # Track contact\n", + "\n", + "for it in range(N_steps):\n", + " t = it*dt\n", + "\n", + " # Compute the dynamics quantities for the model\n", + " M = pin.crba(robot.model, robot.data, q) # Inertie matrix\n", + " b = pin.nle(robot.model, robot.data, q, vq) # Coriolis term\n", + "\n", + " # Compute the PD torque control we apply in actuators order to follow qdes\n", + " tauq_control = - Kp * (q - qdes(t)) - Kv * (vq - qdes.velocity(t)) + alpha * qdes.acceleration(t)\n", + " # Compute the friction torque\n", + " tauq_friction = - Kf * vq\n", + " \n", + " # Simulate the resulting free acceleration (forward dynamics)\n", + " # The total torque is the control torque and the friction torque\n", + " # It corresponds to the acceleration qddot if there is no contact\n", + " aq0 = inv(M) @ (tauq_friction + tauq_control - b)\n", + "\n", + " # Check collision to calculate the real acceleration that respects the contacts\n", + " colwrap.computeCollisions(q, vq)\n", + " raw_collisions = colwrap.getCollisionList()\n", + " raw_dist = colwrap.getCollisionDistances(raw_collisions)\n", + "\n", + " # Keep only the significative collisions because of numerical errors\n", + " collisions = [c for c, d in zip(raw_collisions, raw_dist) if d <= -1e-4]\n", + "\n", + " if not collisions:\n", + " # No real collision so acceleration is the free acceleration\n", + " aq = aq0\n", + " # There is no contact so we reset the tracker\n", + " tracked_collisions_id = set()\n", + " else:\n", + " # extract dists, J_c et Jdotqdot for the actual collisions\n", + " dists = colwrap.getCollisionDistances(collisions)\n", + " J = colwrap.getCollisionJacobian(collisions)\n", + " JdotQdot = colwrap.getCollisionJdotQdot(collisions)\n", + " \n", + " # Use the id of collisions to identify the new collisions\n", + " # for a collision col, col[0] is a unique identifier\n", + " collisions_id = [col[0] for col in collisions]\n", + " # get the pyidx (i.e., the python index) for collision with id (i.e. col[0]) not already tracked\n", + " new_collisions_pyidx = [\n", + " pyidx\n", + " for pyidx, col_id in enumerate(collisions_id)\n", + " if col_id not in tracked_collisions_id\n", + " ]\n", + " # Update our tracker for the next iteration\n", + " tracked_collisions_id = set(collisions_id)\n", + "\n", + " # For the new collisions, adapt vq such that vc is 0\n", + " if new_collisions_pyidx:\n", + " # We extract the line of J only for the new collisions\n", + " J_proj = np.stack([J[i] for i in new_collisions_pyidx], axis=0)\n", + " # And we use pinv to project vq in the kernel of J_proj such that vs=0\n", + " vq -= (pinv(J_proj) @ J_proj) @ vq\n", + "\n", + " # Construct the minimization problem associated with the Gauss principle\n", + " # The constraint is ac >= PD(e, vc) instead of e >= 0\n", + " A = M\n", + " b = M @ aq0\n", + " C = J\n", + " d = - JdotQdot - Kp_c * dists - Kv_c * J @ vq\n", + " \n", + " [aq,cost,_,niter,lag,iact] = quadprog.solve_qp(A,b,C.T,d)\n", + "\n", + " # Integrate the acceleration.\n", + " vq += aq * dt\n", + " q = pin.integrate(robot.model, q, vq * dt)\n", + "\n", + " # Display every TDISP iterations.\n", + " TDISP = 50e-3 # Display every 50ms\n", + " if not it % int(TDISP/dt): # Only display once in a while ...\n", + " viz.display(q)\n", + " time.sleep(TDISP)\n", + "\n", + " # Log the history.\n", + " hq_c.append(q.copy())\n", + " hqdes_c.append(qdes.copy())" ] }, { @@ -879,7 +972,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.10.13" + "version": "3.10.14" } }, "nbformat": 4, diff --git a/5_1_controlopt_intro.ipynb b/5_1_controlopt_intro.ipynb deleted file mode 100644 index f40aca9..0000000 --- a/5_1_controlopt_intro.ipynb +++ /dev/null @@ -1,361 +0,0 @@ -{ - "cells": [ - { - "attachments": { - "image.png": { - "image/png": "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" - } - }, - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Starting example: the unicycle\n", - "\n", - "![image.png](attachment:image.png)\n", - "\n", - "An unicycle represents a kinematic model of a car where it's only possible to move in two directions, i.e. it drives forward and turns on the spot. Its dynamics has nonholonomic constraints because it cannot move sideways. Remember that nonholonomic constraints are nonintegral and has the form $\\mathbf{f(q,\\dot{q})=0}$.\n", - "\n", - "In this example, we define an optimal-control problem for the classical unicycle problem. Our goal is to drive the unicycle towards the origin but at the same time not too fast. For that, the cost function is described as the sum between the distance to the origin and the system speed.\n", - "\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Setup" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import magic_donotload" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "An optimal control problem is:\n", - "$$\\min_u \\int_0^T L(x(t),u(t))dt + \\Phi(x(T))$$\n", - "$$\\dot{x} = f(x,u)$$\n", - "where $x$ is the state variable, $u$ the control. For contact and collision, we could add continuous equality and/or equality constraint.\n", - "\n", - "Control in acceleration through as with the dynamic like in the previous TP is achieved thanks to using $\\tilde{x} = \\left(\\begin{array}{c}\n", - " x \\\\\n", - " \\dot{x}\n", - "\\end{array}\\right)\n", - "$, $u=\\tau$ and $f(\\tilde{x},u) = \\left(\\begin{array}{c}\n", - " \\dot{x} \\\\\n", - " dynamic(x, \\dot{x}, \\tau)\n", - "\\end{array}\\right)\n", - "$" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Crocoddyl\n", - "Crocoddyl stands for Contact robot control with differential dynamic programming library. We will need it for formulating and solving the optimal control problems. \n", - "\n", - "DDP is a second order method to solve the direct discretized version of the previous problem in a simple shooting flavor. As for previous problematic in robotic, recent research propose variation of DDP usefull in the case of robotic. [proxDDP](https://hal.archives-ouvertes.fr/hal-03597630/document)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Introducing Crocoddyl\n", - "Basically, our optimal control problem has the following dynamical model and cost function:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import numpy as np\n", - "x = np.random.rand(3) # x, y, t\n", - "u = np.random.rand(2) # v, w\n", - "\n", - "# Unicycle dynamical model\n", - "v,w = u\n", - "c,s = np.cos(x[2]),np.sin(x[2])\n", - "dt = 1e-2\n", - "dx = np.array([ v*c, v*s, w ]) # In world ref\n", - "xnext = x + dx*dt\n", - "\n", - "# Cost function: driving to origin (state) and reducing speed (control)\n", - "stateWeight = 1\n", - "ctrlWeight = 1\n", - "costResiduals = np.concatenate([stateWeight*x,ctrlWeight*u])\n", - "cost = .5* sum(costResiduals**2)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "For this basic example, the unicycle model is coded in the library [Crocoddyl](https://gepettoweb.laas.fr/doc/loco-3d/crocoddyl/master/doxygen-html/). We will just load it and use it. If you are very curious, have a look! It is in crocoddyl/unicycle.py." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here the cost is $L(x,u) = \\frac{1}{2}(A_s \\|x\\|^2 + A_u \\|u\\|^2)$, it encode the goal of driving the car to the origin, while using as less trust as possible. $A_s$ and $A_u$ tune the tradeoff between control use and importance of reaching the target soon enough.." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We create such a model with the following lines:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import crocoddyl\n", - "model = crocoddyl.ActionModelUnicycle()\n", - "data = model.createData()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The action model contains ... well ... the description of the dynamics and cost function. There you find also the action model parameters (here the time step and the cost weights). On the other hand, the data has the buffers where the results of the calculus are stored.\n", - "\n", - "We decided for this separation for an obvious reason that is given just below." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "model.costWeights = np.array([\n", - " 1, # state weight\n", - " 1 # control weight\n", - "])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "**You can further understand the mathematical definition of action models see introduction_to_crocoddyl.ipynb**" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## I. Defining the shooting problem\n", - "A shooting problem is defined by the initial state from which computing the rollout and a sequence of action models.\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "x0 = np.matrix([ -1., -1., 1. ]).T #x,y,theta\n", - "T = 20\n", - "problem = crocoddyl.ShootingProblem(x0, [ model ] * T, model)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here we define a problem starting from $\\mathbf{x}_0$ with 20 timesteps (of 0.1 sec by default implementation of unicycle). The terminal action model is defined using the running action model.\n", - "\n", - "This defines the model, not any algorithm to solve it. The only computation that the problem can provide is to integrate the system for a given sequence of controls." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "us = [ np.matrix([1., 1.]).T for t in range(T)]\n", - "xs = problem.rollout(us)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The plotUnicycle function plots the system as two arrows that represent the wheels" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%matplotlib inline\n", - "import matplotlib.pylab as plt\n", - "from tp5.unicycle_utils import plotUnicycle\n", - "for x in xs: plotUnicycle(x)\n", - "plt.axis([-2,2.,-2.,2.])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## II. Solve the OCP\n", - "The main solver is named SolverDDP. It is initialized from the problem object and mostly contains the ddp.solve method. We can warm start it and tune the parameters, but for the simple unicycle, let's just solve it!" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "ddp = crocoddyl.SolverDDP(problem)\n", - "done = ddp.solve()\n", - "assert(done)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "plt.clf()\n", - "for x in ddp.xs: plotUnicycle(x)\n", - "plt.axis([-2,2,-2,2])\n", - "print(ddp.xs[-1])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "and the final state is:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "print(ddp.xs[-1])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Well, the terminal state is not so nicely in the origin.\n", - "\n", - "Question 1: why?\n", - "\n", - "Question 2: How can you change this? Create a new DDP problem\n", - "\n", - "Question 3: by changing the cost parameters, the time horizon and the initial position, can you trigger a maneuver?" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# Your code" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp5/generated/unicycle_solutions_termmodel" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "ddp.solve()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "for x in ddp.xs: plotUnicycle(x)\n", - "plt.axis([-2,2.,-2.,2.])" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "print(ddp.xs[-1])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# How to use DDP for real robot control\n", - "In its natural form DDP tackle the problem of the whole trajectory for a problem. In a a sence it is a motion planning method, however in contract with RRT and/or PRM it is not a global space trajectory. DDP can be use to generate a reference trajectory for a task, and PD controller can be use to follow it with a robot. An other approach callled Modele Predictive Control (MPC) is to solve the DDP on some given horizon and take the first fex step of the control solution as an actual controller for the robot. However despite MPC being of a great appeal, there is a lot of computationnal challenges to be able to control robot at 100Hz." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "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.9.13" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/5_2_controlopt.ipynb b/5_2_controlopt.ipynb deleted file mode 100644 index cad724a..0000000 --- a/5_2_controlopt.ipynb +++ /dev/null @@ -1,642 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Reaching multiple targets with a manipulator\n", - "The objective of this exercise is to reach multiple targets with a manipulator.\n", - "\n", - "We provide a basic example for reaching one point, and you have to modify it for sequence of multiple targets. Below it is the basic example, there we'll guide you to the final result.\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Set up" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import magic_donotload" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We will need crocoddyl as in the previous notebook, with the model of the arm of the humanoid robot Talos, a 7-dof arm. It can be found in example robot data." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import crocoddyl\n", - "import pinocchio as pin\n", - "import numpy as np\n", - "import example_robot_data as robex" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## The optimal-control program" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "First, let's load the Pinocchio model for the Talos arm." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "robot = robex.load('talos_arm')\n", - "robot_model = robot.model" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Set robot model." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "robot_model.armature =np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.])*5 # It is a regularization of the mass matric M' = M + lamb I\n", - "robot_model.q0 = np.array([3.5,2,2,0,0,0,0])\n", - "robot_model.x0 = np.concatenate([robot_model.q0, np.zeros(robot_model.nv)])\n", - "robot_model.gravity *= 0" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Let's add a viewer to display the model.\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from utils.meshcat_viewer_wrapper import MeshcatVisualizer\n", - "viz = MeshcatVisualizer(robot)\n", - "viz.display(robot_model.q0)\n", - "viz.viewer.jupyter_cell()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "viz.addBox('world/goal',[.1,.1,.1],[0,1,0,1])\n", - "viz.applyConfiguration('world/goal',[.2,.5,.5,0,0,0,1])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Configure the task." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "FRAME_TIP = robot_model.getFrameId(\"gripper_left_fingertip_3_link\") # Wrapper around pinocchio\n", - "goal = np.array([.2,.5,.5])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Create a cost model per the running and terminal action model." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "state = crocoddyl.StateMultibody(robot_model)\n", - "# The state object containt info about the configspace, the constraint, the velocity, the kinematic values and everything\n", - "\n", - "# State is quite abstract, to have a real solvable OCP we need to define somme cost associated to this model\n", - "# We also need to decide the actual dynamic we will follow (called actuation), it means a solver that will be ourf(x,u) AND a way to descretize it\n", - "\n", - "runningCostModel = crocoddyl.CostModelSum(state) # The state will remain the same during running \n", - "terminalCostModel = crocoddyl.CostModelSum(state) # And also for final state" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Note that we need to include a cost model (i.e. set of cost functions) in order to fully define the action model for our optimal control problem.\n", - "For this particular example, we formulate three running-cost functions: goal-tracking cost, state and control regularization; and a terminal cost: goal cost. First, let's create the common cost functions." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# Cost for 3d tracking || p(q) - pref ||**2\n", - "goalTrackingRes = crocoddyl.ResidualModelFrameTranslation(state,FRAME_TIP,goal)\n", - "goalTrackingCost = crocoddyl.CostModelResidual(state,goalTrackingRes)\n", - "\n", - "# Cost for 6d tracking || log( M(q)^-1 Mref ) ||**2\n", - "Mref = pin.SE3(pin.utils.rpyToMatrix(0,np.pi/2,-np.pi/2), goal)\n", - "goal6TrackingRes = crocoddyl.ResidualModelFramePlacement(state,FRAME_TIP,Mref)\n", - "goal6TrackingCost = crocoddyl.CostModelResidual(state,goal6TrackingRes)\n", - "\n", - "# Cost for state regularization || x - x* ||**2\n", - "xRegWeights = crocoddyl.ActivationModelWeightedQuad(np.array([1,1,1,1,1,1,1, 1,1,1,1,2,2,2.]))\n", - "xRegRes = crocoddyl.ResidualModelState(state,robot_model.x0)\n", - "xRegCost = crocoddyl.CostModelResidual(state,xRegWeights,xRegRes)\n", - "\n", - "# Cost for control regularization || u - g(q) ||**2\n", - "uRegRes = crocoddyl.ResidualModelControlGrav(state)\n", - "uRegCost = crocoddyl.CostModelResidual(state,uRegRes)\n", - "\n", - "# Terminal cost for state regularization || x - x* ||**2\n", - "xRegWeightsT=crocoddyl.ActivationModelWeightedQuad(np.array([1,1,1,1,1,1,1, 1,1,1,1,2,2,2.]))\n", - "xRegResT = crocoddyl.ResidualModelState(state,robot_model.x0)\n", - "xRegCostT = crocoddyl.CostModelResidual(state,xRegWeightsT,xRegResT)\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Then let's added the running and terminal cost functions and the constant weight for each whole cost" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "runningCostModel.addCost(\"gripperPose\", goalTrackingCost, .001) # addCost is a method of CostModelSum that take another CostModel\n", - "runningCostModel.addCost(\"xReg\", xRegCost, 1e-3) # We also weight the sum of cost\n", - "runningCostModel.addCost(\"uReg\", uRegCost, 1e-6)\n", - "terminalCostModel.addCost(\"gripperPose\", goalTrackingCost, 10)\n", - "terminalCostModel.addCost(\"xReg\", xRegCostT, .01)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Next, we need to create an action model for running and terminal knots. The\n", - "forward dynamics (computed using ABA) are implemented inside DifferentialActionModelFullyActuated." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "actuationModel = crocoddyl.ActuationModelFull(state)\n", - "dt = 1e-2\n", - "# A step in the running step\n", - "## We use the freefall forward dynamic as dotx = f(x,u) it could be a contact one (as in prev TP) and so on\n", - "### It is the differential model chosen around the state\n", - "## We precise the duration of the step dt\n", - "## We precise the integration scheme we use \n", - "### It is the integrated model chosen around the differential model\n", - "## We precise which cost is used during this step\n", - "runningModel = crocoddyl.IntegratedActionModelEuler(\n", - " crocoddyl.DifferentialActionModelFreeFwdDynamics(state, actuationModel, runningCostModel), dt)\n", - "runningModel.differential.armature = robot_model.armature\n", - "\n", - "\n", - "terminalModel = crocoddyl.IntegratedActionModelEuler(\n", - " crocoddyl.DifferentialActionModelFreeFwdDynamics(state, actuationModel, terminalCostModel), 0.)\n", - "terminalModel.differential.armature = robot_model.armature" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "For this optimal control problem, we define 250 knots (or running action\n", - "models) plus a terminal knot" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "T = 100\n", - "problem = crocoddyl.ShootingProblem(robot_model.x0, [runningModel] * T, terminalModel)\n", - "# We chain all the discrete step with their cost from an initial value even the final one that have the terminal costs\n", - "# We just repeat the running step for a number of time and add the terminal node\n", - "## This problem object contain discretized dynamic and cost on horizon T for a state (aka a system)\n", - "### Alternative could have be variable actuaction type, e.g. to force sequence of contact\n", - "### other integration...\n", - "### Other type of problem like multiple shooting, colocation...\n", - "# Problem is an OCP problem formulation !" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We finalize the set up by creating the DDP solver for this optimal control problem." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# We wrap the problem into a solver (an algorithm method to solve OCP)\n", - "ddp = crocoddyl.SolverDDP(problem)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Callbacks can be added, for example to at verbose output when the solver runs, or logs the data of the descent algorithm." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "ddp.setCallbacks([\n", - " crocoddyl.CallbackLogger(),\n", - " crocoddyl.CallbackVerbose(),\n", - "])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The DDP algorithm is run by the solver with:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "ddp.solve([],[],1000) # xs_init,us_init,maxiter" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "You can now look at the results, either in Gepetto-viewer by running the trajectory, or by plotting it." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import tp5.croco_utils as crocutils\n", - "crocutils.displayTrajectory(viz,ddp.xs,ddp.problem.runningModels[0].dt,12)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "And plotting..." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%matplotlib inline" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "log = ddp.getCallbacks()[0]\n", - "crocoddyl.plotOCSolution(log.xs, log.us, figIndex=1)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## I. DifferentialActionModel for Pinocchio ABA\n", - "ABA is a Rigid Body Algorithm optimized to calculate the acceleration in configuration space given the torque.\n", - "\n", - "This scenario uses an action model that computes 2nd order differential dynamics with Pinocchio. Note that it can accept several cost models. This action model is tailored for robot applications, and at the same time, it's modular since:\n", - " - you can modify the robot dynamics by changing Pinocchio model, and\n", - " - you can formulate any cost function by simply adding running and/or terminal costs.\n", - "\n", - "## II. Cost models\n", - "\n", - "A cost model computes a scalar cost value and its gradient and Hessian. All the models implemented are computing a cost residual and are computing the Hessian with the Gauss approximation.\n", - "\n", - "We implemented reusable cost models for controlling \n", - " - a frame placement (translation or velocity),\n", - " - the center of mass position, and \n", - " - state and control spaces.\n", - "\n", - "In the example above, we used the CostModelFrameTranslation which defines a 3d position task, and the state and control regularizers." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "All functions are defined by their *model*, which is const, i.e none of its fields is modified by the *calc* and *calcDiff* calls. Temporary buffers are defined in a companion *data*." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "dataCollector = crocoddyl.DataCollectorMultibody(robot.data)\n", - "trackData = goalTrackingCost.createData(dataCollector)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### II.a Frame position cost\n", - "\n", - "You define a frame ID and the reference position as a 3D array. The cost is the distance between the frame and the target. This cost depends on $\\mathbf{x}$ (specifically the configuration $\\mathbf{q}$). You can double check the 0s in its gradient." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "x = ddp.xs[1].copy()\n", - "q = x[:state.nq]\n", - "pin.updateFramePlacements(robot.model, robot.data)\n", - "pin.computeJointJacobians(robot.model, robot.data, q)\n", - "goalTrackingCost.calc(trackData, x)\n", - "goalTrackingCost.calcDiff(trackData, x)\n", - "print('Lx = ',trackData.Lx) # For gradient\n", - "print('Lu = ',trackData.Lu)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### II.b State cost\n", - "In this part of the tutorial you must define a State model. It defines \n", - " - the dimension of the state and its tangent, and\n", - " - the exponential/integrate and difference/log operators.\n", - "The operators can described using Pinocchio functions. And the exercite consists on adding them into your State class. Please note crocoddyl has abstract functions for this.\n", - "\n", - "The state cost uses a reference in state space (State.zero() by default). The cost is the distance, computed with state.difference between the current state and the reference. Hence, with this cost, we regularize both position and velocity.\n", - "\n", - "### II.c Control cost\n", - "\n", - "The control cost uses a control reference as in the state cost. The cost is the distance the current control and the reference. Hence the cost regularizes torque commands." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### II.d Add cost models to the differential action model\n", - "Each time we want to include a new cost function, we use addCost function inside our DAM. In this function you're also able its weight." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## III. Create the problem with integrated action model\n", - "Differential action models describe cost and dynamics in continuous-time, however our optimal control solvers work in discrete-time. We have created the integrated action model in order to deal with this.\n", - "\n", - "In the previous code, we have used an abstract class that uses simpletic Euler rules. In the cartpole exercise you have learnt how to use integrated action models for your problem." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## IV. Callbacks\n", - "\n", - "Callback functions are needed for analysing and debugging the performance of the solver for your specific problem.\n", - "For problems defined with Pinocchio, you can display the robot trajectory per each iterate by including CallbackDisplay. With this callback, you can display robot motions with different rates. Additionally, CallbackVerbose prints a message that allows us to understand the behaviour of the solver.\n", - "\n", - "Generally speaking, an user is able to describe any callback function. This function will be run once per iterate and it has access to all data." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## V. Modifying the example\n", - "\n", - "Start by defining several targets (let's say 4 targets, all at x=0.4, and at y and z being either 0 or 0.4), and display then in the viewer.\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "viz.delete('world/goal')\n", - "goals = np.array([\n", - " [.4, 0., 0.4],\n", - " [.4, 0., 0.],\n", - " [.4, 0.4, 0.4],\n", - " [.4, 0.4, 0.],\n", - "])\n", - "\n", - "for i, g in enumerate(goals):\n", - " viz.addBox(f'world/goal{i}',[.1,.1,.1],[0,1,0,1])\n", - " viz.applyConfiguration(f'world/goal{i}',list(g) + [0,0,0,1])" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The shooting problem will be composed of 4 sequences of action models. Each sequence consists on T shooting \"running\" nodes and 1 terminal node. The running nodes mostly have regularization terms, while the terminal nodes have a strong cost toward the respective target.\n", - "\n", - "[ R1,R1,R1 ... R1,T1, R2,R2 .... R2, T2, R3 ... R3, T3, R4 ... R4 ] , T4\n", - "\n", - "First create 4 running models and 4 terminal models cost." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Then you need to add a position cost, and state and control regularization to each running action model. Please note that for terminal action model is only needed the position cost. Additionally, in the running models, the position cost should be low, and it should be high in the terminal models.\n", - "Be carefull ! Intermediate terminal cost should not have $dt=0$" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Now create different shooting problem if you need to go through 1, 2, 3 or 4 positions." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Create a DDP solver for this problem and run it." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "ddp = crocoddyl.SolverDDP(problem)\n", - "ddp.solve()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Well, it should not work, at least no on the first shot. The DDP solver is likely not strong enough to accept the random weights that you have selected. \n", - "\n", - "If it is working nicely from the first shot, display it in the viewer and go take a coffee. But you will likely have to tweak the gains to make it work.\n", - "\n", - "**It is suggested to first optimize only sequence 1. When you are happy with it, add sequence 2 and optimize again, etc.**\n", - "\n", - "OCP allows to reduce the problem to a weight tunning one. However, some research try to automate this weight tunning part." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The solution if you need it:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "%do_not_load tp5/generated/general_ddp_4stage" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "crocutils.displayTrajectory(viz, ddp.xs, ddp.problem.runningModels[0].dt, 12)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "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.10.13" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/6_RRT.ipynb b/6_RRT.ipynb deleted file mode 100644 index 4df1967..0000000 --- a/6_RRT.ipynb +++ /dev/null @@ -1,992 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "id": "66575b61-30a5-4471-9e4e-a45c6fc396a9", - "metadata": {}, - "source": [ - "# Implement RRT and its variant on UR5" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "f3b9c224-8a28-4554-b0ee-a8ac303aa6df", - "metadata": {}, - "outputs": [], - "source": [ - "import magic_donotload" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "b5d79912-1a64-4466-8017-70724567b28c", - "metadata": {}, - "outputs": [], - "source": [ - "import example_robot_data as robex\n", - "import hppfcl\n", - "import math\n", - "import numpy as np\n", - "import pinocchio as pin\n", - "import time\n", - "from tqdm import tqdm" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "8abf514d-0c36-4c32-934f-e1d013c57ea7", - "metadata": {}, - "outputs": [], - "source": [ - "import matplotlib.pylab as plt; plt.ion()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "bf038376-9d69-48e9-9bdb-0bcf3b641247", - "metadata": {}, - "outputs": [], - "source": [ - "from utils.meshcat_viewer_wrapper import MeshcatVisualizer, colors\n", - "from utils.datastructures.storage import Storage\n", - "from utils.datastructures.pathtree import PathTree\n", - "from utils.datastructures.mtree import MTree\n", - "from tp4.collision_wrapper import CollisionWrapper" - ] - }, - { - "cell_type": "markdown", - "id": "58561974-a3d2-4692-821c-30f4d0caf96f", - "metadata": {}, - "source": [ - "## Load UR5" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "7217ea2c-5cac-430e-8496-93e80e78b859", - "metadata": {}, - "outputs": [], - "source": [ - "robot = robex.load('ur5')\n", - "collision_model = robot.collision_model\n", - "visual_model = robot.visual_model" - ] - }, - { - "cell_type": "markdown", - "id": "98805b5f-f993-4d4a-98ca-c465ff363424", - "metadata": {}, - "source": [ - "Recall some placement for the UR5" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "9f521701-7416-4736-9363-305a45258d14", - "metadata": {}, - "outputs": [], - "source": [ - "a = robot.placement(robot.q0, 6) # Placement of the end effector joint.\n", - "b = robot.framePlacement(robot.q0, 22) # Placement of the end effector tip.\n", - "\n", - "tool_axis = b.rotation[:, 2] # Axis of the tool\n", - "tool_position = b.translation" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "d96626e3-1b22-446f-916a-f7ee54b78f04", - "metadata": {}, - "outputs": [], - "source": [ - "viz = MeshcatVisualizer(robot)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "e2d1d4ee-c1f4-4350-9370-ed8f32dee4cf", - "metadata": {}, - "outputs": [], - "source": [ - "viz.viewer.jupyter_cell()" - ] - }, - { - "cell_type": "markdown", - "id": "8ede57d4-8b0d-4a69-adbd-95901db503cd", - "metadata": {}, - "source": [ - "Set a start and a goal configuration" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "4b14d4cd-9e44-4e14-9a56-ec08256d0238", - "metadata": {}, - "outputs": [], - "source": [ - "q_i = np.array([1., -1.5, 2.1, -.5, -.5, 0])\n", - "q_g = np.array([3., -1., 1, -.5, -.5, 0])\n", - "radius = 0.05" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "a05303fd-5fa9-47bf-92cd-63d64e2212cf", - "metadata": {}, - "outputs": [], - "source": [ - "viz.display(q_i)\n", - "M = robot.framePlacement(q_i, 22)\n", - "name = \"world/sph_initial\"\n", - "viz.addSphere(name, radius, [0., 1., 0., 1.])\n", - "viz.applyConfiguration(name,M)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "dbc882d4-b335-4255-9db3-3aa61eeb8ee7", - "metadata": { - "tags": [] - }, - "outputs": [], - "source": [ - "viz.display(q_g)\n", - "M = robot.framePlacement(q_g, 22)\n", - "name = \"world/sph_goal\"\n", - "viz.addSphere(name, radius, [0., 0., 1., 1.])\n", - "viz.applyConfiguration(name,M)" - ] - }, - { - "cell_type": "markdown", - "id": "6a4bce9b-0c81-4c7a-bee9-02c9aa59b829", - "metadata": {}, - "source": [ - "## Implement everything needed for RRT" - ] - }, - { - "cell_type": "markdown", - "id": "9d4c45e0-ee85-47b1-88ae-94c3c8fb50d8", - "metadata": {}, - "source": [ - "We abstract the robot the environment and its behaviour in a class call `System`\n", - "\n", - "It must be able to:\n", - "- generate random configuration which are not colliding if needed (sampling)\n", - "- implement a distance on the configuration space (distance)\n", - "- generate path between two configuration (steering)\n", - "- check if a path is free between two configuration and return the latest free config (directional free steering)\n", - "and some function to display the configuration.\n", - "\n", - "Recall that in the case of the UR5 the configuration space is $S_1^{6}$, where $S_1$ is the unit cirle, we can parametrize by $\\theta\\in[-\\pi,\\pi]$ such that $-\\pi$ and $\\pi$ are identified.\n", - "\n", - "In the next cell, you must implement the system behaviour for the UR5." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "b74e5455-eae8-49fe-9030-f403467df288", - "metadata": {}, - "outputs": [], - "source": [ - "class System():\n", - "\n", - " def __init__(self, robot):\n", - " self.robot = robot\n", - " robot.gmodel = robot.collision_model\n", - " self.display_edge_count = 0\n", - " self.colwrap = CollisionWrapper(robot) # For collision checking\n", - " self.nq = self.robot.nq\n", - " self.display_count = 0\n", - " \n", - " def distance(self, q1, q2):\n", - " \"\"\"\n", - " Must return a distance between q1 and q2 which can be a batch of config.\n", - " \"\"\"\n", - " if len(q2.shape) > len(q1.shape):\n", - " q1 = q1[None, ...]\n", - " e = np.mod(np.abs(q1 - q2), 2 * np.pi)\n", - " e[e > np.pi] = 2 * np.pi - e[e > np.pi]\n", - " return np.linalg.norm(e, axis=-1)\n", - "\n", - " def random_config(self, free=True):\n", - " \"\"\"\n", - " Must return a random configuration which is not in collision if free=True\n", - " \"\"\"\n", - " q = 2 * np.pi * np.random.rand(6) - np.pi\n", - " if not free:\n", - " return q\n", - " while self.is_colliding(q):\n", - " q = 2 * np.pi * np.random.rand(6) - np.pi\n", - " return q\n", - "\n", - " def is_colliding(self, q):\n", - " \"\"\"\n", - " Use CollisionWrapper to decide if a configuration is in collision\n", - " \"\"\"\n", - " self.colwrap.computeCollisions(q)\n", - " collisions = self.colwrap.getCollisionList()\n", - " return (len(collisions) > 0)\n", - "\n", - " def get_path(self, q1, q2, l_min=None, l_max=None, eps=0.2):\n", - " \"\"\"\n", - " generate a continuous path with precision eps between q1 and q2\n", - " If l_min of l_max is mention, extrapolate or cut the path such\n", - " that \n", - " \"\"\"\n", - " q1 = np.mod(q1 + np.pi, 2 * np.pi) - np.pi\n", - " q2 = np.mod(q2 + np.pi, 2 * np.pi) - np.pi\n", - "\n", - " diff = q2 - q1\n", - " query = np.abs(diff) > np.pi\n", - " q2[query] = q2[query] - np.sign(diff[query]) * 2 * np.pi\n", - "\n", - " d = self.distance(q1, q2)\n", - " if d < eps:\n", - " return np.stack([q1, q2], axis=0)\n", - " \n", - " if l_min is not None or l_max is not None:\n", - " new_d = np.clip(d, l_min, l_max)\n", - " else:\n", - " new_d = d\n", - " \n", - " N = int(new_d / eps + 2)\n", - "\n", - " return np.linspace(q1, q1 + (q2 - q1) * new_d / d, N)\n", - " \n", - " def is_free_path(self, q1, q2, l_min=0.2, l_max=1., eps=0.2):\n", - " \"\"\"\n", - " Create a path and check collision to return the last\n", - " non-colliding configuration. Return X, q where X is a boolean\n", - " who state is the steering has work.\n", - " We require at least l_min must be cover without collision to validate the path.\n", - " \"\"\"\n", - " q_path = self.get_path(q1, q2, l_min, l_max, eps)\n", - " N = len(q_path)\n", - " N_min = N - 1 if l_min is None else min(N - 1, int(l_min / eps))\n", - " for i in range(N):\n", - " if self.is_colliding(q_path[i]):\n", - " break\n", - " if i < N_min:\n", - " return False, None\n", - " if i == N - 1:\n", - " return True, q_path[-1]\n", - " return True, q_path[i - 1]\n", - "\n", - " def reset(self):\n", - " \"\"\"\n", - " Reset the system visualization\n", - " \"\"\"\n", - " for i in range(self.display_count):\n", - " viz.delete(f\"world/sph{i}\")\n", - " viz.delete(f\"world/cil{i}\")\n", - " self.display_count = 0\n", - " \n", - " def display_edge(self, q1, q2, radius=0.01, color=[1.,0.,0.,1]):\n", - " M1 = self.robot.framePlacement(q1, 22) # Placement of the end effector tip.\n", - " M2 = self.robot.framePlacement(q2, 22) # Placement of the end effector tip.\n", - " middle = .5 * (M1.translation + M2.translation)\n", - " direction = M2.translation - M1.translation\n", - " length = np.linalg.norm(direction)\n", - " dire = direction / length\n", - " orth = np.cross(dire, np.array([0, 0, 1]))\n", - " orth /= np.linalg.norm(orth)\n", - " orth2 = np.cross(dire, orth)\n", - " orth2 /= np.linalg.norm(orth2)\n", - " Mcyl = pin.SE3(np.stack([orth2, dire, orth], axis=1), middle)\n", - " name = f\"world/sph{self.display_count}\"\n", - " viz.addSphere(name, radius, [1.,0.,0.,1])\n", - " viz.applyConfiguration(name,M2)\n", - " name = f\"world/cil{self.display_count}\"\n", - " viz.addCylinder(name, length, radius / 4, [0., 1., 0., 1])\n", - " viz.applyConfiguration(name,Mcyl)\n", - " self.display_count +=1\n", - " \n", - " def display_motion(self, qs, step=1e-1):\n", - " # Given a point path display the smooth movement\n", - " for i in range(len(qs) - 1):\n", - " for q in self.get_path(qs[i], qs[i+1])[:-1]:\n", - " viz.display(q)\n", - " time.sleep(step)\n", - " viz.display(qs[-1])\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "51178d60-0474-4d57-9336-d8f1617b8a4a", - "metadata": {}, - "outputs": [], - "source": [ - "system = System(robot)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "4b0ced1c-2211-459a-aeb3-fb9c3b25085d", - "metadata": {}, - "outputs": [], - "source": [ - "system.distance(q_i, q_g)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "9fafd71f-87f0-44b3-a92c-48f53b6580ac", - "metadata": {}, - "outputs": [], - "source": [ - "system.display_motion(system.get_path(q_i, q_g))" - ] - }, - { - "cell_type": "markdown", - "id": "914d0701-bc8f-46c0-8888-8e019f15cfc3", - "metadata": {}, - "source": [ - "## RRT implementation" - ] - }, - { - "cell_type": "markdown", - "id": "3a64cb4c-28b0-4e66-9324-1cba47374186", - "metadata": {}, - "source": [ - "In its most simple form, RRT construct a tree from the start, eventually with a bias toward the goal. In the following class, we add some memoization to avoid recomputing distances. The kNN (k Nearest Neighbors) structure works on node indices." - ] - }, - { - "cell_type": "markdown", - "id": "3b1a4b31-07d2-463f-851e-cd4d2ca09bbf", - "metadata": {}, - "source": [ - "Let us look at an implementation the core algorithm:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "a62a504d-9ac1-4bcc-a149-cd6516f90a0e", - "metadata": {}, - "outputs": [], - "source": [ - "class RRT():\n", - " \"\"\"\n", - " Can be splited into RRT base because different rrt\n", - " have factorisable logic\n", - " \"\"\"\n", - " def __init__(\n", - " self,\n", - " system,\n", - " node_max=500000,\n", - " iter_max=1000000,\n", - " N_bias=10,\n", - " l_min=.2,\n", - " l_max=.5,\n", - " steer_delta=.1,\n", - " ):\n", - " \"\"\"\n", - " [Here, in proper code, we would document the parameters of our function. Do that below,\n", - " using the Google style for docstrings.]\n", - " https://sphinxcontrib-napoleon.readthedocs.io/en/latest/example_google.html\n", - "\n", - " Args:\n", - " node_max: ...\n", - " iter_max: ...\n", - " ...\n", - " \"\"\"\n", - " self.system = system\n", - " # params\n", - " self.l_max = l_max\n", - " self.l_min = l_min\n", - " self.N_bias = N_bias\n", - " self.node_max = node_max\n", - " self.iter_max = iter_max\n", - " self.steer_delta = steer_delta\n", - " # intern\n", - " self.NNtree = None\n", - " self.storage = None\n", - " self.pathtree = None\n", - " # The distance function will be called on N, dim object\n", - " self.real_distance = self.system.distance\n", - " # Internal for computational_opti in calculating distance\n", - " self._candidate = None\n", - " self._goal = None\n", - " self._cached_dist_to_candidate = {}\n", - " self._cached_dist_to_goal = {}\n", - "\n", - " def distance(self, q1_idx, q2_idx):\n", - " if isinstance(q2_idx, int):\n", - " if q1_idx == q2_idx:\n", - " return 0.\n", - " if q1_idx == -1 or q2_idx == -1:\n", - " if q2_idx == -1:\n", - " q1_idx, q2_idx = q2_idx, q1_idx\n", - " if q2_idx not in self._cached_dist_to_candidate:\n", - " self._cached_dist_to_candidate[q2_idx] = self.real_distance(\n", - " self._candidate, self.storage[q2_idx]\n", - " )\n", - " return self._cached_dist_to_candidate[q2_idx]\n", - " if q1_idx == -2 or q2_idx == -2:\n", - " if q2_idx == -2:\n", - " q1_idx, q2_idx = q2_idx, q1_idx\n", - " if q2_idx not in self._cached_dist_to_goal:\n", - " self._cached_dist_to_goal[q2_idx] = self.real_distance(\n", - " self._goal, self.storage[q2_idx]\n", - " )\n", - " return self._cached_dist_to_goal[q2_idx]\n", - " return self.real_distance(self.storage[q1_idx], self.storage[q2_idx])\n", - " if q1_idx == -1:\n", - " q = self._candidate\n", - " elif q1_idx == -2:\n", - " q = self._goal\n", - " else:\n", - " q = self.storage[q1_idx]\n", - " return self.real_distance(q, self.storage[q2_idx])\n", - "\n", - " def new_candidate(self):\n", - " q = self.system.random_config(free=True)\n", - " self._candidate = q\n", - " self._cached_dist_to_candidate = {}\n", - " return q\n", - "\n", - " def solve(self, qi, validate, qg=None):\n", - " self.system.reset()\n", - " self._goal = qg\n", - " \n", - " # Reset internal datastructures\n", - " self.storage = Storage(self.node_max, self.system.nq)\n", - " self.pathtree = PathTree(self.storage)\n", - " self.NNtree = MTree(self.distance)\n", - " qi_idx = self.storage.add_point(qi)\n", - " self.NNtree.add_point(qi_idx)\n", - " self.it_trace = []\n", - "\n", - " found = False\n", - " iterator = range(self.iter_max)\n", - " for i in tqdm(iterator):\n", - " # New candidate\n", - " if i % self.N_bias == 0:\n", - " q_new = self._goal\n", - " q_new_idx = -2\n", - " else:\n", - " q_new = self.new_candidate()\n", - " q_new_idx = -1\n", - "\n", - " # Find closest neighboor to q_new\n", - " q_near_idx, d = self.NNtree.nearest_neighbour(q_new_idx)\n", - " \n", - " # Steer from it toward the new checking for colision\n", - " success, q_prox = self.system.is_free_path(\n", - " self.storage.data[q_near_idx],\n", - " q_new,\n", - " l_min=self.l_min,\n", - " l_max=self.l_max,\n", - " eps=self.steer_delta\n", - " )\n", - "\n", - " if not success:\n", - " self.it_trace.append(0)\n", - " continue\n", - " self.it_trace.append(1)\n", - " \n", - " # Add the points in data structures\n", - " q_prox_idx = self.storage.add_point(q_prox)\n", - " self.NNtree.add_point(q_prox_idx)\n", - " self.pathtree.update_link(q_prox_idx, q_near_idx)\n", - " self.system.display_edge(self.storage[q_near_idx], self.storage[q_prox_idx])\n", - "\n", - " # Test if it reach the goal\n", - " if validate(q_prox):\n", - " q_g_idx = self.storage.add_point(q_prox)\n", - " self.NNtree.add_point(q_g_idx)\n", - " self.pathtree.update_link(q_g_idx, q_prox_idx)\n", - " found = True\n", - " break\n", - " self.iter_done = i + 1\n", - " self.found = found\n", - " return found\n", - "\n", - " def get_path(self, q_g):\n", - " assert self.found\n", - " path = self.pathtree.get_path()\n", - " return np.concatenate([path, q_g[None, :]])\n" - ] - }, - { - "cell_type": "markdown", - "id": "73533b79-9692-4856-8094-b4874e3944ef", - "metadata": {}, - "source": [ - "In proper code, we would document the parameters of our functions.\n", - "\n", - "- **Your turn:** Add docstrings to the code above, following the [Google style](https://sphinxcontrib-napoleon.readthedocs.io/en/latest/example_google.html).\n", - "- Optional: you are welcome to add type annotations if you'd like.\n", - "\n", - "The constructor of the `RRT` class invites you to start." - ] - }, - { - "cell_type": "markdown", - "id": "811cc5ae-b601-477d-9d55-e560d0e45262", - "metadata": {}, - "source": [ - "For this problem, we will instantiate our RRT with the following parameters:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "676b991b-32d1-4e2f-8dd9-ed85252e180c", - "metadata": {}, - "outputs": [], - "source": [ - "rrt = RRT(\n", - " system,\n", - " N_bias=20,\n", - " l_min=0.2,\n", - " l_max=0.5,\n", - " steer_delta=0.1,\n", - ")" - ] - }, - { - "cell_type": "markdown", - "id": "f20ecc74-a2b6-4b91-8131-cbb7ff3e13a9", - "metadata": {}, - "source": [ - "Now let's define our termination condition, and run the main function:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "de20f3cc-6df3-4e5c-ab5b-e183616d4a2e", - "metadata": {}, - "outputs": [], - "source": [ - "eps_final = .1\n", - "def validation(key):\n", - " vec = robot.framePlacement(key, 22).translation - robot.framePlacement(q_g, 22).translation\n", - " return (float(np.linalg.norm(vec)) < eps_final)\n", - "\n", - "rrt.solve(q_i, validation, qg=q_g)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "7f3a6a8d-4fd9-419b-8176-214543c08a22", - "metadata": {}, - "outputs": [], - "source": [ - "system.display_motion(rrt.get_path(q_g))" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "d82012a2-c7c4-4362-85ae-2c8e67a2e2a4", - "metadata": {}, - "outputs": [], - "source": [ - "system.reset()" - ] - }, - { - "cell_type": "markdown", - "id": "3bd7d92a-abea-482b-8a91-a5942a125585", - "metadata": {}, - "source": [ - "## Create obstacle with environments" - ] - }, - { - "cell_type": "markdown", - "id": "8784c9ad-ab66-4440-9a0f-1a1e10ab4b2d", - "metadata": {}, - "source": [ - "We already had some simple algorithms to find free paths, *i.e.* without obstacles. Let us now add some obstacles to the environment:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "5efbc0a8-bd55-4122-b09a-168b64f8de19", - "metadata": {}, - "outputs": [], - "source": [ - "robot = robex.load('ur5')\n", - "collision_model = robot.collision_model\n", - "visual_model = robot.visual_model" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "189570f8-d592-4f6d-b3d7-89a466fdf898", - "metadata": {}, - "outputs": [], - "source": [ - "def addCylinderToUniverse(name, radius, length, placement, color=colors.red):\n", - " geom = pin.GeometryObject(\n", - " name,\n", - " 0,\n", - " hppfcl.Cylinder(radius, length),\n", - " placement\n", - " )\n", - " new_id = collision_model.addGeometryObject(geom)\n", - " geom.meshColor = np.array(color)\n", - " visual_model.addGeometryObject(geom)\n", - " \n", - " for link_id in range(robot.model.nq):\n", - " collision_model.addCollisionPair(\n", - " pin.CollisionPair(link_id, new_id)\n", - " )\n", - " return geom" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "4c0b531f-992c-47cc-b101-d1113a2f0870", - "metadata": {}, - "outputs": [], - "source": [ - "from pinocchio.utils import rotate\n", - "\n", - "[collision_model.removeGeometryObject(e.name) for e in collision_model.geometryObjects if e.name.startswith('world/')]\n", - "\n", - "# Add a red box in the viewer\n", - "radius = 0.1\n", - "length = 1.\n", - "\n", - "cylID = \"world/cyl1\"\n", - "placement = pin.SE3(pin.SE3(rotate('z',np.pi/2), np.array([-0.5,0.4,0.5])))\n", - "addCylinderToUniverse(cylID,radius,length,placement,color=[.7,.7,0.98,1])\n", - "\n", - "\n", - "cylID = \"world/cyl2\"\n", - "placement = pin.SE3(pin.SE3(rotate('z',np.pi/2), np.array([-0.5,-0.4,0.5])))\n", - "addCylinderToUniverse(cylID,radius,length,placement,color=[.7,.7,0.98,1])\n", - "\n", - "cylID = \"world/cyl3\"\n", - "placement = pin.SE3(pin.SE3(rotate('z',np.pi/2), np.array([-0.5,0.7,0.5])))\n", - "addCylinderToUniverse(cylID,radius,length,placement,color=[.7,.7,0.98,1])\n", - "\n", - "\n", - "cylID = \"world/cyl4\"\n", - "placement = pin.SE3(pin.SE3(rotate('z',np.pi/2), np.array([-0.5,-0.7,0.5])))\n", - "addCylinderToUniverse(cylID,radius,length,placement,color=[.7,.7,0.98,1])" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "6780c139-e2de-4c9f-8af4-61cb1e7e1b4e", - "metadata": {}, - "outputs": [], - "source": [ - "q_i = np.array([-1., -1.5, 2.1, -.5, -.5, 0])\n", - "q_g = np.array([3.1, -1., 1, -.5, -.5, 0])\n", - "radius = 0.05" - ] - }, - { - "cell_type": "markdown", - "id": "c114f554-6126-47e9-8749-934d47d2c7c1", - "metadata": {}, - "source": [ - "We need to reload the viewer" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "62ab0ec0-5faf-43fc-bcd8-9ad9cbe3ad56", - "metadata": {}, - "outputs": [], - "source": [ - "viz = MeshcatVisualizer(robot)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "037ac2f5-e0d3-438a-ab10-9f313a8f8803", - "metadata": {}, - "outputs": [], - "source": [ - "viz.display(q_i)\n", - "M = robot.framePlacement(q_i, 22)\n", - "name = \"world/sph_initial\"\n", - "viz.addSphere(name, radius, [0., 1., 0., 1.])\n", - "viz.applyConfiguration(name,M)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "5e5dfe04-e29d-4455-ba00-c7c158a8930c", - "metadata": { - "tags": [] - }, - "outputs": [], - "source": [ - "viz.display(q_g)\n", - "M = robot.framePlacement(q_g, 22)\n", - "name = \"world/sph_goal\"\n", - "viz.addSphere(name, radius, [0., 0., 1., 1.])\n", - "viz.applyConfiguration(name,M)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "6f17610e-e874-4e4f-aaf7-6c6d569f965e", - "metadata": {}, - "outputs": [], - "source": [ - "viz.display(q_g)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "e19068e5-033b-412d-8d64-ffef4def949a", - "metadata": {}, - "outputs": [], - "source": [ - "system = System(robot)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "661a6589-36ff-44c5-b761-c6f588a8eab7", - "metadata": {}, - "outputs": [], - "source": [ - "rrt = RRT(\n", - " system,\n", - " N_bias=20,\n", - " l_min=0.2,\n", - " l_max=0.5,\n", - " steer_delta=0.1,\n", - ")" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "ffa971ee-6396-4533-b875-5c4e7124bc7a", - "metadata": {}, - "outputs": [], - "source": [ - "eps_final = .1\n", - "\n", - "def validation(key):\n", - " vec = robot.framePlacement(key, 22).translation - robot.framePlacement(q_g, 22).translation\n", - " return (float(np.linalg.norm(vec)) < eps_final)\n", - "\n", - "rrt.solve(q_i, validation, qg=q_g)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "cf22611e-ba2d-4c0e-93a8-03ff922b6073", - "metadata": {}, - "outputs": [], - "source": [ - "system.display_motion(rrt.get_path(q_g))" - ] - }, - { - "cell_type": "markdown", - "id": "160cf161-755f-430e-8e91-e926f644fbe2", - "metadata": {}, - "source": [ - "And solve RRT. It is long right ? Let us implement more efficient algorithms" - ] - }, - { - "cell_type": "markdown", - "id": "c90f1487-cd74-4eb8-8f3f-a0f5e65a1aad", - "metadata": {}, - "source": [ - "## Bi-RRT" - ] - }, - { - "cell_type": "markdown", - "id": "d526af5b-9c37-425f-a30c-45bb80588404", - "metadata": {}, - "source": [ - "Now it's your turn. Make a `BiRRT` class, similar to the `RRT` class above, but implementing the Bi-RRT algorithm. (It is not recommended to try to inherit from `RRT`, as you will end up re-implementing most functions.) Here is a template you are free to adapt, with some advice:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "c003e3fe-a042-4e3a-b644-f607acb9faef", - "metadata": {}, - "outputs": [], - "source": [ - "class BiRRT(RRT):\n", - " def __init__(\n", - " self,\n", - " system,\n", - " node_max=500000,\n", - " iter_max=1000000,\n", - " l_min=.2,\n", - " l_max=.5,\n", - " steer_delta=.1,\n", - " ):\n", - " # Initialize attributes:\n", - " # self.l_min = l_min\n", - " # etc.\n", - "\n", - " # New: duplicate this attribute as dictionaries with two keys:\n", - " # \"forward\" and \"backward\". See `solve` below.\n", - " self._cached_dist_to_candidate = {}\n", - " self.storage = {}\n", - " self.pathtree = {}\n", - " self.tree = {}\n", - "\n", - " def tree_distance(self, direction: str, q1_idx, q2_idx):\n", - " # Adapt from RRT.distance\n", - " # There is now a direction string to select the underlying tree,\n", - " # either \"forward\" (from q_init) or \"backward\" (from q_goal).\n", - "\n", - " def forward_distance(self, q1_idx, q2_idx):\n", - " return self.tree_distance(\"forward\", q1_idx, q2_idx)\n", - "\n", - " def backward_distance(self, q1_idx, q2_idx):\n", - " return self.tree_distance(\"backward\", q1_idx, q2_idx)\n", - "\n", - " def new_candidate(self):\n", - " # A minor change is required to adapt RRT.new_candidate to this template.\n", - "\n", - " def solve(self, qi, validate, qg=None):\n", - " # Reset internal datastructures\n", - " for direction in (\"forward\", \"backward\"):\n", - " self._cached_dist_to_candidate[direction] = {}\n", - " self.storage[direction] = Storage(node_max, system.nq)\n", - " self.pathtree[direction] = PathTree(self.storage[direction])\n", - " self.tree = {\n", - " \"forward\": MTree(self.forward_distance),\n", - " \"backward\": MTree(self.backward_distance),\n", - " }\n", - "\n", - " # Now datastructures are initialized\n", - " # The rest is up to you! \n", - "\n", - " def get_path(self):\n", - " assert self.found\n", - " forward_path = self.pathtree[\"forward\"].get_path()\n", - " backward_path = self.pathtree[\"backward\"].get_path()\n", - " return np.concatenate([forward_path, backward_path[::-1]])" - ] - }, - { - "cell_type": "markdown", - "id": "5254b62c-673f-407d-a0e6-effd3e75aabb", - "metadata": {}, - "source": [ - "You should be able to call `BiRRT` similarly to `RRT`:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "60443eb2-ea54-4c0b-8d24-1908a4ca710b", - "metadata": {}, - "outputs": [], - "source": [ - "system.reset()\n", - "\n", - "birrt = BiRRT(\n", - " system,\n", - " l_min=0.2,\n", - " l_max=0.5,\n", - " steer_delta=0.1,\n", - ")\n", - "\n", - "birrt.solve(q_i, validation, qg=q_g)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "b62f8275-b4d7-4168-ad6c-e437d0ea2887", - "metadata": {}, - "outputs": [], - "source": [ - "system.display_motion(birrt.get_path())" - ] - }, - { - "cell_type": "markdown", - "id": "a291e25d-46a4-47b3-b894-8d5810196d39", - "metadata": {}, - "source": [ - "How many iterations did it take to find a solution? Is it faster than previously with `RRT`?" - ] - }, - { - "cell_type": "markdown", - "id": "84285a1d-ac59-40c9-aef1-23527d0bab54", - "metadata": {}, - "source": [ - "## Bonus question: Bi-RRT*" - ] - }, - { - "cell_type": "markdown", - "id": "6212a5aa-5794-48c6-91e5-f70c3ade34fa", - "metadata": {}, - "source": [ - "Implement an optimal variant `BiRRTStar` of your `BiRRT` class and run it in the same configuration as the two algorithms above. What do you notice about the resulting tree? What is the improvement in overall path length between `RRT`, `BiRRT` and `BiRRTStar`?" - ] - } - ], - "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.9.18" - } - }, - "nbformat": 4, - "nbformat_minor": 5 -} diff --git a/7_reinforcement_learning.ipynb b/7_reinforcement_learning.ipynb deleted file mode 100644 index 36f9aac..0000000 --- a/7_reinforcement_learning.ipynb +++ /dev/null @@ -1,981 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "id": "589389e6-2aad-45b6-bc03-e9b37ab1514f", - "metadata": {}, - "source": [ - "# Reinforcement learning for legged robots\n", - "\n", - "## Setup\n", - "\n", - "Before we start, you will need to update your conda environment to use Gymnasium (maintained) rather than OpenAI Gym (discontinued). You can simply run:\n", - "\n", - "```\n", - "conda env create -f robotics_rl_env.yml\n", - "conda activate robotics_course_rl\n", - "```" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "b3fa7b15-843f-4696-9bfc-141da71bf7d1", - "metadata": {}, - "outputs": [], - "source": [ - "import gymnasium as gym\n", - "import stable_baselines3" - ] - }, - { - "cell_type": "markdown", - "id": "8e264559-88cc-48b7-8257-f7755fff3ce7", - "metadata": {}, - "source": [ - "Let's import the usual suspects as well:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "86303cf2-f879-407d-b528-6c0a80b8df20", - "metadata": {}, - "outputs": [], - "source": [ - "import matplotlib.pylab as plt\n", - "import numpy as np\n", - "\n", - "plt.ion()" - ] - }, - { - "cell_type": "markdown", - "id": "b09e16a1-bf4a-403b-8709-3da11bc3c4b4", - "metadata": {}, - "source": [ - "# Inverted pendulum environment\n", - "\n", - "The inverted pendulum model is not just a toy model reproducing the properties of real robot models for balancing: as it turns out, the inverted pendulum appears in the dynamics of *any* mobile robot, that is, a model with a floating-base joint at the root of the kinematic tree. (If you are curious: the inverted pendulum is a limit case of the [Newton-Euler equations](https://scaron.info/robotics/newton-euler-equations.html) corresponding to floating-base coordinates in the equations of motion $M \\ddot{q} + h = S^T \\tau + J_c^T f$, in the limit where the robot [does not vary its angular momentum](https://scaron.info/robotics/point-mass-model.html).) Thus, while we work on a simplified inverted pendulum in this notebook, concepts and tools are those used as-is on real robots, as you can verify by exploring the bonus section.\n", - "\n", - "Gymnasium is mainly a single-agent reinforcement learning API, but it also comes with simple environments, including an inverted pendulum sliding on a linear guide:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "11b5d942-85fa-435e-b5ef-8c85a74ba3db", - "metadata": {}, - "outputs": [], - "source": [ - "with gym.make(\"InvertedPendulum-v4\", render_mode=\"human\") as env:\n", - " action = 0.0 * env.action_space.sample()\n", - " observation, _ = env.reset()\n", - " episode_return = 0.0\n", - " for step in range(200):\n", - " # action[0] = 5.0 * observation[1] + 0.3 * observation[0]\n", - " observation, reward, terminated, truncated, _ = env.step(action)\n", - " episode_return += reward\n", - " if terminated or truncated:\n", - " observation, _ = env.reset()\n", - " print(f\"Return of the episode: {episode_return}\")" - ] - }, - { - "cell_type": "markdown", - "id": "d7322422-94db-4e12-b299-36bb40649cf7", - "metadata": {}, - "source": [ - "The structure of the action and observation vectors are documented in [Inverted Pendulum - Gymnasium Documentation](https://gymnasium.farama.org/environments/mujoco/inverted_pendulum/). The observation, in particular, is a NumPy array with four coordinates that we recall here for reference:\n", - "\n", - "| Num | Observation | Min | Max | Unit |\n", - "|-----|-------------|-----|-----|------|\n", - "| 0 | position of the cart along the linear surface | -Inf | Inf | position (m) |\n", - "| 1 | vertical angle of the pole on the cart | -Inf | Inf | angle (rad) |\n", - "| 2 | linear velocity of the cart | -Inf | Inf | linear velocity (m/s) |\n", - "| 3 | angular velocity of the pole on the cart | -Inf | Inf | anglular velocity (rad/s) |\n", - "\n", - "We will use the following labels to annotate plots:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "a3231c70-f49d-49be-b260-aadbade7b403", - "metadata": {}, - "outputs": [], - "source": [ - "OBSERVATION_LEGEND = (\"pitch\", \"position\", \"linear_velocity\", \"angular_velocity\")" - ] - }, - { - "cell_type": "markdown", - "id": "aa062536-204c-4312-a858-f992f3db61d6", - "metadata": {}, - "source": [ - "Check out the documentation for the definitions of the action and rewards." - ] - }, - { - "cell_type": "markdown", - "id": "c285d7ce-3a97-4b07-8b5f-a9b04d7721ab", - "metadata": {}, - "source": [ - "# PID control\n", - "\n", - "A *massively* used class of policies is the [PID controller](https://en.wikipedia.org/wiki/Proportional%E2%80%93integral%E2%80%93derivative_controller). Let's say we have a reference observation, like $o^* = [0\\ 0\\ 0\\ 0]$ for the inverted pendulum. Denoting by $e(t) = o^* - o(t)$ the *error* of the system when it observes a given state, a continuous-time PID controller will apply the action:\n", - "\n", - "$$\n", - "a(t) = K_p^T e(t) + K_d^T \\dot{e}(t) + K_i^T \\int e(\\tau) \\mathrm{d} \\tau\n", - "$$\n", - "\n", - "where $K_{p}, K_i, K_d \\in \\mathbb{R}^4$ are constants called *gains* and tuned by the user. In discrete time the idea is the same:\n", - "\n", - "$$\n", - "a_k = K_p^T e_k + K_d^T \\frac{e_k - e_{k-1}}{\\delta t} + K_i^T \\sum_{i=0}^{k} e_i {\\delta t}\n", - "$$" - ] - }, - { - "cell_type": "markdown", - "id": "63c381eb-fca9-4ef4-8f99-3b1943231654", - "metadata": {}, - "source": [ - "Let's refactor the rolling out of our episode into a standalone function:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "9c839bc6-168a-42c3-8f1c-c6b0c5411901", - "metadata": {}, - "outputs": [], - "source": [ - "def rollout_from_env(env, policy):\n", - " episode = []\n", - " observation, _ = env.reset()\n", - " episode.append(observation)\n", - " for step in range(1000):\n", - " action = policy(observation)\n", - " observation, reward, terminated, truncated, _ = env.step(action)\n", - " episode.extend([action, reward, observation])\n", - " if terminated or truncated:\n", - " return episode\n", - " return episode\n", - "\n", - "def rollout(policy, show: bool = True):\n", - " kwargs = {\"render_mode\": \"human\"} if show else {}\n", - " with gym.make(\"InvertedPendulum-v4\", **kwargs) as env:\n", - " episode = rollout_from_env(env, policy)\n", - " return episode" - ] - }, - { - "cell_type": "markdown", - "id": "79ff0dce-a4df-4917-bb17-2393353610a3", - "metadata": {}, - "source": [ - "## Question 1: Write a PID controller that balances the inverted pendulum" - ] - }, - { - "cell_type": "markdown", - "id": "e7cfb28b-ff73-42ff-9524-eac8ec12f8a1", - "metadata": {}, - "source": [ - "You can use global variables to store the (discrete) derivative and integral terms, this will be OK here as we only rollout a single trajectory:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "045ddcef-c0f7-4251-b73f-d5df5a0027e5", - "metadata": {}, - "outputs": [], - "source": [ - "def pid_policy(observation: np.ndarray) -> np.ndarray:\n", - " my_action_value: float = 0.0 # your action here\n", - " return np.array([my_action_value])\n", - "\n", - "episode = rollout(pid_policy, show=False)" - ] - }, - { - "cell_type": "markdown", - "id": "a0a005aa-87fa-4f98-8ace-f24421886bed", - "metadata": {}, - "source": [ - "You can look at the system using `show=True`, but intuition usually builds faster when looking at relevant plots:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "9aa5decd-779c-4f0d-84fd-3eb47358b7fa", - "metadata": {}, - "outputs": [], - "source": [ - "observations = np.array(episode[::3])\n", - "\n", - "plt.plot(observations)\n", - "plt.legend(OBSERVATION_LEGEND)" - ] - }, - { - "cell_type": "markdown", - "id": "98d50cd2-26fa-4d3c-a671-1ed0e1b9ee93", - "metadata": {}, - "source": [ - "Can you reach the full reward of 1000 steps?" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "8bacbd0a-2ac5-44cf-848b-8ebfb6fe35d7", - "metadata": {}, - "outputs": [], - "source": [ - "print(f\"Return of the episode: {sum(episode[2::3])}\")" - ] - }, - { - "cell_type": "markdown", - "id": "b17cc998-1b23-416f-8e3b-810100c223fb", - "metadata": {}, - "source": [ - "# Policy optimization\n", - "\n", - "Let us now train a policy, parameterized by a multilayer perceptron (MLP), to maximize the expected return over episodes on the inverted pendulum environment." - ] - }, - { - "cell_type": "markdown", - "id": "d5631f0f-1b84-4ee6-8e9c-b4f2915bd281", - "metadata": {}, - "source": [ - "## Our very first policy\n", - "\n", - "We will use the proximal policy optimization (PPO) algorithm for training, using the implementation from Stable Baselines3: [PPO - Stable Baselines3 documentation](https://stable-baselines3.readthedocs.io/en/master/modules/ppo.html)." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "128867ca-e600-4ba1-abbd-1f918976fba2", - "metadata": {}, - "outputs": [], - "source": [ - "from stable_baselines3 import PPO\n", - "\n", - "with gym.make(\"InvertedPendulum-v4\", render_mode=\"human\") as env:\n", - " first_policy = PPO(\"MlpPolicy\", env, verbose=0)\n", - " first_policy.learn(total_timesteps=1000, progress_bar=False)" - ] - }, - { - "cell_type": "markdown", - "id": "6323400b-18ca-43f6-a81e-a5e7f033a536", - "metadata": {}, - "source": [ - "By instantiating the algorithm with no further ado, we let the library decide for us on a sane set of default hyperparameters, including:\n", - "\n", - "- Rollout buffers of `n_steps = 2048` steps, which we will visit `n_epochs = 10` times with mini-batches of size `batch_size = 64`.\n", - "- Clipping range: ``0.2``.\n", - "- No entropy regularization.\n", - "- Learning rate for the Adam optimizer: ``3e-4``\n", - "- Policy and value-function network architectures: two layers of 64 neurons with $\\tanh$ activation functions.\n", - "\n", - "We then called the `learn` function to execute PPO over a fixed total number of timesteps, here just a thousand." - ] - }, - { - "cell_type": "markdown", - "id": "8b82173c-6609-4b83-8618-36f82c1c1373", - "metadata": {}, - "source": [ - "Rendering actually took a significant chunk of time. Let's instantiate and keep an environment open without rendering:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "460fe1c7-ee3b-450a-b09c-03b96f9086bf", - "metadata": {}, - "outputs": [], - "source": [ - "env = gym.make(\"InvertedPendulum-v4\")" - ] - }, - { - "cell_type": "markdown", - "id": "a9bd090f-ca34-41e0-9900-52977eef9c4b", - "metadata": {}, - "source": [ - "We can use it to train much more steps in roughly the same time, reporting training metrics every `n_steps` step:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "b7262602-c277-4697-8987-ba126a87e75b", - "metadata": {}, - "outputs": [], - "source": [ - "second_policy = PPO(\"MlpPolicy\", env, verbose=1)\n", - "second_policy.learn(total_timesteps=10_000, progress_bar=False)" - ] - }, - { - "cell_type": "markdown", - "id": "6219aab8-1143-4606-a44f-b62fdffebbf1", - "metadata": {}, - "source": [ - "Let's see how this policy performs:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "f17dc178-bb9c-4155-8047-feed1e575226", - "metadata": {}, - "outputs": [], - "source": [ - "def policy_closure(policy):\n", - " \"\"\"Utility function to turn our policy instance into a function.\n", - "\n", - " Args:\n", - " policy: Policy to turn into a function.\n", - " \n", - " Returns:\n", - " Function from observation to policy action.\n", - " \"\"\"\n", - " def policy_function(observation):\n", - " action, _ = policy.predict(observation)\n", - " return action\n", - " return policy_function" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "7e4e3cd4-4572-4c40-94b1-688d472a4b8c", - "metadata": {}, - "outputs": [], - "source": [ - "episode = rollout(policy_closure(second_policy), show=True)" - ] - }, - { - "cell_type": "markdown", - "id": "941219f1-9b3c-4e66-86e5-d42f2473b149", - "metadata": {}, - "source": [ - "Okay, it looks like we didn't train for long enough!" - ] - }, - { - "cell_type": "markdown", - "id": "195f2a85-8dd7-4f3a-8368-7427f1caadca", - "metadata": {}, - "source": [ - "## Monitoring performance during training\n", - "\n", - "Let's train for longer, and use TensorBoard to keep track. We don't know how long training will take so let's put a rather large total number of steps (you can interrupt training once you observed convergence in TensorBoard):" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "196da0ad-1e83-441e-ac10-6c9ecd83c224", - "metadata": {}, - "outputs": [], - "source": [ - "erudite_policy = PPO(\n", - " \"MlpPolicy\",\n", - " env,\n", - " tensorboard_log=\"./inverted_pendulum_tensorboard/\",\n", - " verbose=0,\n", - ")\n", - "\n", - "erudite_policy.learn(\n", - " total_timesteps=1_000_000,\n", - " progress_bar=False,\n", - " tb_log_name=\"erudite\",\n", - ")" - ] - }, - { - "cell_type": "markdown", - "id": "ad91d14e-53e2-443f-b7ab-edd69d480add", - "metadata": {}, - "source": [ - "Run TensorBoard on the directory thus created to open a dashboard in your Web browser:\n", - "\n", - "```\n", - "tensorboard --logdir ./inverted_pendulum_tensorboard/\n", - "```\n", - "\n", - "The link will typically be http://localhost:6006 (port number increases if you run TensorBoard multiple times in parallel). Tips:\n", - "\n", - "- Click the Settings icon in the top-right corner and enable \"Reload data\"\n", - "- Uncheck \"Ignore outliers in chart scaling\" (your preference)" - ] - }, - { - "cell_type": "markdown", - "id": "68771e35-48cd-43be-89ff-0055dc196d0b", - "metadata": {}, - "source": [ - "## Saving our policy\n", - "\n", - "Now that you spent some computing to optimize an actual policy, better save it to disk:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "effeccfc-8b95-48e1-98c4-1b96838bb28e", - "metadata": {}, - "outputs": [], - "source": [ - "erudite_policy.save(\"pendulum_erudite\")" - ] - }, - { - "cell_type": "markdown", - "id": "ea09c56e-8647-414d-aae0-5e1b16ba3a0f", - "metadata": {}, - "source": [ - "You can then reload it later by:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "994dae4f-b651-4488-925e-2ba369eeedc7", - "metadata": {}, - "outputs": [], - "source": [ - "erudite_policy = PPO.load(\"pendulum_erudite\", env=env)" - ] - }, - { - "cell_type": "markdown", - "id": "dded4f1e-ae57-4c94-b2e1-3a6d019aecc4", - "metadata": {}, - "source": [ - "## Question 2: How many steps does it take to train a successful policy?\n", - "\n", - "We consider a policy successful if it consistently achieves the maximum return of 1000." - ] - }, - { - "cell_type": "raw", - "id": "42c6d68d-4812-4222-97da-a6699803b986", - "metadata": {}, - "source": [ - "== Your reply here ==" - ] - }, - { - "cell_type": "markdown", - "id": "553b846f-db13-43ba-81cb-57b039852c86", - "metadata": {}, - "source": [ - "## A more realistic environment\n", - "\n", - "Real systems suffer from the two main issues we saw in the [Perception and estimation](https://scaron.info/robotics-mva/#5-perception-estimation) class: *bias* and *variance*. In this section, we model bias in actuation and perception by adding delays (via low-pass filtering) to respectively the action and observation vectors. Empirically this is an effective model, as for instance it contributes to sim2real transfer on Upkie. To add these delays, we use an [`environment wrapper`](https://gymnasium.farama.org/api/wrappers/), which is a convenient way to compose environments, used in both the Gymnasium and Stable Baselines3 APIs:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "6e8a3140-7ee7-4d6f-afd9-19d6ca4816c0", - "metadata": {}, - "outputs": [], - "source": [ - "class DelayWrapper(gym.Wrapper):\n", - " def __init__(self, env, time_constant: float = 0.2):\n", - " \"\"\"Wrap environment with some actuation and perception modeling.\n", - "\n", - " Args:\n", - " env: Environment to wrap.\n", - " time_constant: Constant of the internal low-pass filter, in seconds.\n", - " Feel free to play with different values but leave it to the default\n", - " of 0.2 seconds when handing out your homework.\n", - "\n", - " Note:\n", - " Delays are implemented by a low-pass filter. The same time constant\n", - " is used for both actions and observations, which is not realistic, but\n", - " makes for less tutorial code ;)\n", - " \"\"\"\n", - " alpha = env.dt / time_constant\n", - " assert 0.0 < alpha < 1.0\n", - " super().__init__(env)\n", - " self._alpha = alpha\n", - " self._prev_action = 0.0 * env.action_space.sample()\n", - " self._prev_observation = np.zeros(4)\n", - "\n", - " def low_pass_filter(self, old_value, new_value):\n", - " return old_value + self._alpha * (new_value - old_value)\n", - " \n", - " def step(self, action):\n", - " new_action = self.low_pass_filter(self._prev_action, action)\n", - " observation, reward, terminated, truncated, info = self.env.step(new_action)\n", - " new_observation = self.low_pass_filter(self._prev_observation, observation)\n", - " self._prev_action = new_action\n", - " self._prev_observation = new_observation\n", - " return new_observation, reward, terminated, truncated, info\n", - "\n", - "delay_env = DelayWrapper(env)" - ] - }, - { - "cell_type": "markdown", - "id": "b1b5de5e-50ca-4049-bb5f-b9203919e0ba", - "metadata": {}, - "source": [ - "We can check how our current policy fares against the delayed environment. Spoiler alert: no great." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "4e1508e6-e04f-4b22-8009-80baae1bae7d", - "metadata": {}, - "outputs": [], - "source": [ - "delay_episode = rollout_from_env(delay_env, policy_closure(erudite_policy))\n", - "observations = np.array(delay_episode[::3])\n", - "\n", - "plt.plot(observations[:, :2])\n", - "plt.legend(OBSERVATION_LEGEND)" - ] - }, - { - "cell_type": "markdown", - "id": "70af3932-751e-47e4-8334-bd55be62aaa1", - "metadata": {}, - "source": [ - "## Question 3: Can't we just re-train a policy on the new environment?\n", - "\n", - "At this point of the tutorial this is a rethorical question, but we should check anyway. Re-train a policy on the delayed environment and comment on its performance:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "693aa97c-3ee2-4cbd-bc06-7cb224e8bc86", - "metadata": {}, - "outputs": [], - "source": [ - "# Your code here" - ] - }, - { - "cell_type": "raw", - "id": "48928906-bcd9-40d5-b17e-35fd06d6c6ac", - "metadata": {}, - "source": [ - "== Your observations here ==" - ] - }, - { - "cell_type": "markdown", - "id": "c0e2df30-259f-477a-ab14-d39c17e5f15f", - "metadata": {}, - "source": [ - "## The Real Question 3: Why do delays degrade both runtime and training performance?\n", - "\n", - "Loss in runtime performance refers to the one we observed when executing a policy trained without delay on an environment with delays. Loss in training performance refers to the fact that, even when we train a new policy on the environment with delays, by the end of training it does not achieve maximum return." - ] - }, - { - "cell_type": "raw", - "id": "3b7459d5-93d0-49cb-85c7-2172e2b08073", - "metadata": {}, - "source": [ - "== Your explanation here ==" - ] - }, - { - "cell_type": "markdown", - "id": "e63a441a-a84d-49ab-aecc-7362dee66b91", - "metadata": {}, - "source": [ - "Propose and implement a way to overcome this. Train the resulting policy in a variable called `iron_policy`." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "b22770ba-4e58-4989-b62c-d5aa1734336c", - "metadata": {}, - "outputs": [], - "source": [ - "# Your code here" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "5a7a876f-e78e-47bb-9b42-9423618d1e42", - "metadata": {}, - "outputs": [], - "source": [ - "iron_policy.save(\"iron_policy\")" - ] - }, - { - "cell_type": "markdown", - "id": "d2a70b63-7fda-4c0f-b777-ef0dc2128ab2", - "metadata": {}, - "source": [ - "Roll out an episode and plot the outcome to show that your policy handles delays properly." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "45f13a2b-6a1c-4d44-bb84-2fffaf6bf6e3", - "metadata": {}, - "outputs": [], - "source": [ - "# Your episode rollout here\n", - "\n", - "plt.plot(np.array(observations)[:, :2])\n", - "plt.legend(OBSERVATION_LEGEND)" - ] - }, - { - "cell_type": "markdown", - "id": "1e12fcf1-88b9-4899-b79d-866c67e4a3f5", - "metadata": {}, - "source": [ - "## Question 4: Can you improve sampling efficiency?\n", - "\n", - "This last question is open: what can you change in the pipeline to train a policy that achieves maximum return using less samples? Report on at least one thing that allowed you to train with less environment steps." - ] - }, - { - "cell_type": "raw", - "id": "0f5cb9a5-fd18-4077-a6fc-83fa5377de96", - "metadata": {}, - "source": [ - "== Your report here ==" - ] - }, - { - "cell_type": "markdown", - "id": "131966f5-9524-4b44-9843-0c1a662ba2e1", - "metadata": {}, - "source": [ - "Here is a state-of-the-art™ utility function if you want to experiment with scheduling some of the ``Callable[[float], float]`` [hyperparameters](https://stable-baselines3.readthedocs.io/en/master/modules/ppo.html#parameters):" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "3de11ab9-2534-4723-8868-1582772d038c", - "metadata": {}, - "outputs": [], - "source": [ - "def affine_schedule(y_0: float, y_1: float):\n", - " \"\"\"Affine schedule as a function over the [0, 1] interval.\n", - "\n", - " Args:\n", - " y_0: Function value at zero.\n", - " y_1: Function value at one.\n", - " \n", - " Returns:\n", - " Corresponding affine function.\n", - " \"\"\"\n", - " def schedule(x: float) -> float:\n", - " return y_0 + x * (y_1 - y_0)\n", - " return schedule" - ] - }, - { - "cell_type": "markdown", - "id": "b21d78dd-f80e-4183-8fa7-55c803e38404", - "metadata": {}, - "source": [ - "And here is a wrapper template if you want to experiment with reward shaping:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "2cf9a3ed-8f76-4fac-98f2-3a23df818deb", - "metadata": {}, - "outputs": [], - "source": [ - "class CustomRewardWrapper(gym.Wrapper):\n", - " def __init__(self, env):\n", - " super().__init__(env)\n", - "\n", - " def step(self, action):\n", - " observation, reward, terminated, truncated, info = self.env.step(action)\n", - " new_reward = 0.0 # your formula here\n", - " return observation, new_reward, terminated, truncated, info" - ] - }, - { - "cell_type": "markdown", - "id": "2c4dd0df-6dc7-4d51-b29b-c77b49bde437", - "metadata": {}, - "source": [ - "# Bonus: training a policy for a real robot\n", - "\n", - "This section is entirely optional and will only work on Linux or macOS. In this part, we follow the same training pipeline but with the open source software of [Upkie](https://hackaday.io/project/185729-upkie-wheeled-biped-robots)." - ] - }, - { - "cell_type": "markdown", - "id": "9634ff93-f09f-4e0a-8d0f-547848f3900b", - "metadata": {}, - "source": [ - "## Setup\n", - "\n", - "\n", - "\n", - "First, make sure you have a C++ compiler (setup one-liners: [Fedora](https://github.com/upkie/upkie/discussions/100), [Ubuntu](https://github.com/upkie/upkie/discussions/101)). You can run an Upkie simulation right from the command line. It won't install anything on your machine, everything will run locally from the repository:\n", - "\n", - "```console\n", - "git clone https://github.com/upkie/upkie.git\n", - "cd upkie\n", - "git checkout fb9a0ab1f67a8014c08b34d7c0d317c7a8f71662\n", - "./start_simulation.sh\n", - "cd ..\n", - "pip install upkie\n", - "```\n", - "\n", - "**NB:** this tutorial is written for the specific commit checked out above. If some instructions don't work it's likely you forgot to check it out." - ] - }, - { - "cell_type": "markdown", - "id": "ba44abc0-f7e9-4c2b-9d4e-a3579213e138", - "metadata": {}, - "source": [ - "## Stepping the environment\n", - "\n", - "If everything worked well, you should be able to step an environment as follows:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "acedf0d6-fc2f-43f4-9ff6-a8e12dbd7ae0", - "metadata": {}, - "outputs": [], - "source": [ - "import gymnasium as gym\n", - "import upkie.envs\n", - "\n", - "upkie.envs.register()\n", - "\n", - "episode_return = 0.0\n", - "with gym.make(\"UpkieGroundVelocity-v1\", frequency=200.0) as env:\n", - " observation, _ = env.reset() # connects to the spine (simulator or real robot)\n", - " action = 0.0 * env.action_space.sample()\n", - " for step in range(1000):\n", - " pitch = observation[0]\n", - " action[0] = 10.0 * pitch # 1D action: [ground_velocity]\n", - " observation, reward, terminated, truncated, _ = env.step(action)\n", - " episode_return += reward\n", - " if terminated or truncated:\n", - " observation, _ = env.reset()\n", - "\n", - "print(f\"We have stepped the environment {step + 1} times\")\n", - "print(f\"The return of our episode is {episode_return}\")" - ] - }, - { - "cell_type": "markdown", - "id": "031343b5-cf94-46ae-98f3-a4c5ebbc037c", - "metadata": {}, - "source": [ - "(If you see a message \"Waiting for spine /vulp to start\", it means the simulation is not running.)" - ] - }, - { - "cell_type": "markdown", - "id": "aecfd91f-676c-4d6f-beb0-a286dc681ae3", - "metadata": {}, - "source": [ - "We can double-check the last observation from the episode:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "ed6d972f-4cc9-4005-b9a1-4a7433a19938", - "metadata": {}, - "outputs": [], - "source": [ - "def report_last_observation(observation):\n", - " print(\"The last observation of the episode is:\")\n", - " print(f\"- Pitch from torso to world: {observation[0]:.2} rad\")\n", - " print(f\"- Ground position: {observation[1]:.2} m\")\n", - " print(f\"- Angular velocity from torso to world in torso: {observation[2]:.2} rad/s\")\n", - " print(f\"- Ground velocity: {observation[3]:.2} m/s\")\n", - " \n", - "report_last_observation(observation)" - ] - }, - { - "cell_type": "markdown", - "id": "d5a269e3-d876-4d05-88e5-b0d73be6f939", - "metadata": {}, - "source": [ - "## Question B1: PID control\n", - "\n", - "Adapt your code from Question 1 to this environment:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "1e8e9f1e-f2a1-4a18-aa38-256a425d018c", - "metadata": {}, - "outputs": [], - "source": [ - "def policy_b1(observation):\n", - " return np.array([0.0]) # replace with your solution\n", - "\n", - "\n", - "def run(policy, nb_steps: int):\n", - " episode_return = 0.0\n", - " with gym.make(\"UpkieGroundVelocity-v1\", frequency=200.0) as env:\n", - " observation, _ = env.reset() # connects to the spine (simulator or real robot)\n", - " for step in range(nb_steps):\n", - " action = policy_b1(observation)\n", - " observation, reward, terminated, truncated, _ = env.step(action)\n", - " if terminated or truncated:\n", - " print(\"Fall detected!\")\n", - " return episode_return\n", - " report_last_observation(observation)\n", - " return episode_return\n", - "\n", - "\n", - "episode_return = run(policy_b1, 1000)\n", - "print(f\"The return of our episode is {episode_return}\")" - ] - }, - { - "cell_type": "markdown", - "id": "e999eb22-a94a-4a58-ac06-9a7dbc15a7ee", - "metadata": {}, - "source": [ - "## Training a new policy\n", - "\n", - "The Upkie repository ships three agents based on PID control, model predictive control and reinforcement learning. We now focus on the latter, called the \"PPO balancer\".\n", - "\n", - "Check that you can run the training part by running, from the root of the repository:\n", - "\n", - "```\n", - "./tools/bazel run //agents/ppo_balancer:train -- --nb-envs 1 --show\n", - "```\n", - "\n", - "A simulation window should pop, and verbose output from SB3 should be printed to your terminal.\n", - "\n", - "By default, training data will be logged to `/tmp`. You can select a different output path by setting the `UPKIE_TRAINING_PATH` environment variable in your shell. For instance:\n", - "\n", - "```\n", - "export UPKIE_TRAINING_PATH=\"${HOME}/src/upkie/training\"\n", - "```\n", - "\n", - "Run TensorBoard from the training directory:\n", - "\n", - "```\n", - "tensorboard --logdir ${UPKIE_TRAINING_PATH} # or /tmp if you keep the default\n", - "```\n", - "\n", - "Each training will be named after a word picked at random in an English dictionary." - ] - }, - { - "cell_type": "markdown", - "id": "a7e47aad-7787-409c-af7e-b83bfccaa592", - "metadata": {}, - "source": [ - "## Selecting the number of processes\n", - "\n", - "We can increase the number of parallel CPU environments ``--nb-envs`` to a value suitable to your computer. Let training run for a minute and check `time/fps`. Increase the number of environments and compare the stationary regime of `time/fps`. You should see a performance increase when adding the first few environments, followed by a declined when there are two many parallel processes compared to your number of CPU cores. Pick the value that works best for you." - ] - }, - { - "cell_type": "markdown", - "id": "696a0943-cc10-4cd0-a2d8-d5313dbe37e5", - "metadata": {}, - "source": [ - "## Running a trained policy\n", - "\n", - "Copy the file `final.zip` from your trained policy directory to `agents/ppo_balancer/policy/params.zip`. Start a simulation and run the policy by:\n", - "\n", - "```\n", - "./tools/bazel run //agents/ppo_balancer\n", - "```\n", - "\n", - "What kind of behavior do you observe?" - ] - }, - { - "cell_type": "raw", - "id": "eaabe73c-f412-44b5-a714-241077720d01", - "metadata": {}, - "source": [ - "== Your observations here ==" - ] - }, - { - "cell_type": "markdown", - "id": "6c356c81-b5ef-4364-a5db-c8e2600e104a", - "metadata": {}, - "source": [ - "## Question B2: Improve this baseline" - ] - }, - { - "cell_type": "markdown", - "id": "527ecb8c-7292-432f-b0d3-b90c36de8719", - "metadata": {}, - "source": [ - "The policy you are testing here is not the one we saw in class. Open question: improve on it using any of the methods we discussed. Measure the improvement by `ep_len_mean` or any other quantitative criterion:" - ] - }, - { - "cell_type": "raw", - "id": "ce7d720b-17b8-493d-8128-e66c6571d3ff", - "metadata": {}, - "source": [ - "== Your experiments here ==\n", - "\n", - "- Tried: ... / Measured outcome: ..." - ] - } - ], - "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.10.13" - } - }, - "nbformat": 4, - "nbformat_minor": 5 -} diff --git a/_meta.md b/_meta.md deleted file mode 100644 index 4db59d4..0000000 --- a/_meta.md +++ /dev/null @@ -1,15 +0,0 @@ -## TODO -- Update from 2022 running TPs -- Clear all output for pushed version -- Add LQR finite horizon -- Add GJK-2D -- Add Other planning algorithm - -## For deployments -- create virgin repo and copy all the content -- do -``` -rm [0-9]* -rm -r tp[0-9]* -``` -- add tpX folder and X_ notebooks incrementaly. diff --git a/dynamics.ipynb b/dynamics.ipynb new file mode 100644 index 0000000..62cbb6f --- /dev/null +++ b/dynamics.ipynb @@ -0,0 +1,233 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import time\n", + "import numpy as np\n", + "import pinocchio as pin\n", + "from robot_descriptions.loaders.pinocchio import load_robot_description\n", + "from utils.meshcat_viewer_wrapper import MeshcatVisualizer\n" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "You can open the visualizer by visiting the following URL:\n", + "http://127.0.0.1:7000/static/\n" + ] + } + ], + "source": [ + "robot = load_robot_description('ur5_description')\n", + "viz = MeshcatVisualizer(robot)" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "q = pin.neutral(robot.model)\n", + "viz.display(q)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Given the rigid body dynamics equation we learned from the lecture:\n", + "$$\n", + "M(q)\\ddot{q} = \\tau(t) - h(q, \\dot{q}) - J_{ee}^{\\mathrm{T}}(q)\\mathcal{F}_{ee}\n", + "$$\n", + "We can use pinocchio to calculate the mass matrix M via the composite rigid body algorithm and the nonlinear effects h." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "vq = np.zeros(robot.model.nv)\n", + "M = pin.crba(robot.model, robot.data, q)\n", + "h = pin.nle(robot.model, robot.data, q, vq)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "In order to simulate the forward dynamics we can solve directly for $\\ddot{q}$:\n", + "$$\n", + "\\ddot{q} = M(q)^{-1}(\\tau(t) - h(q, \\dot{q}) - J_{ee}^{\\mathrm{T}}(q)\\mathcal{F}_{ee})\n", + "$$\n", + "This can be done directly with pinoccio by using the articulated body algorithm aba. Read through the loop below and run the cell to see the dynamics simulation." + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "q = np.array([0,-np.pi/2,0,0,0,0])\n", + "vq = np.zeros(robot.model.nv)\n", + "viz.display(q)\n", + "\n", + "dt = 2e-3\n", + "N_steps = 5000\n", + "\n", + "for it in range(N_steps):\n", + " t = it*dt\n", + "\n", + " # Compute the force that apply\n", + " tauq = np.zeros(robot.model.nv)\n", + "\n", + " # Use aba forward dynamics to calculate aq\n", + " aq = pin.aba(robot.model, robot.data, q, vq, tauq)\n", + "\n", + " # Double integration to update vq and q\n", + " vq += aq * dt\n", + " q = pin.integrate(robot.model, q, vq * dt)\n", + "\n", + " # Visualization\n", + " if it%20==0: \n", + " viz.display(q)\n", + " time.sleep(20*dt)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now lets add friction to the dynamics. Fill in the missing code for aq. This time don't use the aba, but write it directly so you can add a friction term $\\mathcal{K}\\dot{q}$ to simulate the dynamics with friction. " + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [], + "source": [ + "q = np.array([0,-np.pi/2,0,0,0,0])\n", + "vq = np.zeros(robot.model.nv)\n", + "viz.display(q)\n", + "\n", + "dt = 2e-3\n", + "N_steps = 5000\n", + "Kf = 0.3\n", + "\n", + "for it in range(N_steps):\n", + " t = it*dt\n", + "\n", + " M = pin.crba(robot.model, robot.data, q)\n", + " b = pin.nle(robot.model, robot.data, q, vq)\n", + "\n", + " # Zero torque applied at the joints\n", + " tauq = np.zeros(robot.model.nv)\n", + "\n", + " # Dynamics equation with friction\n", + " aq = np.linalg.pinv(M) @ (tauq - Kf * vq - b)\n", + " # Double integration to update vq and q\n", + " vq += aq * dt\n", + " q = pin.integrate(robot.model, q, vq * dt)\n", + "\n", + " # Visualization\n", + " if it%20==0: \n", + " viz.display(q)\n", + " time.sleep(20*dt)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can also solve the inverse dynamics using the recursive newton euler algorithm. This will find the torques $\\tau$ for a given $(q, \\dot{q}, \\ddot{q}, \\mathcal{F_{ee}})$ in our case $\\mathcal{F_{ee}} = \\mathbf{0}$.\n", + "$$\n", + "\\tau = M(q)\\ddot{q} + h(q, \\dot{q})\n", + "$$" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Run the cell below to see the dynamics simulation with inverse dynamics to hold the initial configuration." + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [], + "source": [ + "q = np.array([0,-np.pi/2,np.pi/2,0,0,0])\n", + "vq = np.zeros(robot.model.nv)\n", + "# Set the desired joint values\n", + "q_des = q\n", + "vq_des = np.zeros(robot.model.nv)\n", + "aq_des = vq = np.zeros(robot.model.nv)\n", + "viz.display(q)\n", + "\n", + "dt = 2e-3\n", + "N_steps = 5000\n", + "Kf = 0.3\n", + "\n", + "for it in range(N_steps):\n", + " t = it*dt\n", + "\n", + " # Compute the torque using inverse dynamics\n", + " tauq = pin.rnea(robot.model, robot.data, q_des, vq_des, aq_des)\n", + "\n", + " aq = pin.aba(robot.model, robot.data, q, vq, tauq)\n", + " # Double integration to update vq and q\n", + " vq += aq * dt\n", + " q = pin.integrate(robot.model, q, vq * dt)\n", + "\n", + " # Visualization\n", + " if it%20==0: \n", + " viz.display(q)\n", + " time.sleep(20*dt)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The robot eventually diverges when computing torques this way. What are the problems with this approach? What could be done differently?" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "robotics_tutorials", + "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.10.14" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/forward_kinematics.ipynb b/forward_kinematics.ipynb new file mode 100644 index 0000000..18c603e --- /dev/null +++ b/forward_kinematics.ipynb @@ -0,0 +1,415 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import time\n", + "import numpy as np\n", + "import pinocchio as pin\n", + "from robot_descriptions.loaders.pinocchio import load_robot_description\n", + "from utils.meshcat_viewer_wrapper import MeshcatVisualizer\n" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "You can open the visualizer by visiting the following URL:\n", + "http://127.0.0.1:7002/static/\n" + ] + } + ], + "source": [ + "robot = load_robot_description('ur5_description')\n", + "viz = MeshcatVisualizer(robot)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Lets visualize the neutral position of the robot in the next cell and then we will print out the frames contained in the robot model." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "q = pin.neutral(robot.model)\n", + "viz.display(q)" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Frame 0: universe\n", + "Frame 1: root_joint\n", + "Frame 2: world\n", + "Frame 3: world_joint\n", + "Frame 4: base_link\n", + "Frame 5: base_link-base_fixed_joint\n", + "Frame 6: base\n", + "Frame 7: shoulder_pan_joint\n", + "Frame 8: shoulder_link\n", + "Frame 9: shoulder_lift_joint\n", + "Frame 10: upper_arm_link\n", + "Frame 11: elbow_joint\n", + "Frame 12: forearm_link\n", + "Frame 13: wrist_1_joint\n", + "Frame 14: wrist_1_link\n", + "Frame 15: wrist_2_joint\n", + "Frame 16: wrist_2_link\n", + "Frame 17: wrist_3_joint\n", + "Frame 18: wrist_3_link\n", + "Frame 19: ee_fixed_joint\n", + "Frame 20: ee_link\n", + "Frame 21: wrist_3_link-tool0_fixed_joint\n", + "Frame 22: tool0\n" + ] + } + ], + "source": [ + "for i in range(robot.model.nframes):\n", + " frame = robot.model.frames[i]\n", + " print(f\"Frame {i}: {frame.name}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The following prints out the joint frames, these are typically the actuated joints of the robot. In a pinocchio model there is also always a Joint 0 which corresponds to the world frame which is named universe." + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Joint 0: universe\n", + "Joint 1: shoulder_pan_joint\n", + "Joint 2: shoulder_lift_joint\n", + "Joint 3: elbow_joint\n", + "Joint 4: wrist_1_joint\n", + "Joint 5: wrist_2_joint\n", + "Joint 6: wrist_3_joint\n" + ] + } + ], + "source": [ + "for i in range(robot.model.njoints):\n", + " joint = robot.model.joints[i]\n", + " joint_name = robot.model.names[i]\n", + " print(f\"Joint {i}: {joint_name}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now lets print out the position of each joint frame." + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "universe : 0.00 0.00 0.00\n", + "shoulder_pan_joint : 0.00 0.00 0.00\n", + "shoulder_lift_joint : 0.00 0.00 0.00\n", + "elbow_joint : 0.00 0.00 0.00\n", + "wrist_1_joint : 0.00 0.00 0.00\n", + "wrist_2_joint : 0.00 0.00 0.00\n", + "wrist_3_joint : 0.00 0.00 0.00\n" + ] + } + ], + "source": [ + "for name, oMi in zip(robot.model.names, robot.data.oMi):\n", + " print((\"{:<24} : {: .2f} {: .2f} {: .2f}\"\n", + " .format( name, *oMi.translation.T.flat )))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "As you can see all frames are zero which is not correct. That is because we are using robot.data to print them. In order for the data to be updated in robot.data, we have to call the forward kinematics. Also any other info like velocities, accelerations, forces etc are contained in this data structure. For more info on this take a look at the Data section of the cheatsheet https://github.com/stack-of-tasks/pinocchio/blob/master/doc/pinocchio_cheat_sheet.pdf" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now lets update the frames with the forward kinematics and reprint the frame locations." + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "universe : 0.00 0.00 0.00\n", + "shoulder_pan_joint : 0.00 0.00 0.09\n", + "shoulder_lift_joint : 0.00 0.14 0.09\n", + "elbow_joint : 0.42 0.02 0.09\n", + "wrist_1_joint : 0.82 0.02 0.09\n", + "wrist_2_joint : 0.82 0.11 0.09\n", + "wrist_3_joint : 0.82 0.11 -0.01\n", + " v = 0 0 0\n", + " w = 0 0 0\n", + "\n" + ] + } + ], + "source": [ + "pin.framesForwardKinematics(robot.model, robot.data, pin.neutral(robot.model))\n", + "for name, oMi in zip(robot.model.names, robot.data.oMi):\n", + " print((\"{:<24} : {: .2f} {: .2f} {: .2f}\"\n", + " .format( name, *oMi.translation.T.flat )))\n", + "print(robot.data.v[6])" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "To get specific frames we can use the following:" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Tool placement:\n", + " R =\n", + " -1 -9.79328e-12 4.79541e-23\n", + " 0 4.89664e-12 1\n", + "-9.79328e-12 1 -4.89664e-12\n", + " p = 0.81725 0.19145 -0.005491\n", + "\n", + "Base placement:\n", + " R =\n", + "1 0 0\n", + "0 1 0\n", + "0 0 1\n", + " p = 0 0 0\n", + "\n" + ] + } + ], + "source": [ + "IDX_BASE = robot.model.getFrameId('base_link')\n", + "IDX_TOOL = robot.model.getFrameId('tool0')\n", + "\n", + "oMtool = robot.data.oMf[IDX_TOOL]\n", + "oMbase = robot.data.oMf[IDX_BASE]\n", + "\n", + "print(\"Tool placement:\\n\",oMtool)\n", + "print(\"Base placement:\\n\",oMbase)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now lets visualize a random velocity trajectory. We can integrate the velocities into positions with the pin.integrate function." + ] + }, + { + "cell_type": "code", + "execution_count": 33, + "metadata": {}, + "outputs": [], + "source": [ + "vq = np.random.rand(robot.model.nv)*4 - 2\n", + "DT = 1e-3\n", + "n_steps = 1000\n", + "for t in range(n_steps):\n", + " q = pin.integrate(robot.model,q,vq*DT)\n", + " if t%10==0:\n", + " viz.display(q)\n", + " time.sleep(1/n_steps)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "In the next section we will use inverse velocity kinematics to find the joint configuration that corresponds to an end effector pose. First lets visualize the goal frame. This section of the tutorial will correspond do the numerical inverse kinematics algorithm from section 6.2.2 of *Modern Robotics*." + ] + }, + { + "cell_type": "code", + "execution_count": 34, + "metadata": {}, + "outputs": [], + "source": [ + "oMgoal = pin.SE3(pin.utils.rotate('x',np.pi), np.array([0.2, .4, .7]))\n", + "viz.visualize_frame(\"oMgoal\", oMgoal)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "You can find the Jacobian of the tool frame with the following command." + ] + }, + { + "cell_type": "code", + "execution_count": 35, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "(6, 6)" + ] + }, + "execution_count": 35, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "Jtool = pin.computeFrameJacobian(robot.model, robot.data, q, IDX_TOOL)\n", + "Jtool.shape" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "As we saw in the lecture, using the inverse jacobian we can map twists in a robot frame to joint velocities.\n", + "$$\\dot{q} = J^{\\dagger}_{tool}(\\theta) \\mathcal{V}_{tool}$$\n", + "We can rewrite this to only contain the increments dq and dx in the following way and then define dx as the error between the tool and goal frames.\n", + "$$dq = J^{\\dagger}_{tool}(\\theta) dx$$\n", + "$$dx = \\log({}^0 T_{tool}^{-1} {}^0 T_{goal})$$" + ] + }, + { + "cell_type": "code", + "execution_count": 36, + "metadata": {}, + "outputs": [], + "source": [ + "q = pin.neutral(robot.model)\n", + "viz.display(q)\n", + "n_steps = 10000\n", + "for i in range(n_steps+1):\n", + "\n", + " # Run the algorithms that outputs values in robot.data\n", + " pin.framesForwardKinematics(robot.model,robot.data,q)\n", + " pin.computeJointJacobians(robot.model,robot.data,q)\n", + "\n", + " # Placement from world frame o to frame f oMtool \n", + " oMtool = robot.data.oMf[IDX_TOOL]\n", + "\n", + " # 6D error between the two frame\n", + " tool_nu = pin.log(oMtool.inverse()*oMgoal).vector\n", + "\n", + " # Get corresponding jacobian\n", + " tool_Jtool = pin.computeFrameJacobian(robot.model, robot.data, q, IDX_TOOL, pin.LOCAL)\n", + "\n", + " # Control law by least square\n", + " vq = np.linalg.pinv(tool_Jtool)@tool_nu\n", + "\n", + " q = pin.integrate(robot.model,q, vq * DT)\n", + " if i%10==0:\n", + " viz.display(q)\n", + " time.sleep(1/n_steps)\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now lets visualize the tool frame to see is it corresponds to the goal. If you cant see a difference, then they should be overlapping. You can delete them one after another to confirm this with the last two cells." + ] + }, + { + "cell_type": "code", + "execution_count": 37, + "metadata": {}, + "outputs": [], + "source": [ + "oMtool = robot.data.oMf[IDX_TOOL]\n", + "viz.visualize_frame(\"oMtool\", oMtool)" + ] + }, + { + "cell_type": "code", + "execution_count": 38, + "metadata": {}, + "outputs": [], + "source": [ + "viz.delete(\"oMgoal\")" + ] + }, + { + "cell_type": "code", + "execution_count": 39, + "metadata": {}, + "outputs": [], + "source": [ + "viz.delete(\"oMtool\")" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "robotics_tutorials", + "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.10.14" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/pin_transformations.ipynb b/pin_transformations.ipynb new file mode 100644 index 0000000..984af05 --- /dev/null +++ b/pin_transformations.ipynb @@ -0,0 +1,869 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Transformations in Pinocchio\n", + "In this tutorial we will introduce how to perform rigid body transformations using the pinocchio library. We will go through the following three exercises:\n", + "1. Global and Relative Transformations\n", + "2. Exponential Coordinate Representation of Rigid Body Transforms\n", + "3. Twist and Wrench Transforms \n", + "\n", + "Before we complete the three exercises, we will first perform the setup and demonstrate how to display objects using meshcat." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Set up\n", + "We will need NumPy, Pinocchio, and MeshCat Viewer for vizualizing the robot." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "import time\n", + "import numpy as np\n", + "import pinocchio as pin\n", + "from utils.meshcat_viewer_wrapper import MeshcatVisualizer" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\n", + "## Displaying objects\n", + "Let's first learn how to open a 3D viewer, in which we will build our simulator. We will use the viewer MeshCat which directly displays in a browser. Open it as follows:" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": { + "metadata": {} + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "You can open the visualizer by visiting the following URL:\n", + "http://127.0.0.1:7001/static/\n" + ] + } + ], + "source": [ + "viz = MeshcatVisualizer()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The viz object is a client of the viewer, i.e. it will be use to pass display command to the viewer. The first commands are to create objects:" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "ballID = 'world/ball'; viz.addSphere(ballID,.2,[1,0,0,1])\n", + "boxID = 'world/box'; viz.addBox(boxID,[.5,.2,.4],[1,1,0,1])\n", + "cylID1 = 'world/cyl1'; viz.addCylinder(cylID1,length=0.3,radius=.05,color=[0,0,1,1])\n", + "cylID2 = 'world/cyl2'; viz.addCylinder(cylID2,length=0.2,radius=.06,color=[1,1,0,1])" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "viz.delete(ballID)\n", + "viz.delete(boxID)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Lets also visualize four random coordinate frames and transform the objects to the frames." + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "frame1 = pin.SE3.Random()\n", + "frame2 = pin.SE3.Random()\n", + "frame3 = pin.SE3.Random()\n", + "frame4 = pin.SE3.Random()\n", + "\n", + "viz.visualize_frame(\"frame1\", frame1)\n", + "viz.visualize_frame(\"frame2\", frame2)\n", + "viz.visualize_frame(\"frame3\", frame3)\n", + "viz.visualize_frame(\"frame4\", frame4)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Run the next cell to transform the two cylinders to each frame in meshcat." + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [], + "source": [ + "for frame in [frame1, frame2, frame3, frame4]:\n", + " viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(frame))\n", + " viz.applyConfiguration(cylID2,pin.SE3ToXYZQUAT(frame))\n", + " time.sleep(0.5)\n", + "viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(pin.SE3(1)))\n", + "viz.applyConfiguration(cylID2,pin.SE3ToXYZQUAT(pin.SE3(1)))" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "viz.delete(\"frame1\")\n", + "viz.delete(\"frame2\")\n", + "viz.delete(\"frame3\")\n", + "viz.delete(\"frame4\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now that we have seen how to define transformations in pinocchio and how to visualize them in meshcat, lets move onto the first exercise." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Exercise 1\n", + "Given the following relative transformations T_10, T_12, T_23, T43. Find the global transformations T_01, T_02, T_03, T_04 and transform the two cylinders to each frame. Visualize all of the frames and perform the subsequent global transformations to both cylinders. Then run the test cell to make sure that your computed transforms are correct.\n", + "\n", + "The transform notation corresponds to the one used in *Modern Robotics*.\n", + "$$T_{01} = \\begin{bmatrix} \n", + " R_{01} & p_{01} \\\\\n", + " 0 & 1 \n", + "\\end{bmatrix}$$" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "R_10 = np.array([[0.180678, 0.950891, -0.251321],\n", + " [0.89108, -0.266422, -0.367417],\n", + " [-0.416331, -0.157563, -0.895457]])\n", + "p_10 = np.array([0.740223, 0.593148, -0.640237])\n", + "T_10 = pin.SE3(R_10, p_10)\n", + "\n", + "R_12 = np.array([[-0.246977, 0.817821, -0.51978],\n", + " [0.963818, 0.15181, -0.219108],\n", + " [-0.100284, -0.555088, -0.825724]])\n", + "p_12 = np.array([1.55288, 0.90413, -0.169165])\n", + "T_12 = pin.SE3(R_12, p_12)\n", + "\n", + "R_23 = np.array([[-0.49966, -0.519852, 0.692888],\n", + " [-0.158395, 0.841243, 0.516935],\n", + " [-0.851617, 0.148542, -0.502677]])\n", + "p_23 = np.array([-0.150189, -1.25202, 0.767956])\n", + "T_23 = pin.SE3(R_23, p_23)\n", + "\n", + "R_43 = np.array([[0.420593, 0.383923, 0.822013],\n", + " [-0.882899, 0.381713, 0.273467],\n", + " [-0.208782, -0.840773, 0.499511]])\n", + "p_43 = np.array([0.293482, -0.372091, 0.23161])\n", + "T_43 = pin.SE3(R_43, p_43)" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "T_01 = T_10.inverse()\n", + "T_02 = T_01 * T_12\n", + "T_03 = T_01 * T_12 * T_23\n", + "T_04 = T_01 * T_12 * T_23 * T_43.inverse()" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "viz.visualize_frame(\"T_01\", T_01)\n", + "viz.visualize_frame(\"T_02\", T_02)\n", + "viz.visualize_frame(\"T_03\", T_03)\n", + "viz.visualize_frame(\"T_04\", T_04)" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "for frame in [T_01, T_02, T_03, T_04]:\n", + " viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(frame))\n", + " viz.applyConfiguration(cylID2,pin.SE3ToXYZQUAT(frame))\n", + " time.sleep(1)\n", + "viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(pin.SE3(1)))\n", + "viz.applyConfiguration(cylID2,pin.SE3ToXYZQUAT(pin.SE3(1)))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Fill in the missing parts of the transform_error function to test your transformations against the solutions. An error on the order of 1e-7 is expected for correct transformations." + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": { + "metadata": {} + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "6.14095854715443e-07\n", + "3.5250915839765295e-07\n", + "7.520391730676697e-07\n", + "6.745416992167283e-07\n" + ] + } + ], + "source": [ + "from sol.pin_transformations import T_01_sol, T_02_sol, T_03_sol, T_04_sol\n", + "\n", + "def transform_error(T, T_sol):\n", + " SE3_error = pin.log(T_sol.inverse() * T)\n", + " scalar_error = np.linalg.norm(SE3_error.linear + SE3_error.angular)\n", + " return scalar_error\n", + "\n", + "print(transform_error(T_01, T_01_sol))\n", + "print(transform_error(T_02, T_02_sol))\n", + "print(transform_error(T_03, T_03_sol))\n", + "print(transform_error(T_04, T_04_sol))" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "viz.delete(\"T_01\")\n", + "viz.delete(\"T_02\")\n", + "viz.delete(\"T_03\")\n", + "viz.delete(\"T_04\")\n", + "viz.delete(cylID1)\n", + "viz.delete(cylID2)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Exercise 2\n", + "In this exercise we will visualize the screw interpretation of a rigid body transformation. Through this we will get practice with the exponential coordinate representation of rigid body transformations." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "First lets get familiar with the pinocchio implementations of the log and exp functions that we learned about in the lecture." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "$$\\begin{aligned}\n", + " \\text{log}: &\\quad T \\in SE(3) \\quad \\rightarrow \\quad {\\mathcal{V}} = [S]\\theta \\in se(3).\n", + "\\end{aligned}$$" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": { + "metadata": {} + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Rigid Body Transform in SE(3):\n", + " R =\n", + " 0.180678 0.89108 -0.416331\n", + " 0.950891 -0.266422 -0.157563\n", + "-0.251321 -0.367417 -0.895457\n", + " p = -0.928835 -0.646721 -0.169338\n", + "\n", + "Twist V in se(3) associated with the Rigid Body Transform in SE(3):\n", + " v = -1.1947 -0.142939 0.287799\n", + " w = -2.30461 -1.81213 0.656842\n", + "\n", + "[-1.19470225 -0.14293948 0.28779915]\n", + "[-2.30460792 -1.81213297 0.65684192]\n" + ] + } + ], + "source": [ + "print(\"Rigid Body Transform in SE(3):\")\n", + "print(T_01)\n", + "print(\"Twist V in se(3) associated with the Rigid Body Transform in SE(3):\")\n", + "V_01 = pin.log(T_01)\n", + "print(V_01)\n", + "print(V_01.linear)\n", + "print(V_01.angular)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "$$\\begin{aligned}\n", + " \\text{log}: &\\quad R \\in SO(3) \\quad \\rightarrow \\quad \\omega = [\\hat{\\omega}]\\theta \\in so(3).\n", + "\\end{aligned}$$" + ] + }, + { + "cell_type": "code", + "execution_count": 15, + "metadata": { + "metadata": {} + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Matrix log of SO(3)\n", + "omega = [-2.30460792 -1.81213297 0.65684192] \n", + "\n" + ] + } + ], + "source": [ + "print(\"Matrix log of SO(3)\")\n", + "omega = pin.log3(T_01.rotation)\n", + "print(\"omega =\", omega,\"\\n\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Recovering $\\hat{\\omega}$ and $\\theta$ can be done using the algorithm from section 3.2.3.3 of *Modern Robotics*. Take a look at it if you would like to know the details. In pinocchio we can simply call pin.AngleAxis." + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": { + "metadata": {} + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Angle axis representation of an SO(3) element\n", + "angle: 3.00437\n", + "axis: -0.767075 -0.603157 0.218624\n", + "\n", + "Recover axis from omega\n", + "omega_hat = [-0.76708421 -0.60316489 0.21862854]\n" + ] + } + ], + "source": [ + "print(\"Angle axis representation of an SO(3) element\")\n", + "print(pin.AngleAxis(T_01.rotation))\n", + "print(\"Recover axis from omega\")\n", + "print(\"omega_hat =\", omega / pin.AngleAxis(T_01.rotation).angle)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "$$\\begin{aligned}\n", + " \\text{exp}: &\\quad {\\mathcal{V}} = [S]\\theta \\in se(3) \\quad \\rightarrow \\quad T \\in SE(3)\n", + "\\end{aligned}$$" + ] + }, + { + "cell_type": "code", + "execution_count": 18, + "metadata": { + "metadata": {} + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Matrix exponential for se(3):\n", + " R =\n", + " 0.180674 0.89109 -0.416312\n", + " 0.950885 -0.266425 -0.157594\n", + "-0.251346 -0.367392 -0.89546\n", + " p = -0.928848 -0.646741 -0.169335\n", + "\n" + ] + } + ], + "source": [ + "print(\"Matrix exponential for se(3):\")\n", + "print(pin.exp(V_01))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "$$\\begin{aligned}\n", + " \\text{exp}: &\\quad \\omega = [\\hat{\\omega}]\\theta \\in so(3) \\quad \\rightarrow \\quad R \\in SO(3)\n", + "\\end{aligned}$$" + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "metadata": { + "metadata": {} + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Matrix exponential for so(3):\n", + "[[ 0.18067434 0.89108975 -0.4163122 ]\n", + " [ 0.95088475 -0.26642516 -0.15759389]\n", + " [-0.25134634 -0.36739175 -0.89545984]]\n", + "Compare to original rotation matrix:\n", + "[[ 0.180678 0.89108 -0.416331]\n", + " [ 0.950891 -0.266422 -0.157563]\n", + " [-0.251321 -0.367417 -0.895457]]\n" + ] + } + ], + "source": [ + "print(\"Matrix exponential for so(3):\")\n", + "print(pin.exp3(omega))\n", + "print(\"Compare to original rotation matrix:\")\n", + "print(T_01.rotation)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now that we have presented the necessary pinocchio functions, let's move on to the exercise." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The goal of this exercise is to visualize a rigid body transformation using the screw interpretation of a twist. Fill in the missing parts of the code below. Here the function screw_axis_q() should return the position q of the axis in space and distance d travelled on the screw axis and s_hat the unit vector representing the direction of the screw axis. This equation is found in section 3.3.2.2 in *Modern Robotics*: \n", + "$${\\mathcal{V}} = \\begin{bmatrix}\n", + "\\omega \\\\\n", + "v\n", + "\\end{bmatrix} = \\begin{bmatrix}\n", + "\\hat{s} \\dot{\\theta} \\\\\n", + "-\\hat{s} \\dot{\\theta} \\times q + h \\hat{s} \\dot{\\theta}\n", + "\\end{bmatrix} \\\\\\text{where}:\\\\\n", + "\\dot{\\theta} = \\lVert \\omega \\rVert\\\\\n", + "\\hat{s} = \\omega / \\lVert \\omega \\rVert\\\\\n", + "h = \\hat{\\omega}^Tv/\\dot{\\theta}$$" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "hints: \n", + "see relevant section in book for detailed explanation. \n", + "$\\text{pin.skew}(\\omega) = [\\omega]$" + ] + }, + { + "cell_type": "code", + "execution_count": 20, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "def screw_axis_q(se3_twist):\n", + " \"\"\"args:\n", + " se3_twist: pin se3 object\n", + " returns:\n", + " q: 3x1 np array\n", + " d: float\n", + " \"\"\"\n", + " s_hat = se3_twist.angular / np.linalg.norm(se3_twist.angular)\n", + " theta_dot = np.linalg.norm(se3_twist.angular)\n", + " h = s_hat.T @ se3_twist.linear / theta_dot\n", + "\n", + " q = np.linalg.pinv(pin.skew(se3_twist.angular)) @ \\\n", + " (h * se3_twist.angular - se3_twist.linear)\n", + " d = h * theta_dot\n", + " return q, d, s_hat" + ] + }, + { + "cell_type": "code", + "execution_count": 21, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "cylID1 = 'world/cyl1'; viz.addCylinder(cylID1,length=0.3,radius=.05,color=[0,0,1,1])\n", + "viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(pin.SE3(1)))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "First lets test the visualization on a simple example." + ] + }, + { + "cell_type": "code", + "execution_count": 22, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "transform = pin.SE3(pin.utils.rotate('x',np.pi), np.array([1,0,0]))\n", + "viz.visualize_frame(\"transform\", transform)\n", + "\n", + "V = pin.log(transform)\n", + "q, d, s_hat = screw_axis_q(V)\n", + "\n", + "viz.visualize_axis(\"screw_axis\", q, s_hat, d)\n", + "\n", + "steps = 200\n", + "for i in range(steps + 1):\n", + " alpha = i / steps\n", + " # Interpolate using the exponential map of the weighted twist\n", + " Ti = pin.exp(alpha * V)\n", + " viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(Ti))\n", + " time.sleep(0.01)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "See if your transform is the same as the one shown in the video below." + ] + }, + { + "cell_type": "code", + "execution_count": 23, + "metadata": {}, + "outputs": [ + { + "data": { + "text/html": [ + "" + ], + "text/plain": [ + "" + ] + }, + "execution_count": 23, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "from IPython.display import Video\n", + "\n", + "video_path = \"videos/simple_screw_transform.mp4\"\n", + "Video(video_path)" + ] + }, + { + "cell_type": "code", + "execution_count": 24, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(pin.SE3(1)))\n", + "viz.delete(\"transform\")\n", + "viz.delete(\"screw_axis\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now find visualize the screw transformation on two consecutive transformations. We will use T_01 and T_02 from the previous exercise." + ] + }, + { + "cell_type": "code", + "execution_count": 25, + "metadata": { + "metadata": {} + }, + "outputs": [], + "source": [ + "viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(pin.SE3(1)))\n", + "viz.visualize_frame(\"T_01\", T_01)\n", + "viz.visualize_frame(\"T_02\", T_02)\n", + "steps = 200\n", + "\n", + "V = pin.log(T_01)\n", + "q, d, s_hat = screw_axis_q(V)\n", + "viz.visualize_axis(\"screw_axis\", q, s_hat, d)\n", + "\n", + "for i in range(steps + 1):\n", + " alpha = i / steps\n", + " # Interpolate using the exponential map of the weighted twist\n", + " Ti = pin.exp(alpha * V)\n", + " viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(Ti))\n", + " time.sleep(0.01)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Fill in the missing code and run to see the relative transform." + ] + }, + { + "cell_type": "code", + "execution_count": 26, + "metadata": {}, + "outputs": [], + "source": [ + "T_12 = T_01.inverse() * T_02\n", + "steps = 200\n", + "\n", + "V_12 = pin.log(T_12)\n", + "q_1, d, s_hat_1 = screw_axis_q(V_12)\n", + "# Transform q_1 and s_hat_1 to the global frame 0\n", + "q_0 = (T_01.homogeneous @ np.append(q_1,[1]))[:3]\n", + "s_hat_0 = T_01.rotation @ s_hat_1\n", + "viz.visualize_axis(\"screw_axis\", q_0, s_hat_0, d)\n", + "\n", + "for i in range(steps + 1):\n", + " alpha = i / steps\n", + " # Interpolate using the exponential map of the weighted twist\n", + " Ti_12 = pin.exp(alpha * V_12)\n", + " viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(T_01 * Ti_12))\n", + " time.sleep(0.01)" + ] + }, + { + "cell_type": "code", + "execution_count": 27, + "metadata": {}, + "outputs": [], + "source": [ + "viz.applyConfiguration(cylID1,pin.SE3ToXYZQUAT(pin.SE3(1)))\n", + "viz.delete(\"T_01\")\n", + "viz.delete(\"T_02\")\n", + "viz.delete(\"screw_axis\")\n", + "viz.delete(cylID1)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Exercise 3\n", + "In this exercise we will use pinocchio to transform twists and wrenches between different coordinate frames. Check out the next cell to see how twists and wrenches are defined in pinocchio. Then complete the missing code in the cell with the adjoint_from_SE3() function and manually perform the change of coordinate for both the twist and the wrench. Compare your results with what is outputted in the cell below." + ] + }, + { + "cell_type": "code", + "execution_count": 28, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + " v = 1.39733 -0.58774 -5.38554\n", + " w = -1.12673 1.05975 -0.779361\n", + "\n", + " f = 0.713845 -0.054642 -3.67253\n", + "tau = 1.23912 -2.4723 -0.266949\n", + "\n" + ] + } + ], + "source": [ + "# Twist in Global Frame\n", + "V_0 = pin.Motion(np.array([1,2,3]), np.array([1,-1,1]))\n", + "print(T_01 * V_0)\n", + "# Wrench in Global Frame\n", + "W_0 = pin.Force(np.array([1,2,3]), np.array([1,-1,1]))\n", + "print(T_01 * W_0)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Twist change of coordinate frame\n", + "$${\\mathcal{V}_a} = [\\text{Ad}_{T_{ab}}]{\\mathcal{V}_b}$$" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Wrench change of coordinate frame\n", + "$${\\mathcal{F}_a} = [\\text{Ad}_{T_{ba}}]^T{\\mathcal{F}_b}$$" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Hint for wrench transform:\n", + "$$[\\text{Ad}_T]^{-1} = [\\text{Ad}_{T^{-1}}]$$" + ] + }, + { + "cell_type": "code", + "execution_count": 29, + "metadata": {}, + "outputs": [], + "source": [ + "def adjoint_from_SE3(SE3):\n", + " \"\"\"\"\n", + " input: pinocchio SE3 object\n", + " output: 6x6 numpy array\n", + " \"\"\"\n", + " Adj = np.block([[SE3.rotation, np.zeros((3,3))],\n", + " [pin.skew(SE3.translation) @ SE3.rotation, SE3.rotation]])\n", + " return Adj" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Compare the your transformation with that done above with pinocchio" + ] + }, + { + "cell_type": "code", + "execution_count": 30, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Twist in global frame\n", + "[-1.126733 1.05975 -0.779361 1.39733085 -0.58774042 -5.38554104]\n", + "Wrench in global frame\n", + "[ 1.23911445 -2.47230101 -0.26694735 0.713845 -0.054642 -3.672526 ]\n" + ] + } + ], + "source": [ + "Adj_T_01 = adjoint_from_SE3(T_01)\n", + "print(\"Twist in global frame\")\n", + "print(Adj_T_01 @ np.hstack((V_0.angular, V_0.linear)))\n", + "Adj_T_10 = adjoint_from_SE3(T_01.inverse())\n", + "print(\"Wrench in global frame\")\n", + "print(Adj_T_10.T @ np.hstack((W_0.angular, W_0.linear)))" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "robotics_tutorials", + "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.10.14" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/robotics_course_env.yml b/robotics_tutorials_env.yml similarity index 50% rename from robotics_course_env.yml rename to robotics_tutorials_env.yml index ef912eb..e2a3c8f 100644 --- a/robotics_course_env.yml +++ b/robotics_tutorials_env.yml @@ -1,4 +1,4 @@ -name: robotics_course +name: robotics_tutorials channels: - conda-forge - defaults @@ -7,6 +7,7 @@ dependencies: - numpy - pinocchio - meshcat-python + - robot_descriptions - example-robot-data - jupyterlab - ipywidgets @@ -14,14 +15,14 @@ dependencies: - scipy - quadprog - crocoddyl - - keras - - tensorflow - - gym - - tqdm - - gymnasium - - imageio - - mujoco=2.3.7 - - rich - - stable-baselines3 - - tensorboard - - pip + # - keras + # - tensorflow + # - gym + # - tqdm + # - gymnasium + # - imageio + # - mujoco=2.3.7 + # - rich + # - stable-baselines3 + # - tensorboard + # - pip diff --git a/sol/pin_transformations.py b/sol/pin_transformations.py new file mode 100644 index 0000000..d9bee4c --- /dev/null +++ b/sol/pin_transformations.py @@ -0,0 +1,26 @@ +import numpy as np +import pinocchio as pin + +R_01 = np.array([[0.180678, 0.89108, -0.416331], + [0.950891, -0.266422, -0.157563], + [-0.251321, -0.367417, -0.895457]]) +p_01 = np.array([-0.928835, -0.646721, -0.169338]) +T_01_sol = pin.SE3(R_01, p_01) + +R_02 = np.array([[0.855967, 0.514137, 0.0546189], + [-0.475829, 0.824674, -0.305775], + [-0.202253, 0.235744, 0.950536]]) +p_02 = np.array([0.227817, 0.615672, -0.740323]) +T_02_sol = pin.SE3(R_02, p_02) + +R_03 = np.array([[-0.555644, -0.0043484, 0.831409], + [0.367532, 0.895692, 0.250313], + [-0.745776, 0.444654, -0.496087]]) +p_03 = np.array([-0.502505, -0.580194, -0.275133]) +T_03_sol = pin.SE3(R_03, p_03) + +R_04 = np.array([[0.44806, 0.71628, 0.534962], + [0.704219, 0.0858558, -0.704774], + [-0.550745, 0.692512, -0.465949]]) +p_04 = np.array([-0.491384, -0.591691, 0.252096]) +T_04_sol = pin.SE3(R_04, p_04) diff --git a/tp1/configuration_extended.py b/tp1/configuration_extended.py deleted file mode 100644 index 4d860ec..0000000 --- a/tp1/configuration_extended.py +++ /dev/null @@ -1,81 +0,0 @@ -''' -Stand-alone program to optimize the placement of a 2d robot, where the decision variables -are the placement of the 3 bodies of the robot. BFGS and SLSQP solvers are used. -''' - -import time -import numpy as np -from scipy.optimize import fmin_bfgs,fmin_slsqp -from utils.meshcat_viewer_wrapper import MeshcatVisualizer,translation2d,planar -from numpy.linalg import norm,inv,pinv,svd,eig - -viz = MeshcatVisualizer(url='classical') - -viz.addSphere('joint1',.1,[1,0,0,1]) -viz.addSphere('joint2',.1,[1,0,0,1]) -viz.addSphere('joint3',.1,[1,0,0,1]) -viz.addCylinder('arm1',.75,.05,[.65,.65,.65,1]) -viz.addCylinder('arm2',.75,.05,[.65,.65,.65,1]) -viz.addSphere('target',.1001,[0,.8,.1,1]) - -# %jupyter_snippet display -def display_9(ps): - '''Display the robot in the Viewer. ''' - assert (ps.shape == (9, )) - x1, y1, t1, x2, y2, t2, x3, y3, t3 = ps - viz.applyConfiguration('joint1',planar(x1, y1, t1)) - viz.applyConfiguration('arm1' ,planar(x1 + np.cos(t1) / 2, x1 + np.sin(t1) / 2, t1)) - viz.applyConfiguration('joint2',planar(x2, y2, t2)) - viz.applyConfiguration('arm2' ,planar(x2 + np.cos(t2) / 2, y2 + np.sin(t2) / 2, t2)) - viz.applyConfiguration('joint3',planar(x3, y3, t3)) -# %end_jupyter_snippet - -# %jupyter_snippet endeffector -def endeffector_9(ps): - assert (ps.shape == (9, )) - x1, y1, t1, x2, y2, t2, x3, y3, t3 = ps - return np.array([x3, y3]) -# %end_jupyter_snippet - -target = np.array([.5, .5]) -viz.applyConfiguration('target',translation2d(target[0],target[1])) - -# %jupyter_snippet cost -def cost_9(ps): - eff = endeffector_9(ps) - return norm(eff - target)**2 -# %end_jupyter_snippet - -# %jupyter_snippet constraint -def constraint_9(ps): - assert (ps.shape == (9, )) - x1, y1, t1, x2, y2, t2, x3, y3, t3 = ps - res = np.zeros(6) - res[0] = x1 - 0 - res[1] = y1 - 0 - res[2] = x1 + np.cos(t1) - x2 - res[3] = y1 + np.sin(t1) - y2 - res[4] = x2 + np.cos(t2) - x3 - res[5] = y2 + np.sin(t2) - y3 - return res -# %end_jupyter_snippet - -# %jupyter_snippet penalty -def penalty(ps): - return cost_9(ps) + 10 * sum(np.square(constraint_9(ps))) -# %end_jupyter_snippet - -# %jupyter_snippet callback -def callback_9(ps): - display_9(ps) - time.sleep(.5) -# %end_jupyter_snippet - -x0 = np.array([ 0.0,] * 9) - -with_bfgs = 0 -if with_bfgs: - xopt = fmin_bfgs(penalty, x0, callback=callback_9) -else: - xopt = fmin_slsqp(cost_9, x0, callback=callback_9, f_eqcons=constraint_9, iprint=2, full_output=1)[0] -print('\n *** Xopt = %s\n\n\n\n' % xopt) diff --git a/tp1/configuration_reduced.py b/tp1/configuration_reduced.py deleted file mode 100644 index 8e34c92..0000000 --- a/tp1/configuration_reduced.py +++ /dev/null @@ -1,70 +0,0 @@ -''' -Stand-alone program to optimize the configuration q=[q1,q2] of a 2-R robot with -scipy BFGS. -''' - -# %jupyter_snippet import -import time -import numpy as np -from scipy.optimize import fmin_bfgs,fmin_slsqp -from utils.meshcat_viewer_wrapper import MeshcatVisualizer,translation2d,planar -from numpy.linalg import norm,inv,pinv,svd,eig -# %end_jupyter_snippet - -viz = MeshcatVisualizer(url='classical') - -# %jupyter_snippet create -viz.addSphere('joint1',.1,[1,0,0,1]) -viz.addSphere('joint2',.1,[1,0,0,1]) -viz.addSphere('joint3',.1,[1,0,0,1]) -viz.addCylinder('arm1',.75,.05,[.65,.65,.65,1]) -viz.addCylinder('arm2',.75,.05,[.65,.65,.65,1]) -viz.addSphere('target',.1001,[0,.8,.1,1]) -# %end_jupyter_snippet - -# %jupyter_snippet display -def display(q): - '''Display the robot in Gepetto Viewer. ''' - assert (q.shape == (2,)) - c0 = np.cos(q[0]) - s0 = np.sin(q[0]) - c1 = np.cos(q[0] + q[1]) - s1 = np.sin(q[0] + q[1]) - viz.applyConfiguration('joint1',planar(0, 0, 0)) - viz.applyConfiguration('arm1' ,planar(c0 / 2, s0 / 2, q[0])) - viz.applyConfiguration('joint2',planar(c0, s0, q[0])) - viz.applyConfiguration('arm2' ,planar(c0 + c1 / 2, s0 + s1 / 2, q[0] + q[1])) - viz.applyConfiguration('joint3',planar(c0 + c1, s0 + s1, q[0] + q[1])) -# %end_jupyter_snippet - -# %jupyter_snippet endeffector -def endeffector(q): - '''Return the 2D position of the end effector of the robot at configuration q. ''' - assert (q.shape == (2,)) - c0 = np.cos(q[0]) - s0 = np.sin(q[0]) - c1 = np.cos(q[0] + q[1]) - s1 = np.sin(q[0] + q[1]) - return np.array([c0 + c1, s0 + s1]) -# %end_jupyter_snippet - -# %jupyter_snippet cost -target = np.array([.5, .5]) -viz.applyConfiguration('target',translation2d(target[0],target[1])) - -def cost(q): - eff = endeffector(q) - return np.linalg.norm(eff - target)**2 -# %end_jupyter_snippet - -# %jupyter_snippet callback -def callback(q): - display(q) - time.sleep(.5) -# %end_jupyter_snippet - -# %jupyter_snippet optim -q0 = np.array([0.0, 0.0]) -qopt_bfgs = fmin_bfgs(cost, q0, callback=callback) -print('\n *** Optimal configuration from BFGS = %s \n\n\n\n' % qopt_bfgs) -# %end_jupyter_snippet diff --git a/tp1/generated/configuration_extended_callback b/tp1/generated/configuration_extended_callback deleted file mode 100644 index edd948c..0000000 --- a/tp1/generated/configuration_extended_callback +++ /dev/null @@ -1,3 +0,0 @@ -def callback_9(ps): - display_9(ps) - time.sleep(.5) diff --git a/tp1/generated/configuration_extended_constraint b/tp1/generated/configuration_extended_constraint deleted file mode 100644 index 478e40f..0000000 --- a/tp1/generated/configuration_extended_constraint +++ /dev/null @@ -1,12 +0,0 @@ -def constraint_9(ps): - assert (ps.shape == (9, )) - x1, y1, t1, x2, y2, t2, x3, y3, t3 = ps - res = np.zeros(7) - res[0] = x1 - 0 - res[1] = y1 - 0 - res[2] = x1 + np.cos(t1) - x2 - res[3] = y1 + np.sin(t1) - y2 - res[4] = x2 + np.cos(t2) - x3 - res[5] = y2 + np.sin(t2) - y3 - res[6] = t3 - t2 - return res diff --git a/tp1/generated/configuration_extended_cost b/tp1/generated/configuration_extended_cost deleted file mode 100644 index 862e1a3..0000000 --- a/tp1/generated/configuration_extended_cost +++ /dev/null @@ -1,3 +0,0 @@ -def cost_9(ps): - eff = endeffector_9(ps) - return norm(eff - target)**2 diff --git a/tp1/generated/configuration_extended_display b/tp1/generated/configuration_extended_display deleted file mode 100644 index 1c291d9..0000000 --- a/tp1/generated/configuration_extended_display +++ /dev/null @@ -1,9 +0,0 @@ -def display_9(ps): - '''Display the robot in the Viewer. ''' - assert (ps.shape == (9, )) - x1, y1, t1, x2, y2, t2, x3, y3, t3 = ps - viz.applyConfiguration('joint1',planar(x1, y1, t1)) - viz.applyConfiguration('arm1' ,planar(x1 + np.cos(t1) / 2, x1 + np.sin(t1) / 2, t1)) - viz.applyConfiguration('joint2',planar(x2, y2, t2)) - viz.applyConfiguration('arm2' ,planar(x2 + np.cos(t2) / 2, y2 + np.sin(t2) / 2, t2)) - viz.applyConfiguration('joint3',planar(x3, y3, t3)) diff --git a/tp1/generated/configuration_extended_endeffector b/tp1/generated/configuration_extended_endeffector deleted file mode 100644 index 9bb8fa2..0000000 --- a/tp1/generated/configuration_extended_endeffector +++ /dev/null @@ -1,4 +0,0 @@ -def endeffector_9(ps): - assert (ps.shape == (9, )) - x1, y1, t1, x2, y2, t2, x3, y3, t3 = ps - return np.array([x3, y3]) diff --git a/tp1/generated/configuration_extended_penalty b/tp1/generated/configuration_extended_penalty deleted file mode 100644 index 69f575f..0000000 --- a/tp1/generated/configuration_extended_penalty +++ /dev/null @@ -1,2 +0,0 @@ -def penalty(ps): - return cost_9(ps) + 10 * sum(np.square(constraint_9(ps))) diff --git a/tp1/generated/configuration_reduced_callback b/tp1/generated/configuration_reduced_callback deleted file mode 100644 index 9895885..0000000 --- a/tp1/generated/configuration_reduced_callback +++ /dev/null @@ -1,3 +0,0 @@ -def callback(q): - display(q) - time.sleep(.5) diff --git a/tp1/generated/configuration_reduced_cost b/tp1/generated/configuration_reduced_cost deleted file mode 100644 index c5083f9..0000000 --- a/tp1/generated/configuration_reduced_cost +++ /dev/null @@ -1,6 +0,0 @@ -target = np.array([.5, .5]) -viz.applyConfiguration('target',translation2d(target[0],target[1])) - -def cost(q): - eff = endeffector(q) - return np.linalg.norm(eff - target)**2 diff --git a/tp1/generated/configuration_reduced_create b/tp1/generated/configuration_reduced_create deleted file mode 100644 index a94c684..0000000 --- a/tp1/generated/configuration_reduced_create +++ /dev/null @@ -1,6 +0,0 @@ -viz.addSphere('joint1',.1,[1,0,0,1]) -viz.addSphere('joint2',.1,[1,0,0,1]) -viz.addSphere('joint3',.1,[1,0,0,1]) -viz.addCylinder('arm1',.75,.05,[.65,.65,.65,1]) -viz.addCylinder('arm2',.75,.05,[.65,.65,.65,1]) -viz.addSphere('target',.1001,[0,.8,.1,1]) diff --git a/tp1/generated/configuration_reduced_display b/tp1/generated/configuration_reduced_display deleted file mode 100644 index 04ae257..0000000 --- a/tp1/generated/configuration_reduced_display +++ /dev/null @@ -1,12 +0,0 @@ -def display(q): - '''Display the robot in Gepetto Viewer. ''' - assert (q.shape == (2,)) - c0 = np.cos(q[0]) - s0 = np.sin(q[0]) - c1 = np.cos(q[0] + q[1]) - s1 = np.sin(q[0] + q[1]) - viz.applyConfiguration('joint1',planar(0, 0, 0)) - viz.applyConfiguration('arm1' ,planar(c0 / 2, s0 / 2, q[0])) - viz.applyConfiguration('joint2',planar(c0, s0, q[0])) - viz.applyConfiguration('arm2' ,planar(c0 + c1 / 2, s0 + s1 / 2, q[0] + q[1])) - viz.applyConfiguration('joint3',planar(c0 + c1, s0 + s1, q[0] + q[1])) diff --git a/tp1/generated/configuration_reduced_endeffector b/tp1/generated/configuration_reduced_endeffector deleted file mode 100644 index 74b7d92..0000000 --- a/tp1/generated/configuration_reduced_endeffector +++ /dev/null @@ -1,8 +0,0 @@ -def endeffector(q): - '''Return the 2D position of the end effector of the robot at configuration q. ''' - assert (q.shape == (2,)) - c0 = np.cos(q[0]) - s0 = np.sin(q[0]) - c1 = np.cos(q[0] + q[1]) - s1 = np.sin(q[0] + q[1]) - return np.array([c0 + c1, s0 + s1]) diff --git a/tp1/generated/configuration_reduced_import b/tp1/generated/configuration_reduced_import deleted file mode 100644 index 8ea3f11..0000000 --- a/tp1/generated/configuration_reduced_import +++ /dev/null @@ -1,5 +0,0 @@ -import time -import numpy as np -from scipy.optimize import fmin_bfgs,fmin_slsqp -from utils.meshcat_viewer_wrapper import MeshcatVisualizer,translation2d,planar -from numpy.linalg import norm,inv,pinv,svd,eig diff --git a/tp1/generated/configuration_reduced_optim b/tp1/generated/configuration_reduced_optim deleted file mode 100644 index 96d9dda..0000000 --- a/tp1/generated/configuration_reduced_optim +++ /dev/null @@ -1,3 +0,0 @@ -q0 = np.array([0.0, 0.0]) -qopt_bfgs = fmin_bfgs(cost, q0, callback=callback) -print('\n *** Optimal configuration from BFGS = %s \n\n\n\n' % qopt_bfgs) diff --git a/tp5/arm_example.py b/tp5/arm_example.py deleted file mode 100644 index 07c5737..0000000 --- a/tp5/arm_example.py +++ /dev/null @@ -1,102 +0,0 @@ -''' -# In this example test, we will solve the reaching-goal task with the Talos arm. -# For that, we use the forward dynamics (with its analytical derivatives) -# developed inside crocoddyl; it describes inside DifferentialActionModelFullyActuated class. -# Finally, we use an Euler sympletic integration scheme. -''' - -import sys -WITHDISPLAY = 'display' in sys.argv -WITHPLOT = 'plot' in sys.argv - -import crocoddyl; crocoddyl.switchToNumpyMatrix() -import pinocchio -import numpy as np -import example_robot_data - -# First, let's load the Pinocchio model for the Talos arm. -robot = example_robot_data.load('talos_arm') - -# Set robot model -robot_model = robot.model -robot_model.armature =np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.])*5 -robot_model.q0 = np.array([3.5,2,2,0,0,0,0]) -robot_model.x0 = np.concatenate([robot_model.q0, pinocchio.utils.zero(robot_model.nv)]) -robot_model.gravity *= 0 - -# Configure task -FRAME_TIP = robot_model.getFrameId("gripper_left_fingertip_3_link") -goal = np.array([.2,0.5,.5]) - -# Configure viewer -from tp3.meshcat_viewer_wrapper import MeshcatVisualizer -viz = MeshcatVisualizer(robot,url='tcp://127.0.0.1:6004')#classical') -viz.display(robot_model.q0) -viz.addBox('world/box',[.1,.1,.1], [1.,0,0,1]) -viz.addBox('world/goal',[.1,.1,.1],[0,1,0,1]) -viz.applyConfiguration('world/goal',[0.2,0.5,.5,0,0,0,1]) - -# Create a cost model per the running and terminal action model. -state = crocoddyl.StateMultibody(robot_model) -runningCostModel = crocoddyl.CostModelSum(state) -terminalCostModel = crocoddyl.CostModelSum(state) - -# Note that we need to include a cost model (i.e. set of cost functions) in -# order to fully define the action model for our optimal control problem. -# For this particular example, we formulate three running-cost functions: -# goal-tracking cost, state and control regularization; and one terminal-cost: -# goal cost. First, let's create the common cost functions. -Mref = crocoddyl.FramePlacement(FRAME_TIP,pinocchio.SE3(np.eye(3), goal)) -#goalTrackingCost = crocoddyl.CostModelFramePlacement(state, Mref) -pref = crocoddyl.FrameTranslation(FRAME_TIP,goal) -goalTrackingCost = crocoddyl.CostModelFrameTranslation(state, pref) -weights=crocoddyl.ActivationModelWeightedQuad(np.array([1,1,1,1,1,1,1, 1,1,1,1,2,2,2.])) -xRegCost = crocoddyl.CostModelState(state,weights,robot_model.x0) -uRegCost = crocoddyl.CostModelControl(state) -weightsT=crocoddyl.ActivationModelWeightedQuad(np.array([.01,.01,.01,.01,.01,.01,.01, 1,1,1,1,2,2,2.])) -xRegCostT = crocoddyl.CostModelState(state,weights,robot_model.x0) - -# Then let's added the running and terminal cost functions -runningCostModel.addCost("gripperPose", goalTrackingCost, .001) -runningCostModel.addCost("xReg", xRegCost, 1e-3) -runningCostModel.addCost("uReg", uRegCost, 1e-6) -terminalCostModel.addCost("gripperPose", goalTrackingCost, 10) -terminalCostModel.addCost("xReg", xRegCostT, .01) - -# Next, we need to create an action model for running and terminal knots. The -# forward dynamics (computed using ABA) are implemented -# inside DifferentialActionModelFullyActuated. -actuationModel = crocoddyl.ActuationModelFull(state) -dt = 1e-2 -runningModel = crocoddyl.IntegratedActionModelEuler( - crocoddyl.DifferentialActionModelFreeFwdDynamics(state, actuationModel, runningCostModel), dt) -runningModel.differential.armature = robot_model.armature -terminalModel = crocoddyl.IntegratedActionModelEuler( - crocoddyl.DifferentialActionModelFreeFwdDynamics(state, actuationModel, terminalCostModel), 0.) -terminalModel.differential.armature = robot_model.armature - -# For this optimal control problem, we define 250 knots (or running action -# models) plus a terminal knot -T = 100 -problem = crocoddyl.ShootingProblem(robot_model.x0, [runningModel] * T, terminalModel) - -# Creating the DDP solver for this OC problem, defining a logger -ddp = crocoddyl.SolverDDP(problem) -ddp.setCallbacks([ - crocoddyl.CallbackLogger(), - crocoddyl.CallbackVerbose(), -]) - -# Solving it with the DDP algorithm -ddp.solve([],[],1000) # xs_init,us_init,maxiter - -# Plotting the solution and the DDP convergence -if WITHPLOT: - log = ddp.getCallbacks()[0] - crocoddyl.plotOCSolution(log.xs, log.us, figIndex=1, show=False) - crocoddyl.plotConvergence(log.costs, log.u_regs, log.x_regs, log.grads, log.stops, log.steps, figIndex=2) - -# Visualizing the solution in gepetto-viewer -if WITHDISPLAY: - import tp7.croco_utils as crocutils - crocutils.displayTrajectory(viz,ddp.xs,ddp.problem.runningModels[0].dt,12) diff --git a/tp5/croco_utils.py b/tp5/croco_utils.py deleted file mode 100644 index f667a58..0000000 --- a/tp5/croco_utils.py +++ /dev/null @@ -1,17 +0,0 @@ -def displayTrajectory(viz, xs, dt=0.01, rate=-1): - """ Display a robot trajectory xs using Gepetto-viewer gui. - - :param robot: Robot wrapper - :param xs: state trajectory - :param dt: step duration - :param rate: visualization rate - """ - - import time - S = 1 if rate <= 0 else max(int(1/dt/rate), 1) - for i, x in enumerate(xs): - if not i % S: - viz.display(x[:viz.model.nq]) - time.sleep(dt*S) - viz.display(xs[-1][:viz.model.nq]) - diff --git a/tp5/generated/general_ddp_4stage b/tp5/generated/general_ddp_4stage deleted file mode 100644 index f81498d..0000000 --- a/tp5/generated/general_ddp_4stage +++ /dev/null @@ -1,77 +0,0 @@ -state = crocoddyl.StateMultibody(robot_model) -# The state object containt info about the configspace, the constraint, the velocity, the kinematic values and everything - -# State is quite abstract, to have a real solvable OCP we need to define somme cost associated to this model -# We also need to decide the actual dynamic we will follow (called actuation), it means a solver that will be ourf(x,u) AND a way to descretize it - -rcms = [] -tcms = [] - -for i in range(4): - runningCostModel = crocoddyl.CostModelSum(state) # The state will remain the same during running - terminalCostModel = crocoddyl.CostModelSum(state) # And also for final state - - ### Cost for reaching the target - pref = crocoddyl.FrameTranslation(FRAME_TIP, goals[i]) - goalTrackingCost = crocoddyl.CostModelFrameTranslation(state, pref) - - ### Cost for regularizing the state about robot_model.x0, running AND terminal - weights=crocoddyl.ActivationModelWeightedQuad(np.array([1,1,1,1,1,1,1, 1,1,1,1,2,2,2.])) - xRegCost = crocoddyl.CostModelState(state,weights,robot_model.x0) - weightsT=crocoddyl.ActivationModelWeightedQuad(np.array([.01,.01,.01,.01,.01,.01,.01, 1,1,1,1,2,2,2.])) - xRegCostT = crocoddyl.CostModelState(state,weightsT,robot_model.x0) - - ### Cost for keeping the control low: around zeros with uniform weights - uRegCost = crocoddyl.CostModelControl(state) - - - runningCostModel.addCost("gripperPose", goalTrackingCost, .001) # addCost is a method of CostModelSum that take another CostModel - runningCostModel.addCost("xReg", xRegCost, 1e-3) # We also weight the sum of cost - runningCostModel.addCost("uReg", uRegCost, 1e-6) - terminalCostModel.addCost("gripperPose", goalTrackingCost, 10) - terminalCostModel.addCost("xReg", xRegCostT, .01) - terminalCostModel.addCost("uReg", xRegCostT, 1e-6) - - rcms.append(runningCostModel) - tcms.append(terminalCostModel) - - -actuationModel = crocoddyl.ActuationModelFull(state) -dt = 1e-2 -# A step in the running step -## We use the freefall forward dynamic as dotx = f(x,u) it could be a contact one (as in prev TP) and so on -### It is the differential model chosen around the state -## We precise the duration of the step dt -## We precise the integration scheme we use -### It is the integrated model chosen around the differential model -## We precise which cost is used during this step -def make_running_model(rcm): - runningModel = crocoddyl.IntegratedActionModelEuler( - crocoddyl.DifferentialActionModelFreeFwdDynamics(state, actuationModel, rcm), dt) - runningModel.differential.armature = robot_model.armature - return runningModel - -def make_terminal_model(tcm): - runningModel = crocoddyl.IntegratedActionModelEuler( - crocoddyl.DifferentialActionModelFreeFwdDynamics(state, actuationModel, tcm), 0.) - runningModel.differential.armature = robot_model.armature - return runningModel - -terminalModel = crocoddyl.IntegratedActionModelEuler( - crocoddyl.DifferentialActionModelFreeFwdDynamics(state, actuationModel, terminalCostModel), 0.) -terminalModel.differential.armature = robot_model.armature - -T = 100 -T_inter = 1 - -def create_problem(n): - rmseq = [] - for i in range(n - 1): - rmseq += [make_running_model(rcms[i])] * T - rmseq += [make_running_model(tcms[i])] * T_inter - rmseq += [make_running_model(rcms[n-1])] * T - tm = make_terminal_model(tcms[n-1]) - return crocoddyl.ShootingProblem(robot_model.x0, rmseq, tm) - -ddp = crocoddyl.SolverDDP(create_problem(4)) -ddp.solve() diff --git a/tp5/generated/unicycle_solutions_termmodel b/tp5/generated/unicycle_solutions_termmodel deleted file mode 100644 index 328550f..0000000 --- a/tp5/generated/unicycle_solutions_termmodel +++ /dev/null @@ -1,10 +0,0 @@ -model_term = crocoddyl.ActionModelUnicycle() - -model_term.costWeights = np.matrix([ - 100, # state weight - 0 # control weight -]).T - -# Define integral+terminal models -problem = crocoddyl.ShootingProblem(x0, [ model ] * T, model_term) -ddp = crocoddyl.SolverDDP(problem) diff --git a/tp5/unicycle_solutions.py b/tp5/unicycle_solutions.py deleted file mode 100644 index c41d30b..0000000 --- a/tp5/unicycle_solutions.py +++ /dev/null @@ -1,38 +0,0 @@ -import crocoddyl -from unicycle_utils import plotUnicycleSolution -import numpy as np -import matplotlib.pylab as plt; plt.ion() - -### HYPER PARAMS: horizon and initial state -T = 100 -x0 = np.array([-1,-1,1]) - -### PROBLEM DEFINITION - -model = crocoddyl.ActionModelUnicycle() -# %jupyter_snippet termmodel -model_term = crocoddyl.ActionModelUnicycle() - -model_term.costWeights = np.matrix([ - 100, # state weight - 0 # control weight -]).T - -# Define integral+terminal models -problem = crocoddyl.ShootingProblem(x0, [ model ] * T, model_term) -ddp = crocoddyl.SolverDDP(problem) -# %end_jupyter_snippet - -# Add solvers for verbosity and plots -ddp.setCallbacks([crocoddyl.CallbackLogger(), crocoddyl.CallbackVerbose()]) - -### SOLVER PROBLEM -done = ddp.solve() -assert(done) - -### PLOT -log = ddp.getCallbacks()[0] -crocoddyl.plotOCSolution(log.xs, log.us, figIndex=1, show=False) -crocoddyl.plotConvergence(log.costs, log.u_regs, log.x_regs, log.grads, log.stops, log.steps, figIndex=2, show=False) -plotUnicycleSolution(log.xs, figIndex=3, show=True) - diff --git a/tp5/unicycle_utils.py b/tp5/unicycle_utils.py deleted file mode 100644 index 2980cff..0000000 --- a/tp5/unicycle_utils.py +++ /dev/null @@ -1,23 +0,0 @@ -import matplotlib.pyplot as plt -import numpy as np - - -def plotUnicycle(x): - sc, delta = .1, .1 - a, b, th = x[0], x[1], x[2] - c, s = np.cos(th), np.sin(th) - refs = [ - plt.arrow(a - sc / 2 * c - delta * s, b - sc / 2 * s + delta * c, c * sc, s * sc, head_width=.05), - plt.arrow(a - sc / 2 * c + delta * s, b - sc / 2 * s - delta * c, c * sc, s * sc, head_width=.05) - ] - return refs - - -def plotUnicycleSolution(xs, figIndex=1, show=True): - import matplotlib.pylab as plt - plt.figure(figIndex, figsize=(6.4, 6.4)) - for x in xs: - plotUnicycle(x) - plt.axis([-2, 2., -2., 2.]) - if show: - plt.show() diff --git a/tp7/ddpg.py b/tp7/ddpg.py deleted file mode 100644 index ed4e187..0000000 --- a/tp7/ddpg.py +++ /dev/null @@ -1,306 +0,0 @@ -''' -Deep actor-critic network, -From "Continuous control with deep reinforcement learning", by Lillicrap et al, arXiv:1509.02971 -''' - -from env_pendulum import EnvPendulumSinCos; Env = lambda : EnvPendulumSinCos(1,viewer='meshcat') -import gym -import tensorflow as tf -import tensorflow.keras as tfk -import numpy as np -import matplotlib.pyplot as plt -import time -import random -from collections import deque -import signal - -#######################################################################################################33 -#######################################################################################################33 -#######################################################################################################33 -### --- Random seed -RANDOM_SEED = 0 # int((time.time()%10)*1000) -print("Seed = %d" % RANDOM_SEED) -np .random.seed (RANDOM_SEED) -random.seed (RANDOM_SEED) -tf.random.set_seed (RANDOM_SEED) - -### --- Hyper paramaters -NEPISODES = 1000 # Max training steps -NSTEPS = 200 # Max episode length -QVALUE_LEARNING_RATE = 0.001 # Base learning rate for the Q-value Network -POLICY_LEARNING_RATE = 0.0001 # Base learning rate for the policy network -DECAY_RATE = 0.99 # Discount factor -UPDATE_RATE = 0.01 # Homotopy rate to update the networks -REPLAY_SIZE = 10000 # Size of replay buffer -BATCH_SIZE = 64 # Number of points to be fed in stochastic gradient -NH1 = NH2 = 250 # Hidden layer size -EXPLORATION_NOISE = 0.2 - -### --- Environment -# problem = "Pendulum-v1" -# env = gym.make(problem) -# NX = env.observation_space.shape[0] -# NU = env.action_space.shape[0] -# UMAX = env.action_space.high[0] -# env.reset(seed=RANDOM_SEED) -# assert( env.action_space.low[0]==-UMAX) - -env = Env() # Continuous pendulum -NX = env.nx # ... training converges with q,qdot with 2x more neurones. -NU = env.nu # Control is dim-1: joint torque -UMAX = env.umax[0] # Torque range - - -#######################################################################################################33 -### NETWORKS ##########################################################################################33 -#######################################################################################################33 - -class QValueNetwork: - ''' - Neural representaion of the Quality function: - Q: x,y -> Q(x,u) \in R - ''' - def __init__(self,nx,nu,nhiden1=32,nhiden2=256,learning_rate=None): - - state_input = tfk.layers.Input(shape=(nx)) - state_out = tfk.layers.Dense(nhiden1, activation="relu")(state_input) - state_out = tfk.layers.Dense(nhiden1, activation="relu")(state_out) - - action_input = tfk.layers.Input(shape=(nu)) - action_out = tfk.layers.Dense(nhiden1, activation="relu")(action_input) - - concat = tfk.layers.Concatenate()([state_out, action_out]) - - out = tfk.layers.Dense(nhiden2, activation="relu")(concat) - out = tfk.layers.Dense(nhiden2, activation="relu")(out) - value_output = tfk.layers.Dense(1)(out) - - self.model = tfk.Model([state_input, action_input], value_output) - - @tf.function - def targetAssign(self,target,tau=UPDATE_RATE): - for (tar,cur) in zip(target.model.variables,self.model.variables): - tar.assign(cur * tau + tar * (1 - tau)) - - -class PolicyNetwork: - ''' - Neural representation of the policy function: - Pi: x -> u=Pi(x) \in R^nu - ''' - def __init__(self,nx,nu,umax,nhiden=32,learning_rate=None): - random_init = tf.random_uniform_initializer(minval=-0.005, maxval=0.005) - - state_input = tfk.layers.Input(shape=(nx,)) - out = tfk.layers.Dense(nhiden, activation="relu")(state_input) - out = tfk.layers.Dense(nhiden, activation="relu")(out) - policy_output = tfk.layers.Dense(1, activation="tanh", - kernel_initializer=random_init)(out)*umax - self.model = tfk.Model(state_input, policy_output) - - @tf.function - def targetAssign(self,target,tau=UPDATE_RATE): - for (tar,cur) in zip(target.model.variables,self.model.variables): - tar.assign(cur * tau + tar * (1 - tau)) - - def numpyPolicy(self,x,noise=None): - '''Eval the policy with numpy input-output (nx,)->(nu,).''' - x_tf = tf.expand_dims(tf.convert_to_tensor(x), 0) - u = np.squeeze(self.model(x_tf).numpy(),0) - if noise is not None: - u = np.clip( u+noise, -UMAX,UMAX) - return u - - def __call__(self, x,**kwargs): - return self.numpyPolicy(x,**kwargs) - - - -#######################################################################################################33 - -class OUNoise: - ''' - Ornstein–Uhlenbeck processes are markov random walks with the nice property to eventually - converge to its mean. - We use it for adding some random search at the begining of the exploration. - ''' - def __init__(self, mean, std_deviation, theta=0.15, dt=1e-2, y_initial=None,dtype=np.float32): - self.theta = theta - self.mean = mean.astype(dtype) - self.std_dev = std_deviation.astype(dtype) - self.dt = dt - self.dtype=dtype - self.reset(y_initial) - - def __call__(self): - # Formula taken from https://www.wikipedia.org/wiki/Ornstein-Uhlenbeck_process. - noise = np.random.normal(size=self.mean.shape).astype(self.dtype) - self.y += \ - self.theta * (self.mean - self.y) * self.dt \ - + self.std_dev * np.sqrt(self.dt) * noise - return self.y.copy() - - def reset(self,y_initial = None): - self.y = y_initial.astype(self.dtype) if y_initial is not None else np.zeros_like(self.mean) - -### --- Replay memory -class ReplayItem: - ''' - Storage for the minibatch - ''' - def __init__(self,x,u,r,d,x2): - self.x = x - self.u = u - self.reward = r - self.done = d - self.x2 = x2 - - -#######################################################################################################33 -quality = QValueNetwork(NX,NU,NH1,NH2) -qualityTarget = QValueNetwork(NX,NU,NH1,NH2) -quality.targetAssign(qualityTarget,1) - -policy = PolicyNetwork(NX,NU,umax=UMAX,nhiden=NH2) -policyTarget = PolicyNetwork(NX,NU,umax=UMAX,nhiden=NH2) -policy.targetAssign(policyTarget,1) - -replayDeque = deque() - -ou_noise = OUNoise(mean=np.zeros(1), std_deviation=float(EXPLORATION_NOISE) * np.ones(1)) -ou_noise.reset( np.array([ UMAX/2 ]) ) - -#######################################################################################################33 -### MAIN ACTOR-CRITIC BLOCK -#######################################################################################################33 - -critic_optimizer = tfk.optimizers.Adam(QVALUE_LEARNING_RATE) -actor_optimizer = tfk.optimizers.Adam(POLICY_LEARNING_RATE) - -@tf.function -def learn(state_batch, action_batch, reward_batch, next_state_batch): - ''' - is isolated in a tf.function to make it more efficient. - @tf.function forces tensorflow to optimize the inner computation graph defined in this function. - ''' - - # Automatic differentiation of the critic loss, using tf.GradientTape - # The critic loss is the classical Q-learning loss: - # loss = || Q(x,u) - (reward + Q(xnext,Pi(xnexT)) ) ||**2 - with tf.GradientTape() as tape: - target_actions = policyTarget.model(next_state_batch, training=True) - y = reward_batch + DECAY_RATE * qualityTarget.model( - [next_state_batch, target_actions], training=True - ) - critic_value = quality.model([state_batch, action_batch], training=True) - critic_loss = tf.math.reduce_mean(tf.math.square(y - critic_value)) - - critic_grad = tape.gradient(critic_loss, quality.model.trainable_variables) - critic_optimizer.apply_gradients( - zip(critic_grad, quality.model.trainable_variables) - ) - - # Automatic differentiation of the actor loss, using tf.GradientTape - # The actor loss implements a greedy optimization on the quality function - # loss(u) = Q(x,u) - with tf.GradientTape() as tape: - actions = policy.model(state_batch, training=True) - critic_value = quality.model([state_batch, actions], training=True) - actor_loss = -tf.math.reduce_mean(critic_value) - - actor_grad = tape.gradient(actor_loss, policy.model.trainable_variables) - actor_optimizer.apply_gradients( - zip(actor_grad, policy.model.trainable_variables) - ) - - -#######################################################################################################33 -#######################################################################################################33 -#######################################################################################################33 - -def rendertrial(maxiter=NSTEPS,verbose=True): - ''' - Display a roll-out from random start and optimal feedback. - Press ^Z to get a roll-out at training time. - ''' - x = env.reset() - rsum = 0. - for i in range(maxiter): - u = policy(x) - x, reward = env.step(u)[:2] - env.render() - rsum += reward - if verbose: print('Lasted ',i,' timestep -- total reward:',rsum) -signal.signal(signal.SIGTSTP, lambda x,y:rendertrial()) # Roll-out when CTRL-Z is pressed -env.full.sleepAtDisplay=5e-3 - -# Logs -h_rewards = [] -h_steps = [] - -# Takes about 4 min to train -for episode in range(NEPISODES): - - prev_state = env.reset() - - for step in range(NSTEPS): - # Uncomment this to see the Actor in action - # But not in a python notebook. - #env.render() - - action = policy(prev_state, noise=ou_noise()) - state, reward = env.step(action)[:2] - done=False - - replayDeque.append(ReplayItem(prev_state, action, reward, done, state)) - - prev_state = state - - if len(replayDeque) <= BATCH_SIZE: continue - - - #################################################################### - # Sample a minibatch - - batch = random.sample(replayDeque,BATCH_SIZE) # Random batch from replay memory. - state_batch = tf.convert_to_tensor([ b.x for b in batch ]) - action_batch = tf.convert_to_tensor([ b.u for b in batch ]) - reward_batch = tf.convert_to_tensor([ [ b.reward ] for b in batch ],dtype=np.float32) - done_batch = tf.convert_to_tensor([ b.done for b in batch ]) - next_state_batch = tf.convert_to_tensor([ b.x2 for b in batch ]) - - #################################################################### - # One gradient step for the minibatch - - # Critic and actor gradients - learn(state_batch, action_batch, reward_batch, next_state_batch) - # Step smoothing using target networks - policy.targetAssign(policyTarget) - quality.targetAssign(qualityTarget) - - if done: break # stop at episode end. - - # Some prints and logs - episodic_reward = sum([ replayDeque[-i-1].reward for i in range(step+1) ]) - h_rewards.append( episodic_reward ) - h_steps.append(step+1) - - print(f'Ep#{episode:3d}: lasted {step+1:d} steps, reward={episodic_reward:3.1f} ') - - - # avg_reward = np.mean(h_rewards[-40:]) - # if episode==5 and RANDOM_SEED==0: - # assert( abs(avg_reward + 1423.0528188196286) < 1e-3 ) - # if episode==0 and RANDOM_SEED==0: - # assert( abs(avg_reward + 1712.386325099637) < 1e-3 ) - -# Plotting graph -# Episodes versus Avg. Rewards -plt.plot(h_rewards) -plt.xlabel("Episode") -plt.ylabel("Epsiodic Reward") -plt.show() - -#######################################################################################################33 -#######################################################################################################33 -#######################################################################################################33 diff --git a/tp7/deeptable.py b/tp7/deeptable.py deleted file mode 100644 index d4498e7..0000000 --- a/tp7/deeptable.py +++ /dev/null @@ -1,106 +0,0 @@ -''' -Example of Q-table learning with a simple discretized 1-pendulum environment using a linear Q network. -''' - -import numpy as np -import random -import tensorflow as tf -import tensorflow.compat.v1 as tf1 -import matplotlib.pyplot as plt -from tp7.env_pendulum import EnvPendulumDiscrete; Env = lambda : EnvPendulumDiscrete(1,viewer='meshcat') -import signal -import time -tf1.disable_eager_execution() - - -### --- Random seed -RANDOM_SEED = int((time.time()%10)*1000) -print("Seed = %d" % RANDOM_SEED) -np.random.seed(RANDOM_SEED) - -### --- Hyper paramaters -NEPISODES = 2000 # Number of training episodes -NSTEPS = 50 # Max episode length -LEARNING_RATE = 0.1 # Step length in optimizer -DECAY_RATE = 0.99 # Discount factor - -### --- Environment -env = Env() -NX = env.nx -NU = env.nu - -### --- Q-value networks -class QValueNetwork: - def __init__(self): - x = tf1.placeholder(shape=[1,NX],dtype=tf.float32) - W = tf1.Variable(tf1.random_uniform([NX,NU],0,0.01,seed=100)) - qvalue = tf1.matmul(x,W) - u = tf1.argmax(qvalue,1) - - qref = tf1.placeholder(shape=[1,NU],dtype=tf.float32) - loss = tf1.reduce_sum(tf.square(qref - qvalue)) - optim = tf1.train.GradientDescentOptimizer(LEARNING_RATE).minimize(loss) - - self.x = x # Network input - self.qvalue = qvalue # Q-value as a function of x - self.u = u # Policy as a function of x - self.qref = qref # Reference Q-value at next step (to be set to l+Q o f) - self.optim = optim # Optimizer - -### --- Tensor flow initialization -#tf.reset_default_graph() -qvalue = QValueNetwork() -sess = tf1.InteractiveSession() -tf1.global_variables_initializer().run() - -def onehot(ix,n=NX): - '''Return a vector which is 0 everywhere except index set to 1.''' - return np.array([[ (i==ix) for i in range(n) ],],np.float) - -def disturb(u,i): - u += int(np.random.randn()*10/(i/50+10)) - return np.clip(u,0,NU-1) - -def rendertrial(maxiter=100): - x = env.reset() - for i in range(maxiter): - u = sess.run(qvalue.u,feed_dict={ qvalue.x:onehot(x) }) - x,r = env.step(u) - env.render() - if r==1: print('Reward!'); break -signal.signal(signal.SIGTSTP, lambda x,y:rendertrial()) # Roll-out when CTRL-Z is pressed - -### --- History of search -h_rwd = [] # Learning history (for plot). - -### --- Training -for episode in range(1,NEPISODES): - x = env.reset() - rsum = 0.0 - - for step in range(NSTEPS-1): - u = sess.run(qvalue.u,feed_dict={ qvalue.x: onehot(x) })[0] # Greedy policy ... - u = disturb(u,episode) # ... with noise - x2,reward = env.step(u) - - # Compute reference Q-value at state x respecting HJB - Q2 = sess.run(qvalue.qvalue,feed_dict={ qvalue.x: onehot(x2) }) - Qref = sess.run(qvalue.qvalue,feed_dict={ qvalue.x: onehot(x ) }) - Qref[0,u] = reward + DECAY_RATE*np.max(Q2) - - # Update Q-table to better fit HJB - sess.run(qvalue.optim,feed_dict={ qvalue.x : onehot(x), - qvalue.qref : Qref }) - - rsum += reward - x = x2 - if reward == 1: break - - h_rwd.append(rsum) - if not episode%20: print('Episode #%d done with %d sucess' % (episode,sum(h_rwd[-20:]))) - -print("Total rate of success: %.3f" % (sum(h_rwd)/NEPISODES)) -rendertrial() -plt.plot( np.cumsum(h_rwd)/range(1,NEPISODES) ) -plt.show() - diff --git a/tp7/discretization.py b/tp7/discretization.py deleted file mode 100644 index f1caded..0000000 --- a/tp7/discretization.py +++ /dev/null @@ -1,85 +0,0 @@ -''' -Helper class to systematically convert a R^n vector of float into a -N^n vector of integers, and to a single integer. -The main methods are flat2continuous and continuous2flat. -Build it from the size of the real vector space, the bounds in each directions and -the number of discretization steps. - -See also numpy.digitalize. -''' - -import numpy as np -from functools import reduce - -class VectorDiscretization: - ''' - Convertion between continuous R^N bounded vectors and their discretization - as N^N bounded integer vectors and N*N integer. - ''' - def __init__(self,nv,vmax=1.,vmin=None,nsteps=10,modulo=None,moduloIdx=[]): - self.nv = nv # Dimension of the vector space - self.vmax = vmax if isinstance(vmax,np.ndarray) else np.array([vmax,]*nv) - self.vmin = vmin if isinstance(vmin,np.ndarray) else -self.vmax if vmin is None else np.array([vmin,]*nv) - self.nsteps = nsteps if isinstance(nsteps,np.ndarray) else np.array([nsteps,]*nv) - self.nd = reduce(lambda i,j:i*j,self.nsteps) # prod_{s in nsteps} s = s1*s2*...*s_nv - self.modulo = modulo - self.moduloIdx = moduloIdx - assert( self.nsteps.dtype == np.int32 or self.nsteps.dtype == np.int64) - - def continuous2discrete(self,vc): - if self.modulo is not None and len(self.moduloIdx)>0: - vc = vc.copy() - vc[self.moduloIdx] += self.modulo/2 - vc[self.moduloIdx] = vc[self.moduloIdx] % self.modulo - vc[self.moduloIdx] -= self.modulo/2 - vc = np.clip(vc,self.vmin,self.vmax) - return ((vc-self.vmin)/(self.vmax-self.vmin)*self.nsteps).astype(self.nsteps.dtype) - - def discrete2continuous(self,vd): - return (vd+.5)*(self.vmax-self.vmin)/self.nsteps+self.vmin - - def flatten(self,vd): - '''change an array of int to a flat int.''' - assert( np.all(vd=0 and i0.0: tau -= self.Kf*v - # Evaluate cost - cost += self.cost(np.concatenate([q,v]),u)/self.NDT - #print(self,self.cost,t,x,u,cost) - # Evaluate dynamics - a = pin.aba(self.rmodel,self.rdata,q,v,tau) - if verbose: print(q,v,tau,a) - v += a*dt - v = np.clip(v,self.xmin[self.nq:],self.xmax[self.nq:]) - q = pin.integrate(self.rmodel,q,v*dt) - xnext = np.concatenate([q,v]) - return xnext,cost - -# ---------------------------------------------------------------------------------------- -# --- PARTIALLY OBSERVABLE --------------------------------------------------------------- -# ---------------------------------------------------------------------------------------- -class EnvPartiallyObservable(EnvContinuousAbstract): - def __init__(self,env_fully_observable,nobs,obs,obsInv=None): - ''' - Define a partially-observable markov model from a fully-observable model - and an observation function. - The new env model is defined with the observable as new state, while - the original state is kept inside the fully-observable model. - - @param env_fully_observable: the fully-observable model. - @param obs: the observation function y=h(x) - @param obsinv: if available, the inverse function of h: x=h^-1(y). - ''' - self.full = env_fully_observable - self.obs = obs - self.obsinv = obsInv - EnvContinuousAbstract.__init__(self,nx=nobs, - nu=self.full.nu, - xmax=obs(self.full.xmax), - xmin=obs(self.full.xmin), - umax=self.full.umax,umin=self.full.umin) - - def randomState(self): - return self.obs(self.full.randomState()) - def dynAndCost(self,x,u): - assert(self.obsinv is not None) - x,c = self.full.dynAndCost(self.obsinv(x),u) - return self.obs(x),c - def display(self,x): - assert(self.obsinv is not None) - self.full.display(self.obsinv(x)) - - def reset(self,x=None): - assert(x is not None or self.obsinv is not None) - return self.obs(self.full.reset(x)) - def step(self,u): - x,c = self.full.step(u) - return self.obs(x),c - def render(self): - return self.full.render() - @property - def x(self): - return self.obs(self.full.x) - - - -# ---------------------------------------------------------------------------------------- -# --- DISCRETIZED ENV -------------------------------------------------------------------- -# ---------------------------------------------------------------------------------------- - -class EnvDiscretized(EnvAbstract): - def __init__(self,envContinuous,discretize_x = 0,discretize_u = 0): - self.conti = envContinuous - if discretize_u != 0: - self.discretize_u = VectorDiscretization(self.conti.nu, - vmax=self.conti.umax,nsteps=discretize_u) - self.encode_u = self.discretize_u.c2i - self.decode_u = self.discretize_u.i2c - nu = self.discretize_u.nd - else: - self.discretize_u = None - self.encode_u = lambda u:u - self.decode_u = lambda u:u - nu = envContinuous.nu - if discretize_x != 0: - self.discretize_x = VectorDiscretization(self.conti.nx, - vmax=self.conti.xmax,nsteps=discretize_x) - self.encode_x = self.discretize_x.c2i - self.decode_x = self.discretize_x.i2c - nx = self.discretize_x.nd - else: - self.discretize_x = None - self.encode_x = lambda x:x - self.decode_x = lambda x:x - nx = envContinuous.nx - - EnvAbstract.__init__(self,nx=nx,nu=nu) - - def randomState(self): - return self.encode_x(self.conti.randomState()) - def display(self,x): - self.conti.display(self.decode_x(x)) - def dynAndCost(self,x,u): - x,c=self.conti.dynAndCost(self.decode_x(x),self.decode_u(u)) - return self.encode_x(x),c - def reset(self,xi=None): - if xi is None: - x = self.conti.reset() - xi = self.encode_x(x) - else: - x = None - x_eps = self.decode_x(xi) - if x_eps is not x: - self.conti.reset(x_eps) - self.x = xi - return self.x - def step(self,u): - ###assert(self.x == self.encode_x(self.conti.x)) - ###assert(np.allclose(self.decode_x(self.x),self.conti.x)) - x,c = self.conti.step(self.decode_u(u)) - self.x= self.encode_x(x) - x_eps = self.decode_x(self.x) - if x_eps is not x: self.conti.reset(x_eps) - return self.x,c - def render(self): - self.conti.render() - - - - diff --git a/tp7/env_pendulum.py b/tp7/env_pendulum.py deleted file mode 100644 index c21859d..0000000 --- a/tp7/env_pendulum.py +++ /dev/null @@ -1,191 +0,0 @@ -''' -Create a simulation environment for a N-pendulum. -See the main at the end of the file for an example. - -We define here 4 main environments that are tested in the __main__: - -- EnvPendulum: state NX=2 continuous, control NU=1 continuous, Euler integration step with DT=1e-2 and high friction -- EnvPendulumDiscrete: state NX=441 discrete, control NU=11 discrete, Euler step DT=0.5 low friction -- EnvPendulumSinCos: state NX=3 with x=[cos,sin,vel], control NU=1 control, Euler step DT=1e-2, high friction -- EnvPendulumHybrid: state NX=3 continuous with x=[cos,sin,vel], control NU=11 discrete, Euler step DT=0.5 low friction - -''' - -import pinocchio as pin -import numpy as np -from tp7.models.pendulum import createPendulum -from tp7.env_abstract import EnvPinocchio -import tp7.env_abstract as env_abstract - -# --- PENDULUM ND CONTINUOUS -------------------------------------------------------------------- -# --- PENDULUM ND CONTINUOUS -------------------------------------------------------------------- -# --- PENDULUM ND CONTINUOUS -------------------------------------------------------------------- - -class EnvPendulum(EnvPinocchio): - ''' - Define a class Robot with 7DOF (shoulder=3 + elbow=1 + wrist=3). - The configuration is nq=7. The velocity is the same. - The members of the class are: - * viewer: a display encapsulating a gepetto viewer client to create 3D objects and place them. - * model: the kinematic tree of the robot. - * data: the temporary variables to be used by the kinematic algorithms. - * visuals: the list of all the 'visual' 3D objects to render the robot, each element of the list being - an object Visual (see above). - - See tp1.py for an example of use. - ''' - - def __init__(self,nbJoint=1,viewer=None): - ''' - Create a Pinocchio model of a N-pendulum, with N the argument . - is expected to be in { "meshcat" | "gepetto" | None }. - ''' - self.model,self.geometryModel = createPendulum(nbJoint) - if viewer == 'meshcat': - from pinocchio.visualize import MeshcatVisualizer - self.viewer = MeshcatVisualizer(self.model,self.geometryModel,self.geometryModel) - self.viewer.initViewer(loadModel=True) - elif 'gepetto' == viewer: - from pinocchio.visualize import GepettoVisualizer - self.viewer = GepettoVisualizer(self.model,self.geometryModel,self.geometryModel) - self.viewer.initViewer(loadModel=True) - else: - self.viewer = None - if viewer is not None: ## warning - print('Error: is expected to be in { "meshcat" | "gepetto" | None }, but we got:', viewer) - - self.q0 = pin.neutral(self.model) - self.v0 = np.zeros(self.model.nv) - self.x0 = np.concatenate([self.q0,self.v0]) - - EnvPinocchio.__init__(self,self.model,self.viewer,taumax=2.5) - self.DT = 1e-2 # duration of one environment step - self.NDT = 5 # number of euler integration step per environment step (i.e integration interval is DT/NDT) - self.Kf = 1.0 # Friction coefficient - - self.costWeights = { 'q': 1, 'v' : 1e-1, 'u' : 1e-3, 'tip' : 0. } - self.tipDes = float(nbJoint) - - def cost(self,x=None,u=None): - if x is None: x = self.x - cost = 0. - q,v = x[:self.nq],x[-self.nv:] - qdes = self.xdes[:self.nq] - cost += self.costWeights['q']*np.sum((q-qdes)**2) - cost += self.costWeights['v']*np.sum(v**2) - cost += 0 if u is None else self.costWeights['u']*np.sum(u**2) - cost += self.costWeights['tip']*(self.tip(q)-self.tipDes)**2 - return cost - - def tip(self,q=None): - '''Return the altitude of pendulum tip''' - if q is None: q = self.x[:self.nq] - pin.framesForwardKinematics(self.rmodel,self.rdata,q) - return self.rdata.oMf[1].translation[2] - - def jupyter_cell(self): - return self.viewer.viewer.jupyter_cell() - -# --- SPIN-OFF ---------------------------------------------------------------------------------- -# --- SPIN-OFF ---------------------------------------------------------------------------------- -# --- SPIN-OFF ---------------------------------------------------------------------------------- - -class EnvPendulumDiscrete(env_abstract.EnvDiscretized): - def __init__(self,nbJoint=1,**kwargs): - env = EnvPendulum(nbJoint,**kwargs) - env.DT=5e-1 # Larger integration step to allow larger discretization grid - env.Kf=0.1 # Reduced friction, because larger steps would make friction unstable. - env_abstract.EnvDiscretized.__init__(self,env,21,11) - self.discretize_x.modulo = np.pi*2 - self.discretize_x.moduloIdx = range(env.nq) - self.discretize_x.vmax[:env.nq] = np.pi - self.discretize_x.vmin[:env.nq] = -np.pi - self.reset() - self.conti.costWeights = { 'q': 0, 'v' : 0, 'u' : 0, 'tip' : 1 } - self.withSimpleCost = True - def step(self,u): - x,c=env_abstract.EnvDiscretized.step(self,u) - if self.withSimpleCost: - c = int(np.all(np.abs(self.conti.x)<1e-3)) - return x,c - def jupyter_cell(self): - return self.conti.viewer.viewer.jupyter_cell() - -class EnvPendulumSinCos(env_abstract.EnvPartiallyObservable): - def __init__(self,nbJoint=1,**kwargs): - env = EnvPendulum(nbJoint,**kwargs) - def sincos(x,nq): - q,v = x[:nq],x[nq:] - return np.concatenate([np.concatenate([(np.cos(qi),np.sin(qi)) for qi in q]),v]) - def atan(x,nq): - cq,sq,v = x[:2*nq:2],x[1:2*nq:2],x[2*nq:] - return np.concatenate([np.arctan2(sq,cq),v]) - env_abstract.EnvPartiallyObservable.__init__(self,env,nobs=env.nq*2+env.nv, - obs=lambda x:sincos(x,env.nq), - obsInv=lambda csv:atan(csv,env.nq)) - self.reset() - def jupyter_cell(self): - return self.full.viewer.jupyter_cell() - -class EnvPendulumHybrid(env_abstract.EnvDiscretized): - def __init__(self,nbJoint=1,**kwargs): - env = EnvPendulumSinCos(nbJoint,**kwargs) - NU = 21 #11 - env_abstract.EnvDiscretized.__init__(self,env,discretize_x=0,discretize_u=NU) - self.conti.full.Kf=.1 # Reduced friction, because larger steps would make friction unstable. - self.conti.full.DT=1e-1 # 5e-1 # Larger integration step to allow larger discretization grid - self.conti.full.costWeights = {'q': 0, 'tip': 1.0, 'u': 0.00, 'v': 0.1 } - - self.reset() - # self.withSimpleCost = False - # def step(self,u): - # x,c=env_abstract.EnvDiscretizedenv_abstract.step(self,u) - # if self.withSimpleCost: - # c = int(np.all(np.abs(self.conti.x)<1e-3)) - # return x,c - def jupyter_cell(self): - return self.conti.full.viewer.viewer.jupyter_cell() - - -# --- MAIN ------------------------------------------------------------------------------- -# --- MAIN ------------------------------------------------------------------------------- -# --- MAIN ------------------------------------------------------------------------------- - -if __name__ == "__main__": - import time - - envs = [] - - env = EnvPendulum(1,viewer='gepetto') - env.name = str(env.__class__) - env.u0 = np.zeros(env.nu) - envs.append(env) - - env = EnvPendulumDiscrete(1,viewer='gepetto') - env.name = str(env.__class__) - env.u0 = env.encode_u(np.zeros(1)) - envs.append(env) - - env = EnvPendulumSinCos(1,viewer='gepetto') - env.name = str(env.__class__) - env.u0 = np.zeros(env.nu) - envs.append(env) - - env = EnvPendulumHybrid(1,viewer='gepetto') - env.name = str(env.__class__) - env.u0 = env.encode_u(np.zeros(1)) - envs.append(env) - - # Reset all environment to the same initial state. - envs[1].reset() - for env in envs: - if env is not envs[1]: env.reset(envs[1].conti.x) - - # Simulate a free fall for all environments. - for env in envs: - env.render() - print(env.name) - time.sleep(1) - for i in range(10): - env.step(env.u0) - env.render() diff --git a/tp7/flow.py b/tp7/flow.py deleted file mode 100644 index 3563922..0000000 --- a/tp7/flow.py +++ /dev/null @@ -1,15 +0,0 @@ -import matplotlib.pylab as plt -import numpy as np - -def plotFlow(env,policy,x2d): - flow = [] - for s in range(env.nx): - env.reset(s) - x = x2d(s) - a = policy(s) - snext,r = env.step(a) - xnext = x2d(snext) - flow.append( [x,xnext-x] ) - - flow=np.array( [ np.concatenate(a) for a in flow ]) - h = plt.quiver(flow[:,0],flow[:,1],flow[:,2],flow[:,3]) diff --git a/tp7/models/pendulum.py b/tp7/models/pendulum.py deleted file mode 100644 index ba96692..0000000 --- a/tp7/models/pendulum.py +++ /dev/null @@ -1,92 +0,0 @@ -''' -Create a simulation environment for a N-pendulum. -Example of use: - -env = Pendulum(N) -env.reset() - -for i in range(1000): - env.step(zero(env.nu)) - env.render() - -''' - -from pinocchio.utils import * -import pinocchio as pin -import hppfcl - -# --- PENDULUM ND CONTINUOUS -------------------------------------------------------------------- -# --- PENDULUM ND CONTINUOUS -------------------------------------------------------------------- -# --- PENDULUM ND CONTINUOUS -------------------------------------------------------------------- - -def Capsule(name,joint,radius,length,placement,color=[.7,.7,0.98,1]): - '''Create a Pinocchio::FCL::Capsule to be added in the Geom-Model. ''' - hppgeom = hppfcl.Capsule(radius,length) - geom = pin.GeometryObject(name,joint,hppgeom,placement) - geom.meshColor = np.array(color) - return geom - - -def createPendulum(nbJoint,length=1.0,mass=1.0,viewer=None): - ''' - Creates the Pinocchio kinematic and visuals models for - a N-pendulum. - - @param nbJoint: number of joints of the N-pendulum. - @param length: length of each arm of the pendulum. - @param mass: mass of each arm of the pendulum. - @param viewer: gepetto-viewer CORBA client. If not None, then creates the geometries - in the viewer. - ''' - rmodel = pin.Model() - gmodel = pin.GeometryModel() - - color = [red,green,blue,transparency] = [1,1,0.78,1.0] - colorred = [1.0,0.0,0.0,1.0] - - radius = 0.1*length - - prefix = '' - jointId = 0 - jointPlacement = pin.SE3.Identity() - inertia = pin.Inertia(mass, - np.matrix([0.0,0.0,length/2]).T, - mass/5*np.diagflat([ length**2, 1e-2, 1e-2 ]) ) - - for i in range(nbJoint): - # Add a new joint - istr = str(i) - name = prefix+"joint"+istr - jointName,bodyName = [name+"_joint",name+"_body"] - jointId = rmodel.addJoint(jointId,pin.JointModelRX(),jointPlacement,jointName) - rmodel.appendBodyToJoint(jointId,inertia,pin.SE3.Identity()) - jointPlacement = pin.SE3(eye(3),np.matrix([0.0,0.0,length]).T) - - # Add a red sphere for visualizing the joint. - gmodel.addGeometryObject(Capsule(jointName,jointId,1.5*radius,0.0,pin.SE3.Identity(),colorred)) - # Add a white segment for visualizing the link. - gmodel.addGeometryObject(Capsule(bodyName ,jointId,radius,0.8*length, - pin.SE3(eye(3),np.matrix([0.,0.,length/2]).T), - color)) - - rmodel.addFrame( pin.Frame('tip',jointId,0,jointPlacement,pin.FrameType.OP_FRAME) ) - - rmodel.upperPositionLimit = np.zeros(nbJoint)+2*np.pi - rmodel.lowerPositionLimit = np.zeros(nbJoint)-2*np.pi - rmodel.velocityLimit = np.zeros(nbJoint)+5.0 - - return rmodel,gmodel - -def createPendulumWrapper(nbJoint,initViewer=True): - ''' - Returns a RobotWrapper with a N-pendulum inside. - ''' - rmodel,gmodel = createPendulum(nbJoint) - rw = pin.RobotWrapper(rmodel,visual_model=gmodel,collision_model=gmodel) - return rw - -if __name__ == "__main__": - rw = createPendulumWrapper(3,True) - rw.initViewer(loadModel=True) - rw.display(np.random.rand(3)*6-3) - diff --git a/tp7/qlearn.py b/tp7/qlearn.py deleted file mode 100644 index 15e3ca7..0000000 --- a/tp7/qlearn.py +++ /dev/null @@ -1,129 +0,0 @@ -''' -Train a Q-value following a classical Q-learning algorithm (enforcing the -satisfaction of HJB method), using a noisy greedy exploration strategy. - -The result of a training for a continuous pendulum (after 200 iterations) -are stored in qvalue.h5. - -Reference: -Mnih, Volodymyr, et al. "Human-level control through deep reinforcement learning." -Nature 518.7540 (2015): 529. -''' - -from tp7.env_pendulum import EnvPendulumHybrid; Env = lambda : EnvPendulumHybrid(1,viewer='meshcat') -from tp7.qnetwork import QNetwork -from collections import deque -import time -import signal -import matplotlib.pyplot as plt -import random -import numpy as np -import tensorflow as tf - -### --- Random seed -RANDOM_SEED = int((time.time()%10)*1000) -print("Seed = %d" % RANDOM_SEED) -np .random.seed (RANDOM_SEED) -random.seed (RANDOM_SEED) - -### --- Environment -env = Env() - -### --- Hyper paramaters -NEPISODES = 1000 # Max training steps -NSTEPS = 60 # Max episode length -QVALUE_LEARNING_RATE = 0.001 # Base learning rate for the Q-value Network -DECAY_RATE = 0.99 # Discount factor -UPDATE_RATE = 0.01 # Homotopy rate to update the networks -REPLAY_SIZE = 10000 # Size of replay buffer -BATCH_SIZE = 64 # Number of points to be fed in stochastic gradient -NH1 = NH2 = 32 # Hidden layer size - -### --- Replay memory -class ReplayItem: - def __init__(self,x,u,r,d,x2): - self.x = x - self.u = u - self.reward = r - self.done = d - self.x2 = x2 -replayDeque = deque() - -### --- Tensor flow initialization -qvalue = QNetwork(nx=env.nx,nu=env.nu,learning_rate=QVALUE_LEARNING_RATE) -qvalueTarget = QNetwork(name='target',nx=env.nx,nu=env.nu) -# Uncomment to load networks -#qvalue.load() -#qvalueTarget.load() - -def rendertrial(maxiter=NSTEPS,verbose=True): - x = env.reset() - traj = [x.copy()] - rsum = 0. - for i in range(maxiter): - u = qvalue.policy(x)[0] - x, reward = env.step(u) - env.render() - time.sleep(1e-2) - rsum += reward - traj.append(x.copy()) - if verbose: print('Lasted ',i,' timestep -- total reward:',rsum) - return np.array(traj) -signal.signal(signal.SIGTSTP, lambda x,y:rendertrial()) # Roll-out when CTRL-Z is pressed - -### History of search -h_rwd = [] - -### --- Training -for episode in range(1,NEPISODES): - x = env.reset() - rsum = 0.0 - - for step in range(NSTEPS): - u = qvalue.policy(x, # Greedy policy ... - noise=1. / (1. + episode + step)) # ... with noise - x2,r = env.step(u) - done = False # Some environment may return information when task completed - - replayDeque.append(ReplayItem(x,u,r,done,x2)) # Feed replay memory ... - if len(replayDeque)>REPLAY_SIZE: replayDeque.popleft() # ... with FIFO forgetting. - - rsum += r - x = x2 - if done: break - - # Start optimizing networks when memory size > batch size. - if len(replayDeque) > BATCH_SIZE: - batch = random.sample(replayDeque,BATCH_SIZE) # Random batch from replay memory. - x_batch = np.vstack([ b.x for b in batch ]) - u_batch = np.vstack([ b.u for b in batch ]) - r_batch = np.array([ [b.reward] for b in batch ]) - d_batch = np.array([ [b.done] for b in batch ]) - x2_batch = np.vstack([ b.x2 for b in batch ]) - - # Compute Q(x,u) from target network - v_batch = qvalueTarget.value(x2_batch) - qref_batch = r_batch + (d_batch==False)*(DECAY_RATE*v_batch) - - # Update qvalue to solve HJB constraint: q = r + q' - qvalue.trainer.train_on_batch([x_batch,u_batch],qref_batch) - - # Update target networks by homotopy. - qvalueTarget.targetAssign(qvalue,UPDATE_RATE) - - # \\\END_FOR step in range(NSTEPS) - - # Display and logging (not mandatory). - print('Ep#{:3d}: lasted {:d} steps, reward={:3.0f}' .format(episode, step,rsum)) - h_rwd.append(rsum) - if not (episode+1) % 200: rendertrial(30) - -# \\\END_FOR episode in range(NEPISODES) - -print("Average reward during trials: %.3f" % (sum(h_rwd)/NEPISODES)) -rendertrial() -plt.plot( np.cumsum(h_rwd)/range(1,NEPISODES) ) -plt.show() - -# Uncomment to save networks -#qvalue.save() diff --git a/tp7/qnetwork.py b/tp7/qnetwork.py deleted file mode 100644 index 9c87cca..0000000 --- a/tp7/qnetwork.py +++ /dev/null @@ -1,160 +0,0 @@ -''' -Deep Q learning, i.e. learning the Q function Q(x,u) so that Pi(x) = u = argmax Q(x,u) -is the optimal policy. The control u is discretized as 0..NU-1 - -This program instantiates an environment env and a Q network qvalue. -The main signals are qvalue.x (state input), qvalue.qvalues (value for any u in 0..NU-1), -qvalue.policy (i.e. argmax(qvalue.qvalues)) and qvalue.qvalue (i.e. max(qvalue.qvalue)). - -Reference: -Mnih, Volodymyr, et al. "Human-level control through deep reinforcement learning." -Nature 518.7540 (2015): 529. -''' - -import tensorflow as tf -import numpy as np -from tensorflow.keras import layers -import tensorflow.keras as keras -import tensorflow.keras.backend as K - -def batch_gather(reference, indices): - """ - From https://github.com/keras-team/keras/pull/6377 (not merged). - - Batchwise gathering of row indices. - The numpy equivalent is `reference[np.arange(batch_size), indices]`, where - `batch_size` is the first dimension of the reference tensor. - # Arguments - reference: A tensor with ndim >= 2 of shape. - (batch_size, dim1, dim2, ..., dimN) - indices: A 1d integer tensor of shape (batch_size) satisfying - 0 <= i < dim2 for each element i. - # Returns - The selected tensor with shape (batch_size, dim2, ..., dimN). - # Examples - 1. If reference is `[[3, 5, 7], [11, 13, 17]]` and indices is `[2, 1]` - then the result is `[7, 13]`. - """ - batch_size = keras.backend.shape(reference)[0] - indices = tf.concat([tf.reshape(tf.range(batch_size),[batch_size,1]), - indices],1) - return tf.gather_nd(reference,indices=indices) - - -class QNetwork: - ''' - Build a keras model computing: - - qvalues(x) = [ Q(x,u_1) ... Q(x,u_NU) ] - - value(x) = max_u qvalues(x) - - qvalue(x,u) = Q(x,u) - ''' - def __init__(self,nx,nu,name='',nhiden=32,learning_rate=None): - ''' - The network has the following structure: - - x => [ DENSE1 ] => [ DENSE2 ] => [ QVALUES ] ==========MAX=> VALUE(x) - \=>[ ] - u ============================================>[ NGATHER ] => QVALUE(x,u) - - where: - - qvalues(x) = [ qvalue(x,u=0) ... qvalue(x,u=NU-1) ] - - value(x) = max_u qvalues(x) - - value(x,u) = qvalues(x)[u] - - The model self.trainer corresponds to a mean-square loss of qvalue(x,u) - wrt to a reference q_ref. - The main model self.model has no optimizer and simply computes qvalues,value,qvalue - as a function of x and u (useful for debug only). - Additional helper functions are set to compute the value function and the policy. - ''' - - self.nx=nx;self.nu=nu - input_x = keras.Input(shape=(nx,), name=name+'state') - input_u = keras.Input(shape=(1,), name=name+'control',dtype="int32") - dens1 = keras.layers.Dense(nhiden, activation='relu', name=name+'dense_1', - bias_initializer='random_uniform')(input_x) - dens2 = keras.layers.Dense(nhiden, activation='relu', name=name+'dense_2', - bias_initializer='random_uniform')(dens1) - qvalues = keras.layers.Dense(nu, activation='linear', name=name+'qvalues', - bias_initializer='random_uniform')(dens2) - value = keras.backend.max(qvalues,keepdims=True,axis=1) - value = keras.layers.Lambda(lambda x:x,name=name+'value')(value) - qvalue = batch_gather(qvalues,input_u) - qvalue = keras.layers.Lambda(lambda x:x,name=name+'qvalue')(qvalue) - policy = keras.backend.argmax(qvalues,axis=1) - policy = keras.layers.Lambda(lambda x:x,name=name+'policy')(policy) - - self.trainer = keras.Model(inputs=[input_x,input_u],outputs=qvalue) - self.saver = keras.Model(inputs=input_x,outputs=qvalues) - self.trainer.compile(optimizer='adam',loss='mse') - if learning_rate is not None: - self.trainer.optimizer.lr = learning_rate - - self.model = keras.Model(inputs=[input_x,input_u], - outputs=[qvalues,value,qvalue,policy]) - self.saver = keras.Model(inputs=input_x,outputs=qvalues) # For saving the weights - - self._policy = keras.backend.function(input_x,policy) - self._qvalues = keras.backend.function(input_x,qvalues) - self._value = keras.backend.function(input_x,value) - - # FOR DEBUG ONLY - self._qvalues = keras.backend.function(input_x,qvalues) - self._h1 = keras.backend.function(input_x,dens1) - self._h2 = keras.backend.function(input_x,dens2) - - def targetAssign(self,ref,rate): - ''' - Change model to approach modelRef, with homotopy parameter - (rate=0: do not change, rate=1: exacttly set it to the ref). - ''' - assert(rate<=1 and rate>=0) - for v,vref in zip(self.trainer.trainable_variables,ref.trainer.trainable_variables): - v.assign((1-rate)*v+rate*vref) - - def policy(self,x,noise=None): - ''' - Evaluate the policy u = pi(x) = argmax_u Q(x,u). - If noise is not None, then evaluate a noisy-greedy policy - u = pi(x|noise) = argmax_u(Q(x,u)+uniform(noise)). - ''' - if len(x.shape)==1: x=np.reshape(x,[1,len(x)]) - if noise is None: return self._policy(x) - q = self._qvalues(x) - if noise is not None: q += (np.random.rand(self.nu)*2-1)*noise - return np.argmax(q,axis=1) - - def value(self,x): - ''' - Evaluate the value function at x: V(x). - ''' - if len(x.shape)==1: x=np.reshape(x,[1,len(x)]) - return self._value(x) - - def save(self,filename='qvalue.h5'): - self.saver.save_weights(filename) - def load(self,filename='qvalue.h5'): - self.saver.load_weights(filename) - - -if __name__ == "__main__": - NX = 3; NU = 10 - qnet = QNetwork(NX,NU) - - A = np.random.random([ NX,1])*2-1 - def data(x): - y = (5*x+3)**2 - return y@A - - NSAMPLES = 1000 - xs = np.random.random([ NSAMPLES,NX ]) - us = np.random.randint( NU,size=NSAMPLES,dtype=np.int32 ) - ys = np.vstack([ data(x) for x in xs ]) - - qnet.trainer.fit([xs,us],ys,epochs=50,batch_size=64) - - import matplotlib.pylab as plt - plt.ion() - plt.plot(xs,ys, '+') - ypred=qnet.trainer.predict([xs,us]) - plt.plot(xs,ypred, '+r') diff --git a/tp7/qtable.py b/tp7/qtable.py deleted file mode 100644 index 8de8afb..0000000 --- a/tp7/qtable.py +++ /dev/null @@ -1,69 +0,0 @@ -''' -Example of Q-table learning with a simple discretized 1-pendulum environment. --- concerge in 1k episods with pendulum(1) --- Converge in 10k episods with cozmo model -''' - -import matplotlib.pyplot as plt -import signal -import time -import numpy as np - -### --- Random seed -RANDOM_SEED = 1188 #int((time.time()%10)*1000) -print("Seed = %d" % RANDOM_SEED) -np.random.seed(RANDOM_SEED) - -### --- Environment -from tp6.env_pendulum import EnvPendulumDiscrete; Env = lambda : EnvPendulumDiscrete(1,viewer='meshcat') -env = Env() - -### --- Hyper paramaters -NEPISODES = 400 # Number of training episodes -NSTEPS = 50 # Max episode length -LEARNING_RATE = 0.85 # -DECAY_RATE = 0.99 # Discount factor - -Q = np.zeros([env.nx,env.nu]) # Q-table initialized to 0 - -def policy(x): - return np.argmax(Q[x,:]) - -def rendertrial(s0=None,maxiter=100): - '''Roll-out from random state using greedy policy.''' - s = env.reset(s0) - traj = [s] - for i in range(maxiter): - a = np.argmax(Q[s,:]) - s,r = env.step(a) - env.render() - traj.append(s) - return traj - -signal.signal(signal.SIGTSTP, lambda x,y:rendertrial()) # Roll-out when CTRL-Z is pressed - -h_rwd = [] # Learning history (for plot). -for episode in range(1,NEPISODES): - x = env.reset() - rsum = 0.0 - for steps in range(NSTEPS): - u = np.argmax(Q[x,:] + np.random.randn(1,env.nu)/episode) # Greedy action with noise - x2,reward = env.step(u) - - # Compute reference Q-value at state x respecting HJB - Qref = reward + DECAY_RATE*np.max(Q[x2,:]) - - # Update Q-Table to better fit HJB - Q[x,u] += LEARNING_RATE*(Qref-Q[x,u]) - x = x2 - rsum += reward - - h_rwd.append(rsum) - if not episode%20: - print('Episode #%d done with average cost %.2f' % (episode,sum(h_rwd[-20:])/20)) - -print("Total rate of success: %.3f" % (sum(h_rwd)/NEPISODES)) -rendertrial() -plt.plot( np.cumsum(h_rwd)/range(1,NEPISODES) ) -plt.show() - diff --git a/utils/meshcat_viewer_wrapper/visualizer.py b/utils/meshcat_viewer_wrapper/visualizer.py index 0aae50c..a858dc3 100644 --- a/utils/meshcat_viewer_wrapper/visualizer.py +++ b/utils/meshcat_viewer_wrapper/visualizer.py @@ -5,8 +5,20 @@ import pinocchio as pin from pinocchio.visualize import MeshcatVisualizer as PMV +# visualize_frame method taken from https://github.com/sea-bass/pyroboplan/tree/main + from . import colors +FRAME_AXIS_POSITIONS = ( + np.array([[0, 0, 0], [1, 0, 0], [0, 0, 0], [0, 1, 0], [0, 0, 0], [0, 0, 1]]) + .astype(np.float32) + .T +) +FRAME_AXIS_COLORS = ( + np.array([[1, 0, 0], [1, 0.6, 0], [0, 1, 0], [0.6, 1, 0], [0, 0, 1], [0, 0.6, 1]]) + .astype(np.float32) + .T +) def materialFromColor(color): if isinstance(color, meshcat.geometry.MeshPhongMaterial): @@ -60,6 +72,67 @@ def addBox(self, name, dims, color): material = materialFromColor(color) self.viewer[name].set_object(meshcat.geometry.Box(dims), material) + def visualize_frame(self, name, tform, line_length=0.2, line_width=3): + """ + Visualizes a coordinate frame as an axis triad at a specified pose. + + Parameters + ---------- + name : str + The name of the MeshCat component to add. + tform : `pinocchio.SE3` + The transform at which to display the frame. + line_length : float, optional + The length of the axes in the triad. + line_width : float, optional + The width of the axes in the triad. + """ + color = FRAME_AXIS_COLORS + + self.viewer[name].set_object( + meshcat.geometry.LineSegments( + meshcat.geometry.PointsGeometry( + position=line_length * FRAME_AXIS_POSITIONS, + color=color, + ), + meshcat.geometry.LineBasicMaterial( + linewidth=line_width, + vertexColors=True, + ), + ) + ) + self.viewer[name].set_transform(tform.homogeneous) + + def visualize_axis(self, name, axis_point, axis_direction, distance_along_axis, line_width=3, color=[0, 0, 1]): + """ + Visualizes a screw axis as a line in the 3D viewer. + + Parameters: + name : str + The name of the MeshCat component to add. + axis_point : np.array + A point on the axis (3x1 vector). + axis_direction : np.array + The direction vector of the axis (3x1 vector). + length : float, optional + The length of the axis line to be visualized. + line_width : int, optional + The width of the axis line. + color : list, optional + The color of the axis as an RGB list. + """ + start_point = axis_point + end_point = axis_point + distance_along_axis * axis_direction + points = np.vstack([start_point, end_point]).T + colors = np.tile(np.array(color, dtype=np.float32).reshape(3, 1), (1, 2)) + + self.viewer[name].set_object( + meshcat.geometry.LineSegments( + meshcat.geometry.PointsGeometry(position=points, color=colors), + meshcat.geometry.LineBasicMaterial(linewidth=line_width, vertexColors=True) + ) + ) + def applyConfiguration(self, name, placement): if isinstance(placement, list) or isinstance(placement, tuple): placement = np.array(placement) @@ -83,4 +156,4 @@ def delete(self, name): self.viewer[name].delete() def __getitem__(self, name): - return self.viewer[name] + return self.viewer[name] \ No newline at end of file diff --git a/videos/simple_screw_transform.mp4 b/videos/simple_screw_transform.mp4 new file mode 100644 index 0000000..8ce12be Binary files /dev/null and b/videos/simple_screw_transform.mp4 differ