From 851cec3b7a3ba99dbbebd1443d297cc031770dea Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sat, 27 Apr 2019 14:39:49 +0800 Subject: [PATCH 01/22] minor improvement to tutorial --- .../source/tutorials/tut1_basic_example.ipynb | 87 ++++++++----------- 1 file changed, 38 insertions(+), 49 deletions(-) diff --git a/docs/source/tutorials/tut1_basic_example.ipynb b/docs/source/tutorials/tut1_basic_example.ipynb index 29343fe7..15ad25b0 100644 --- a/docs/source/tutorials/tut1_basic_example.ipynb +++ b/docs/source/tutorials/tut1_basic_example.ipynb @@ -4,20 +4,26 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "# A basic example\n", + "# A simple example\n", "\n", - "The most basic usecase of TOPP-RA is compute the time-optimal\n", + "TOPP-RA solves the time-optimal path-parametrization (TOPP) problem: given a geometric\n", + "path and constraints, compute the fastest way to traverse the geometric path without\n", + "violating these given constraints.\n", + "\n", + "In this tutorial, we consider the most basic usecase of TOPP-RA: compute the time-optimal\n", "time-parameterization subject to joint velocity and acceleration\n", "constraints. \n", "\n", - "## Setup the problem\n", + "## Problem setup\n", "\n", - "First, we need to load `toppra`." + "As an example, we randomly choose 5 waypoints and fit a cubic spline through\n", + "all five to obtain a geometric path. Similarly, we randomly sample a joint\n", + "acceleration and a joint velocity constraints.\n" ] }, { "cell_type": "code", - "execution_count": 1, + "execution_count": 2, "metadata": {}, "outputs": [], "source": [ @@ -31,35 +37,18 @@ "import time" ] }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We now randomly choose 5 waypoints and fit a cubic spline through\n", - "all five to obtain a geometric path." - ] - }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 4, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "\n" - ] - } - ], + "outputs": [], "source": [ "# Random waypoints used to obtain a random geometric path. Here,\n", "# we use spline interpolation.\n", "dof = 6\n", "np.random.seed(0)\n", "way_pts = np.random.randn(5, dof)\n", - "path = ta.SplineInterpolator(np.linspace(0, 1, 5), way_pts)\n", - "print(path)" + "path = ta.SplineInterpolator(np.linspace(0, 1, 5), way_pts)" ] }, { @@ -68,13 +57,16 @@ "source": [ "Similarly, we choose a random set of velocity and acceleration constraints below.\n", "\n", - "A constraint can have different `discretization_scheme`: `Interpolation` and `Collocation`.\n", + "A constraint can have different `discretization_scheme`: \n", + "- `Interpolation` and \n", + "- `Collocation`.\n", + "\n", "Generally, `Interpolation` leads to higher quality trajectory with a longer (slightly) computation time." ] }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 5, "metadata": {}, "outputs": [ { @@ -117,26 +109,30 @@ "\n", "## Solve TOPP\n", "\n", - "We now solve for the time-optimal path parametrization." + "We now solve for the time-optimal path parametrization. An important parameter\n", + "to choose is the number of grid points. A larger number leads to trajectories\n", + "with higher quality, with the drawback of higher computational cost. In the\n", + "below example, we choose 200 gridpoints." ] }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 11, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "Parameterization time: 0.00719380378723 secs\n" + "Parameterization time: 0.0300650596619 secs\n" ] } ], "source": [ "t0 = time.time()\n", "# Setup a parametrization instance, then retime\n", - "instance = algo.TOPPRA([pc_vel, pc_acc], path, solver_wrapper='seidel')\n", + "gridpoints = np.linspace(0, path.duration, 200)\n", + "instance = algo.TOPPRA([pc_vel, pc_acc], path, gridpoints=gridpoints, solver_wrapper='seidel')\n", "jnt_traj, aux_traj, int_data = instance.compute_trajectory(0, 0, return_data=True)\n", "print(\"Parameterization time: {:} secs\".format(time.time() - t0))" ] @@ -155,23 +151,23 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 13, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "seidel : comp. time 0.0073 secs: traj dur. 18.343413 sec\n", - "hotqpoases : comp. time 0.0259 secs: traj dur. 18.343413 sec\n", - "cvxpy : comp. time 1.5985 secs: traj dur. 18.343420 sec\n" + "seidel : comp. time 0.0173 secs: traj dur. 17.912383 sec\n", + "hotqpoases : comp. time 0.0689 secs: traj dur. 17.912383 sec\n", + "cvxpy : comp. time 2.9252 secs: traj dur. 17.912386 sec\n" ] } ], "source": [ "for solver_wrapper in ['seidel', 'hotqpoases', 'cvxpy']:\n", " t0 = time.time()\n", - " instance = algo.TOPPRA([pc_vel, pc_acc], path, solver_wrapper=solver_wrapper)\n", + " instance = algo.TOPPRA([pc_vel, pc_acc], path, gridpoints=gridpoints, solver_wrapper=solver_wrapper)\n", " traj, _ = instance.compute_trajectory(0, 0)\n", " print(\"{:20}: comp. time {:.4f} secs: traj dur. {:4f} sec\".format(solver_wrapper, time.time() - t0, traj.get_duration()))" ] @@ -188,14 +184,14 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 14, "metadata": {}, "outputs": [ { "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAtwAAAEKCAYAAAAhJoLGAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nR/8LBQItyUzNgrAAAAAASUVORK5CYII=\n", + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAtwAAAEKCAYAAAAhJoLGAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\n", "text/plain": [ - "" + "" ] }, "metadata": {}, @@ -231,14 +227,14 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 15, "metadata": {}, "outputs": [ { "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAZ4AAAEKCAYAAAAiizNaAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nPPYAAAAASUVORK5CYII=\n", + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAZcAAAEKCAYAAADenhiQAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\njDEm6P4fdXsHi4DU57YAAAAASUVORK5CYII=\n", "text/plain": [ - "" + "" ] }, "metadata": {}, @@ -254,13 +250,6 @@ "plt.ylabel(\"Squared path velocity $x:=\\dot s^2$\")\n", "plt.show()" ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] } ], "metadata": { From 063a4796f60bc7b52456d2a53f186aa27443947a Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sat, 27 Apr 2019 14:59:13 +0800 Subject: [PATCH 02/22] create skeleton for two new tutorials --- docs/source/tutorials.rst | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/source/tutorials.rst b/docs/source/tutorials.rst index 65d38c44..e94f2e0b 100644 --- a/docs/source/tutorials.rst +++ b/docs/source/tutorials.rst @@ -8,7 +8,8 @@ Some tutorials to get you used to TOPP-RA :maxdepth: 1 tutorials/tut1_basic_example.ipynb - tutorials/0a_trapezoidal_scalar + tutorials/tut2_using_toppra_output.ipynb + tutorials/tut3_non_zero_velocities.ipynb tutorials/1_geometric_path tutorials/2_can_linear_constraints From aff48d168f599261ba0626f9c01bf8f5e3a35909 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sat, 27 Apr 2019 15:58:17 +0800 Subject: [PATCH 03/22] minor change to SplineInterpolator initial default bc --- .../tutorials/tut2_using_toppra_output.ipynb | 144 ++++++++++++++++ .../tutorials/tut3_non_zero_velocities.ipynb | 154 ++++++++++++++++++ .../interpolators/test_spline_interpolator.py | 40 ++--- toppra/interpolator.py | 18 +- 4 files changed, 328 insertions(+), 28 deletions(-) create mode 100644 docs/source/tutorials/tut2_using_toppra_output.ipynb create mode 100644 docs/source/tutorials/tut3_non_zero_velocities.ipynb diff --git a/docs/source/tutorials/tut2_using_toppra_output.ipynb b/docs/source/tutorials/tut2_using_toppra_output.ipynb new file mode 100644 index 00000000..8bd2c6b4 --- /dev/null +++ b/docs/source/tutorials/tut2_using_toppra_output.ipynb @@ -0,0 +1,144 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Advanced usage of toppra output\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [], + "source": [ + "# toppra\n", + "import toppra as ta\n", + "import toppra.constraint as constraint\n", + "import toppra.algorithm as algo\n", + "import numpy as np\n", + "# misc: for plotting and measuring time\n", + "import matplotlib.pyplot as plt\n", + "import seaborn as sns\n", + "import time\n", + "\n", + "# Random waypoints used to obtain a random geometric path. Here,\n", + "# we use spline interpolation.\n", + "dof = 6\n", + "np.random.seed(0)\n", + "way_pts = np.random.randn(3, dof)\n", + "path = ta.SplineInterpolator(np.linspace(0, 1, 3), way_pts)\n", + "\n", + "# Create velocity bounds, then velocity constraint object\n", + "vlim_ = np.random.rand(dof) * 20\n", + "vlim = np.vstack((-vlim_, vlim_)).T\n", + "# Create acceleration bounds, then acceleration constraint object\n", + "alim_ = np.random.rand(dof) * 100\n", + "alim = np.vstack((-alim_, alim_)).T\n", + "pc_vel = constraint.JointVelocityConstraint(vlim)\n", + "pc_acc = constraint.JointAccelerationConstraint(\n", + " alim, discretization_scheme=constraint.DiscretizationType.Interpolation)\n", + "\n", + "t0 = time.time()\n", + "# Setup a parametrization instance, then retime\n", + "gridpoints = np.linspace(0, path.duration, 200)\n", + "instance = algo.TOPPRA([pc_vel, pc_acc], path, gridpoints=gridpoints, solver_wrapper='seidel')\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 17, + "metadata": {}, + "outputs": [], + "source": [ + "sdd_grid, sd_grid, _, K_grid = instance.compute_parameterization(0, 0, return_data=True)" + ] + }, + { + "cell_type": "code", + "execution_count": 18, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAX4AAAEBCAYAAAB/rs7oAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "plt.plot(sd_grid, label='path velocity')\n", + "plt.plot(np.sqrt(K_grid[:, 0]), label='lower bound')\n", + "plt.plot(np.sqrt(K_grid[:, 1]), label='upper bound')\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 2", + "language": "python", + "name": "python2" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.12" + }, + "latex_envs": { + "LaTeX_envs_menu_present": true, + "autoclose": false, + "autocomplete": true, + "bibliofile": "biblio.bib", + "cite_by": "apalike", + "current_citInitial": 1, + "eqLabelWithNumbers": true, + "eqNumInitial": 1, + "hotkeys": { + "equation": "Ctrl-E", + "itemize": "Ctrl-I" + }, + "labels_anchors": false, + "latex_user_defs": false, + "report_style_numbering": false, + "user_envs_cfg": false + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/docs/source/tutorials/tut3_non_zero_velocities.ipynb b/docs/source/tutorials/tut3_non_zero_velocities.ipynb new file mode 100644 index 00000000..e59a9bf0 --- /dev/null +++ b/docs/source/tutorials/tut3_non_zero_velocities.ipynb @@ -0,0 +1,154 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Non-zero starting and ending velocities\n", + "\n", + "TOPP-RA can also parametrize geometric paths that respect initial and final velocity:\n", + "\\[\n", + " \\dot{\\mathbf q}(0) = \\mathbf p'(0) * 0.2 \\\\\n", + " \\dot{\\mathbf q}(T_{final}) = \\mathbf p'(1) * 0.2\n", + "\\]" + ] + }, + { + "cell_type": "code", + "execution_count": 49, + "metadata": {}, + "outputs": [], + "source": [ + "# toppra\n", + "import toppra as ta\n", + "import toppra.constraint as constraint\n", + "import toppra.algorithm as algo\n", + "import numpy as np\n", + "# misc: for plotting and measuring time\n", + "import matplotlib.pyplot as plt\n", + "import time\n", + "\n", + "ta.setup_logging()\n", + "\n", + "# Random waypoints used to obtain a random geometric path. Here,\n", + "# we use spline interpolation.\n", + "dof = 6\n", + "np.random.seed(0)\n", + "way_pts = np.random.randn(3, dof)\n", + "path = ta.SplineInterpolator(np.linspace(0, 1, 3), way_pts, bc_type='not-a-knot')\n", + "\n", + "# Create velocity bounds, then velocity constraint object\n", + "vlim_ = np.random.rand(dof) * 20\n", + "vlim = np.vstack((-vlim_, vlim_)).T\n", + "# Create acceleration bounds, then acceleration constraint object\n", + "alim_ = np.random.rand(dof) * 100\n", + "alim = np.vstack((-alim_, alim_)).T\n", + "pc_vel = constraint.JointVelocityConstraint(vlim)\n", + "pc_acc = constraint.JointAccelerationConstraint(\n", + " alim, discretization_scheme=constraint.DiscretizationType.Interpolation)" + ] + }, + { + "cell_type": "code", + "execution_count": 50, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Parameterization time: 0.0123839378357 secs\n" + ] + } + ], + "source": [ + "t0 = time.time()\n", + "# Setup a parametrization instance, then retime\n", + "gridpoints = np.linspace(0, path.duration, 200)\n", + "instance = algo.TOPPRA([pc_vel, pc_acc], path, gridpoints=gridpoints, solver_wrapper='seidel')\n", + "jnt_traj, aux_traj, int_data = instance.compute_trajectory(0.2, 0.2, return_data=True)\n", + "print(\"Parameterization time: {:} secs\".format(time.time() - t0))\n", + "if jnt_traj is None:\n", + " print(\"Unable to parametrize this path\")" + ] + }, + { + "cell_type": "code", + "execution_count": 64, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAA7IAAAEKCAYAAAAvhmnFAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nhBBCCCG8iiSyQgghhBBCCCG8yv8DchgvtxdmeEoAAAAASUVORK5CYII=\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "ts_sample = np.linspace(0, jnt_traj.get_duration(), 100)\n", + "qdds_sample = jnt_traj.evaldd(ts_sample)\n", + "qds_sample = jnt_traj.evald(ts_sample)\n", + "\n", + "initial_velocities = path.evald(0) * 0.2\n", + "final_velocities = path.evald(path.duration) * 0.2\n", + "fig, axs = plt.subplots(1, 2, sharex=True, figsize=[16, 4])\n", + "for i in range(6):\n", + " color = \"C%d\" % i\n", + " axs[0].plot(ts_sample, qdds_sample[:, i], label=\"J{:d}\".format(i + 1), c=color)\n", + " axs[1].plot(ts_sample, qds_sample[:, i], label=\"J{:d}\".format(i + 1), c=color)\n", + " axs[1].scatter([0, jnt_traj.duration],\n", + " [initial_velocities[i], final_velocities[i]], c=color)\n", + "axs[0].set_xlabel(\"Time (s)\")\n", + "axs[0].set_ylabel(\"Joint acceleration (rad/s^2)\")\n", + "axs[0].legend()\n", + "axs[1].legend()\n", + "axs[1].set_xlabel(\"Time (s)\")\n", + "axs[1].set_ylabel(\"Joint velocity (rad/s)\")\n", + "plt.show()\n" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 2", + "language": "python", + "name": "python2" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.12" + }, + "latex_envs": { + "LaTeX_envs_menu_present": true, + "autoclose": false, + "autocomplete": true, + "bibliofile": "biblio.bib", + "cite_by": "apalike", + "current_citInitial": 1, + "eqLabelWithNumbers": true, + "eqNumInitial": 1, + "hotkeys": { + "equation": "Ctrl-E", + "itemize": "Ctrl-I" + }, + "labels_anchors": false, + "latex_user_defs": false, + "report_style_numbering": false, + "user_envs_cfg": false + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/tests/interpolators/test_spline_interpolator.py b/tests/interpolators/test_spline_interpolator.py index d9bba82d..88845afe 100644 --- a/tests/interpolators/test_spline_interpolator.py +++ b/tests/interpolators/test_spline_interpolator.py @@ -5,26 +5,6 @@ from ..testing_utils import IMPORT_OPENRAVEPY, IMPORT_OPENRAVEPY_MSG -@pytest.fixture(scope='module') -def robot_fixture(rave_env): - import openravepy as orpy - rave_env.Reset() - rave_env.Load("data/lab1.env.xml") - robot = rave_env.GetRobots()[0] - manipulator = robot.GetManipulators()[0] - robot.SetActiveDOFs(manipulator.GetArmIndices()) - # Generate IKFast if needed - iktype = orpy.IkParameterization.Type.Transform6D - ikmodel = orpy.databases.inversekinematics.InverseKinematicsModel( - robot, iktype=iktype) - if not ikmodel.load(): - print('Generating IKFast {0}. It will take few minutes...'.format( - iktype.name)) - ikmodel.autogenerate() - print('IKFast {0} has been successfully generated'.format(iktype.name)) - yield robot - rave_env.Destroy() - @pytest.mark.parametrize("sswp, wp, ss, path_interval", [ [[0, 0.3, 0.5], [1, 2, 3], [0., 0.1, 0.2, 0.3, 0.5], [0, 0.5]], @@ -79,6 +59,26 @@ def test_2waypoints(xs, ys, yd): npt.assert_allclose(pi.evaldd(0), np.zeros_like(ys[0])) +@pytest.fixture(scope='module') +def robot_fixture(rave_env): + import openravepy as orpy + rave_env.Reset() + rave_env.Load("data/lab1.env.xml") + robot = rave_env.GetRobots()[0] + manipulator = robot.GetManipulators()[0] + robot.SetActiveDOFs(manipulator.GetArmIndices()) + # Generate IKFast if needed + iktype = orpy.IkParameterization.Type.Transform6D + ikmodel = orpy.databases.inversekinematics.InverseKinematicsModel( + robot, iktype=iktype) + if not ikmodel.load(): + print('Generating IKFast {0}. It will take few minutes...'.format( + iktype.name)) + ikmodel.autogenerate() + print('IKFast {0} has been successfully generated'.format(iktype.name)) + yield robot + rave_env.Destroy() + @pytest.mark.skipif(not IMPORT_OPENRAVEPY, reason=IMPORT_OPENRAVEPY_MSG) @pytest.mark.parametrize("ss_waypoints, waypoints", [ [[0, 0.2, 0.5, 0.9], [[0.377, -0.369, 1.042, -0.265, -0.35, -0.105, -0.74], diff --git a/toppra/interpolator.py b/toppra/interpolator.py index 867fc70b..d2ae775d 100644 --- a/toppra/interpolator.py +++ b/toppra/interpolator.py @@ -309,7 +309,14 @@ class SplineInterpolator(Interpolator): waypoints: array Shaped (N+1, dof). Waypoints. bc_type: str, optional - Boundary condition. Can be 'not-a-knot', 'clamped', 'natural' or 'periodic'. + Boundary conditions of the spline. Can be 'not-a-knot', + 'clamped', 'natural' or 'periodic'. + + - 'not-a-knot': The most default option, return to natural + looking spline. + - 'clamped': First-order derivatives of the spline at the two + end are zeroed. + See scipy.CubicSpline documentation for more details. Attributes @@ -317,15 +324,10 @@ class SplineInterpolator(Interpolator): dof : int Output dimension of the function cspl : :class:`scipy.interpolate.CubicSpline` - The path. - cspld : :class:`scipy.interpolate.CubicSpline` - The path 1st derivative. - cspldd : :class:`scipy.interpolate.CubicSpline` - The path 2nd derivative. - + The underlying cubic spline. """ - def __init__(self, ss_waypoints, waypoints, bc_type='clamped'): + def __init__(self, ss_waypoints, waypoints, bc_type='not-a-knot'): super(SplineInterpolator, self).__init__() assert ss_waypoints[0] == 0, "First index must equals zero." self.ss_waypoints = np.array(ss_waypoints) From 84bdb7516499fb7407919ead8b066ddbc9cd8f6f Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sat, 27 Apr 2019 16:28:18 +0800 Subject: [PATCH 04/22] improve docstring for Interpolator base class + update example --- .../tutorials/tut3_non_zero_velocities.ipynb | 5 +- toppra/interpolator.py | 86 ++++++------------- 2 files changed, 28 insertions(+), 63 deletions(-) diff --git a/docs/source/tutorials/tut3_non_zero_velocities.ipynb b/docs/source/tutorials/tut3_non_zero_velocities.ipynb index e59a9bf0..96d0fe7f 100644 --- a/docs/source/tutorials/tut3_non_zero_velocities.ipynb +++ b/docs/source/tutorials/tut3_non_zero_velocities.ipynb @@ -7,10 +7,11 @@ "# Non-zero starting and ending velocities\n", "\n", "TOPP-RA can also parametrize geometric paths that respect initial and final velocity:\n", - "\\[\n", + "\n", + "$$\n", " \\dot{\\mathbf q}(0) = \\mathbf p'(0) * 0.2 \\\\\n", " \\dot{\\mathbf q}(T_{final}) = \\mathbf p'(1) * 0.2\n", - "\\]" + "$$" ] }, { diff --git a/toppra/interpolator.py b/toppra/interpolator.py index d2ae775d..b5debbdf 100644 --- a/toppra/interpolator.py +++ b/toppra/interpolator.py @@ -55,19 +55,34 @@ def _find_left_index(gridpoints, s): class Interpolator(object): - """Abstract class for interpolators.""" + """Base class for Interpolators. + + Derive Interpolator should inherit this abstract class. + + """ def __init__(self): pass - def get_dof(self): - # type: () -> int - """Return the degree-of-freedom of the path. + def __call__(self, path_positions, order=0): + """Evaluate the path at given positions. + + Parameters + ---------- + path_positions: float or np.ndarray + Path positions to evaluate the interpolator. + order: int + Order of the evaluation call. + + - 0: position + - 1: first-order derivative + - 2: second-order derivative Returns ------- - out: - Degree-of-freedom of the path. + np.ndarray + Evaluated values. + """ raise NotImplementedError @@ -81,8 +96,8 @@ def dof(self): """Return the degrees-of-freedom of the path.""" raise NotImplementedError - def get_path_interval(self): - # type: () -> np.ndarray + @property + def path_interval(self): """Return the starting and ending path positions. Returns @@ -91,64 +106,13 @@ def get_path_interval(self): The starting and ending path positions. """ - return np.array([self.s_start, self.s_end]) - - def eval(self, ss_sam): - # type: (any[np.ndarray, float]) -> np.ndarray - """Evaluate joint positions at specified path positions. - - Parameters - ---------- - ss_sam : - Shape (m,) or float. The path positions to sample at. - - Returns - ------- - out : - Shape (m, dof) if input is an array: evaluated values at positions. - Shape (dof,) if input is a float. - """ raise NotImplementedError - def evald(self, ss_sam): - # type: (any[np.ndarray, float]) -> np.ndarray - """Evaluate first derivative at specified path positions. - - Parameters - ---------- - ss_sam : - Shape (m,) or float. The path positions to sample at. - - Returns - ------- - out : - Shape (m, dof) if input is an array: evaluated values at positions. - Shape (dof,) if input is a float. - """ - raise NotImplementedError - - def evaldd(self, ss_sam): - # type: (Union[np.ndarray, float]) -> np.ndarray - """Evaluate second derivative at specified path positions. - - Parameters - ---------- - ss_sam : - Shape (m,) or float. The path positions to sample at. - - Returns - ------- - out : - Shape (m, dof) if input is an array: evaluated values at positions. - Shape (dof,) if input is a float. - """ - raise NotImplementedError - - def compute_rave_trajectory(self, robot): + def to_rave_trajectory(self, robot): """Return the corresponding Openrave Trajectory.""" raise NotImplementedError - def compute_ros_trajectory(self): + def to_ros_trajectory_msg(self): """Return the corresponding ROS trajectory.""" raise NotImplementedError From 02fc02c0f2befc98b711a14bc38996f7dfa084e6 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 28 Apr 2019 19:55:53 +0800 Subject: [PATCH 05/22] minor fixes --- tests/constraint/test_second_order.py | 20 +++++------ tests/interpolators/test_poly_interpolator.py | 2 +- .../interpolators/test_spline_interpolator.py | 10 +++--- .../retime/robustness/test_robustness_main.py | 2 +- tests/retime/test_zero_motions.py | 2 ++ toppra/interpolator.py | 35 ++++++++++++++----- toppra/utils.py | 15 ++++++++ 7 files changed, 60 insertions(+), 26 deletions(-) diff --git a/tests/constraint/test_second_order.py b/tests/constraint/test_second_order.py index ffab6959..f7620712 100644 --- a/tests/constraint/test_second_order.py +++ b/tests/constraint/test_second_order.py @@ -76,18 +76,22 @@ def inv_dyn(q, qd, qdd): np.testing.assert_allclose(cnst_F(q_vec[i]), F[i]) np.testing.assert_allclose(cnst_g(q_vec[i]), g[i]) +@pytest.fixture +def friction(): + def randomized_friction(q): + """Randomize with fixed input/output.""" + np.random.seed(int(abs(np.sum(q)) * 1000)) + return 2 + np.sin(q) + np.random.rand(len(q)) + yield randomized_friction + -def test_correctness_friction(coefficients_functions): +def test_correctness_friction(coefficients_functions, friction): """ Same as the above test, but has frictional effect. """ # setup A, B, C, cnst_F, cnst_g, path = coefficients_functions def inv_dyn(q, qd, qdd): return A(q).dot(qdd) + np.dot(qd.T, np.dot(B(q), qd)) + C(q) - def friction(q): - """Randomize with fixed input/output.""" - np.random.seed(int(np.sum(q) * 1000)) - return 2 + np.sin(q) + np.random.rand(len(q)) constraint = toppra.constraint.SecondOrderConstraint(inv_dyn, cnst_F, cnst_g, 2, friction=friction) constraint.set_discretization_type(0) @@ -109,17 +113,13 @@ def friction(q): np.testing.assert_allclose(cnst_F(p_vec[i]), F[i]) -def test_joint_force(coefficients_functions): +def test_joint_force(coefficients_functions, friction): """ Same as the above test, but has frictional effect. """ # setup A, B, C, cnst_F, cnst_g, path = coefficients_functions def inv_dyn(q, qd, qdd): return A(q).dot(qdd) + np.dot(qd.T, np.dot(B(q), qd)) + C(q) - def friction(q): - """Randomize with fixed input/output.""" - np.random.seed(int(np.sum(q) * 1000)) - return 2 + np.sin(q) + np.random.rand(len(q)) taulim = np.random.randn(2, 2) constraint = toppra.constraint.SecondOrderConstraint.joint_torque_constraint( diff --git a/tests/interpolators/test_poly_interpolator.py b/tests/interpolators/test_poly_interpolator.py index a62f3459..e868b595 100644 --- a/tests/interpolators/test_poly_interpolator.py +++ b/tests/interpolators/test_poly_interpolator.py @@ -11,7 +11,7 @@ def test_scalar(): npt.assert_allclose(pi.eval([0, 0.5, 1]), [1, 2.75, 6]) npt.assert_allclose(pi.evald([0, 0.5, 1]), [2, 5, 8]) npt.assert_allclose(pi.evaldd([0, 0.5, 1]), [6, 6, 6]) - npt.assert_allclose(pi.get_path_interval(), np.r_[0, 2]) + npt.assert_allclose(pi.path_interval, np.r_[0, 2]) def test_2_dof(): diff --git a/tests/interpolators/test_spline_interpolator.py b/tests/interpolators/test_spline_interpolator.py index 88845afe..157a48a5 100644 --- a/tests/interpolators/test_spline_interpolator.py +++ b/tests/interpolators/test_spline_interpolator.py @@ -19,7 +19,7 @@ def test_scalar(sswp, wp, ss, path_interval): assert pi.evald(ss).shape == (len(ss), ) assert pi.evaldd(ss).shape == (len(ss), ) assert pi.eval(0).shape == () - npt.assert_allclose(pi.get_path_interval(), path_interval) + npt.assert_allclose(pi.path_interval, path_interval) def test_5_dof(): @@ -32,14 +32,14 @@ def test_5_dof(): assert pi.eval(ss).shape == (10, 5) assert pi.evald(ss).shape == (10, 5) assert pi.evaldd(ss).shape == (10, 5) - npt.assert_allclose(pi.get_path_interval(), np.r_[0, 1]) + npt.assert_allclose(pi.path_interval, np.r_[0, 1]) def test_1waypoints(): "The case where there is only one waypoint." pi = SplineInterpolator([0], [[1, 2, 3]]) assert pi.dof == 3 - npt.assert_allclose(pi.get_path_interval(), np.r_[0, 0]) + npt.assert_allclose(pi.path_interval, np.r_[0, 0]) npt.assert_allclose(pi.eval(0), np.r_[1, 2, 3]) npt.assert_allclose(pi.evald(0), np.r_[0, 0, 0]) @@ -54,7 +54,7 @@ def test_1waypoints(): def test_2waypoints(xs, ys, yd): "There is only two waypoints. Linear interpolation is done between them." pi = SplineInterpolator(xs, ys, bc_type='natural') - npt.assert_allclose(pi.get_path_interval(), xs) + npt.assert_allclose(pi.path_interval, xs) npt.assert_allclose(pi.evald((xs[0] + xs[1]) / 2), yd) npt.assert_allclose(pi.evaldd(0), np.zeros_like(ys[0])) @@ -96,7 +96,7 @@ def test_compute_rave_trajectory(robot_fixture, ss_waypoints, waypoints): traj = path.compute_rave_trajectory(robot_fixture) spec = traj.GetConfigurationSpecification() - xs = np.linspace(0, path.get_duration(), 10) + xs = np.linspace(0, path.duration, 10) # Interpolate with spline qs_spline = path.eval(xs) diff --git a/tests/retime/robustness/test_robustness_main.py b/tests/retime/robustness/test_robustness_main.py index 1d713db6..0ed82967 100644 --- a/tests/retime/robustness/test_robustness_main.py +++ b/tests/retime/robustness/test_robustness_main.py @@ -59,7 +59,7 @@ def test_robustness_main(request): t0 = time.time() path = toppra.SplineInterpolator( problem_data['ss_waypoints'], - problem_data['waypoints']) + problem_data['waypoints'], bc_type='clamped') vlim = np.vstack((- problem_data['vlim'], problem_data['vlim'])).T alim = np.vstack((- problem_data['alim'], problem_data['alim'])).T pc_vel = constraint.JointVelocityConstraint(vlim) diff --git a/tests/retime/test_zero_motions.py b/tests/retime/test_zero_motions.py index 4732eeec..6b8df5e4 100644 --- a/tests/retime/test_zero_motions.py +++ b/tests/retime/test_zero_motions.py @@ -9,6 +9,7 @@ toppra.setup_logging(level="INFO") +@pytest.mark.skip(reason="scaling is deprecated") @pytest.mark.parametrize("scaling", [1e-3, 1e-4]) @pytest.mark.parametrize("Ngrid", [101, 501, 1001]) def test_scalar_zero_motion(scaling, Ngrid): @@ -43,6 +44,7 @@ def test_scalar_zero_motion(scaling, Ngrid): assert jnt_traj.get_duration() < 9e-4 # less than 1ms +@pytest.mark.skip(reason="scaling is deprecated") @pytest.mark.parametrize("Ngrid", [101, 501, 1001]) def test_scalar_auto_scaling(Ngrid): """Automatic scaling should lead to better results at slower diff --git a/toppra/interpolator.py b/toppra/interpolator.py index b5debbdf..4579b447 100644 --- a/toppra/interpolator.py +++ b/toppra/interpolator.py @@ -5,6 +5,7 @@ import warnings import numpy as np from scipy.interpolate import UnivariateSpline, CubicSpline, PPoly +from .utils import deprecated logger = logging.getLogger(__name__) @@ -331,25 +332,30 @@ def get_waypoints(self): """Return the appropriate scaled waypoints.""" return self.ss_waypoints, self.waypoints + @deprecated def get_duration(self): - warnings.warn( - "get_duration is deprecated, use duration (property) instead", - PendingDeprecationWarning) return self.duration @property def duration(self): return self.ss_waypoints[-1] - self.ss_waypoints[0] + @property + def path_interval(self): + return np.array([self.ss_waypoints[0], self.ss_waypoints[-1]]) + + @deprecated + def get_path_interval(self): + return self.path_interval + @property def dof(self): if np.isscalar(self.waypoints[0]): return 1 return self.waypoints[0].shape[0] + @deprecated def get_dof(self): # type: () -> int - warnings.warn("get_dof is deprecated, use dof (property) instead", - PendingDeprecationWarning) return self.dof def eval(self, ss_sam): @@ -435,9 +441,14 @@ def __init__(self, ss_waypoints, waypoints): self.uspld = [spl.derivative() for spl in self.uspl] self.uspldd = [spl.derivative() for spl in self.uspld] + @deprecated def get_duration(self): return self.duration + @deprecated + def get_path_interval(self): + return self.path_interval + def eval(self, ss_sam): data = [] for spl in self.uspl: @@ -510,14 +521,20 @@ def dof(self): def duration(self): return self.s_end - self.s_start + @property + def path_interval(self): + return np.array([self.s_start, self.s_end]) + + @deprecated + def get_path_interval(self): + return self.path_interval + + @deprecated def get_duration(self): - warnings.warn("get_duration is deprecated, use duration", - PendingDeprecationWarning) return self.duration + @deprecated def get_dof(self): - warnings.warn("get_dof is deprecated, use dof", - PendingDeprecationWarning) return self.dof def eval(self, ss_sam): diff --git a/toppra/utils.py b/toppra/utils.py index 3e2b06c6..a0d8f0e1 100644 --- a/toppra/utils.py +++ b/toppra/utils.py @@ -4,10 +4,25 @@ """ import logging, coloredlogs import numpy as np +import functools +import warnings + LOGGER = logging.getLogger(__name__) +def deprecated(func): + """This is a decorator which can be used to mark functions + as deprecated. It will result in a warning being emitted + when the function is used.""" + @functools.wraps(func) + def new_func(*args, **kwargs): + warnings.warn("Call to deprecated function {}.".format(func.__name__), + category=DeprecationWarning) + return func(*args, **kwargs) + return new_func + + def setup_logging(level="WARN"): """ Setup basic logging facility to console. """ From 555e18ce44d783e1988886b945df2f83c89b6ad9 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 28 Apr 2019 20:36:23 +0800 Subject: [PATCH 06/22] path velocities are now correctly returned --- toppra/algorithm/algorithm.py | 9 ++------ .../reachability_algorithm.py | 5 +++-- toppra/interpolator.py | 22 ++++++++++++++++++- 3 files changed, 26 insertions(+), 10 deletions(-) diff --git a/toppra/algorithm/algorithm.py b/toppra/algorithm/algorithm.py index 6091d640..e41d1451 100644 --- a/toppra/algorithm/algorithm.py +++ b/toppra/algorithm/algorithm.py @@ -112,12 +112,6 @@ def compute_trajectory(self, sd_start=0, sd_end=0, return_profile=False, bc_type else: return None, None - if bc_type is None: - if sd_start == 0 and sd_end == 0: - bc_type = "clamped" - else: - bc_type = "not-a-knot" - # Gridpoint time instances t_grid = np.zeros(self._N + 1) skip_ent = [] @@ -136,7 +130,8 @@ def compute_trajectory(self, sd_start=0, sd_end=0, return_profile=False, bc_type gridpoints = np.delete(self.gridpoints, skip_ent) / scaling q_grid = self.path.eval(gridpoints) - traj_spline = SplineInterpolator(t_grid, q_grid, bc_type) + traj_spline = SplineInterpolator(t_grid, q_grid, ( + (1, self.path(0, 1) * sd_start), (1, self.path(self.path.duration, 1) * sd_end))) if v_grid.shape[1] == 0: v_spline = None diff --git a/toppra/algorithm/reachabilitybased/reachability_algorithm.py b/toppra/algorithm/reachabilitybased/reachability_algorithm.py index b61d7164..eb73cd57 100644 --- a/toppra/algorithm/reachabilitybased/reachability_algorithm.py +++ b/toppra/algorithm/reachabilitybased/reachability_algorithm.py @@ -264,11 +264,12 @@ def compute_parameterization(self, sd_start, sd_end, return_data=False): Shape (N+1, 2). Return the controllable set if `return_data` is True. """ - assert sd_end >= 0 and sd_start >= 0, "Path velocities must be positive" + if sd_end < 0 or sd_start < 0: + raise ValueError("Negative path velocities: path velocities must be positive: (%s, %s)" % (sd_start, sd_end)) K = self.compute_controllable_sets(sd_end, sd_end) if np.isnan(K).any(): logger.warning("An error occurred when computing controllable velocities. " - "The path is not controllable, or is badly conditioned.") + "The path is not controllable, or is badly conditioned.") if return_data: return None, None, None, K else: diff --git a/toppra/interpolator.py b/toppra/interpolator.py index 4579b447..30bd5884 100644 --- a/toppra/interpolator.py +++ b/toppra/interpolator.py @@ -273,7 +273,7 @@ class SplineInterpolator(Interpolator): Shaped (N+1,). Path positions of the waypoints. waypoints: array Shaped (N+1, dof). Waypoints. - bc_type: str, optional + bc_type: optional Boundary conditions of the spline. Can be 'not-a-knot', 'clamped', 'natural' or 'periodic'. @@ -328,6 +328,16 @@ def _1dof_cspld(s): self.cspld = self.cspl.derivative() self.cspldd = self.cspld.derivative() + def __call__(self, path_positions, order=0): + if order == 0: + return self.eval(path_positions) + elif order == 1: + return self.evald(path_positions) + elif order == 2: + return self.evaldd(path_positions) + else: + raise ValueError("Invalid order %s" % order) + def get_waypoints(self): """Return the appropriate scaled waypoints.""" return self.ss_waypoints, self.waypoints @@ -513,6 +523,16 @@ def __init__(self, coeff, s_start=0.0, s_end=1.0): self.polyd = [poly.deriv() for poly in self.poly] self.polydd = [poly.deriv() for poly in self.polyd] + def __call__(self, path_positions, order=0): + if order == 0: + return self.eval(path_positions) + elif order == 1: + return self.evald(path_positions) + elif order == 2: + return self.evaldd(path_positions) + else: + raise ValueError("Invalid order %s" % order) + @property def dof(self): return self.coeff.shape[0] From f268d9da4c720976e4f0d87494ce2700bb0a0371 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 28 Apr 2019 20:51:54 +0800 Subject: [PATCH 07/22] improve codestyle for utils.py --- .pylintrc | 3 +- toppra/interpolator.py | 29 +++++++++++++++---- toppra/utils.py | 66 +++++++++++++++++++++++------------------- 3 files changed, 62 insertions(+), 36 deletions(-) diff --git a/.pylintrc b/.pylintrc index 69dac2da..d0088b6d 100644 --- a/.pylintrc +++ b/.pylintrc @@ -343,7 +343,8 @@ good-names=i, logger, dx, dy, dz, dq, q, x, y, z, s, dt, F, g, a, b, c, - N, ds + N, ds, q, qd, qdd, qddd, + us, xs, vs, # special toppra-specific variables # Include a hint for the correct naming format with invalid-name diff --git a/toppra/interpolator.py b/toppra/interpolator.py index 30bd5884..dd85a0ab 100644 --- a/toppra/interpolator.py +++ b/toppra/interpolator.py @@ -232,15 +232,14 @@ def __init__(self, traj, robot): self.ppoly_d = self.ppoly.derivative() self.ppoly_dd = self.ppoly.derivative(2) + @deprecated def get_duration(self): - warnings.warn( - "`get_duration` method is deprecated, use `duration` property instead", - PendingDeprecationWarning) + """Return the path's duration.""" return self.duration + @deprecated def get_dof(self): # type: () -> int - warnings.warn("This method is deprecated, use the property instead", - PendingDeprecationWarning) + """Return the path's dof.""" return self.dof @property @@ -252,12 +251,15 @@ def dof(self): return self._dof def eval(self, ss_sam): + """Evalute path postition.""" return self.ppoly(ss_sam) def evald(self, ss_sam): + """Evalute path velocity.""" return self.ppoly_d(ss_sam) def evaldd(self, ss_sam): + """Evalute path acceleration.""" return self.ppoly_dd(ss_sam) @@ -344,6 +346,7 @@ def get_waypoints(self): @deprecated def get_duration(self): + """Return the path's duration.""" return self.duration @property @@ -356,6 +359,7 @@ def path_interval(self): @deprecated def get_path_interval(self): + """Return the path interval.""" return self.path_interval @property @@ -366,15 +370,19 @@ def dof(self): @deprecated def get_dof(self): # type: () -> int + """Return the path's dof.""" return self.dof def eval(self, ss_sam): + """Return the path position.""" return self.cspl(ss_sam) def evald(self, ss_sam): + """Return the path velocity.""" return self.cspld(ss_sam) def evaldd(self, ss_sam): + """Return the path acceleration.""" return self.cspldd(ss_sam) def compute_rave_trajectory(self, robot): @@ -453,25 +461,30 @@ def __init__(self, ss_waypoints, waypoints): @deprecated def get_duration(self): + """Return the path duration.""" return self.duration @deprecated def get_path_interval(self): + """Return the path interval.""" return self.path_interval def eval(self, ss_sam): + """Return the path position.""" data = [] for spl in self.uspl: data.append(spl(ss_sam)) return np.array(data).T def evald(self, ss_sam): + """Return the path velocity.""" data = [] for spl in self.uspld: data.append(spl(ss_sam)) return np.array(data).T def evaldd(self, ss_sam): + """Return the path acceleration.""" data = [] for spl in self.uspldd: data.append(spl(ss_sam)) @@ -547,29 +560,35 @@ def path_interval(self): @deprecated def get_path_interval(self): + """Return the path interval.""" return self.path_interval @deprecated def get_duration(self): + """Return the path duration.""" return self.duration @deprecated def get_dof(self): + """Return the path's dof.""" return self.dof def eval(self, ss_sam): + """Return the path position.""" res = [poly(np.array(ss_sam)) for poly in self.poly] if self.dof == 1: return np.array(res).flatten() return np.array(res).T def evald(self, ss_sam): + """Return the path velocity.""" res = [poly(np.array(ss_sam)) for poly in self.polyd] if self.dof == 1: return np.array(res).flatten() return np.array(res).T def evaldd(self, ss_sam): + """Return the path acceleration.""" res = [poly(np.array(ss_sam)) for poly in self.polydd] if self.dof == 1: return np.array(res).flatten() diff --git a/toppra/utils.py b/toppra/utils.py index a0d8f0e1..6fd40834 100644 --- a/toppra/utils.py +++ b/toppra/utils.py @@ -2,19 +2,23 @@ Some utility functions need to generate PathConstraints. Most are specific to different scenarios. """ -import logging, coloredlogs -import numpy as np +import logging import functools import warnings +import coloredlogs +import numpy as np + -LOGGER = logging.getLogger(__name__) +logger = logging.getLogger(__name__) def deprecated(func): """This is a decorator which can be used to mark functions as deprecated. It will result in a warning being emitted when the function is used.""" + + # pylint: disable=C0111 @functools.wraps(func) def new_func(*args, **kwargs): warnings.warn("Call to deprecated function {}.".format(func.__name__), @@ -24,16 +28,17 @@ def new_func(*args, **kwargs): def setup_logging(level="WARN"): - """ Setup basic logging facility to console. + """Setup basic logging facility to console. """ - coloredlogs.install(logger=logging.getLogger("toppra"), level=level, - fmt="%(levelname)5s [%(filename)s : %(lineno)d] [%(funcName)s] %(message)s", - datefmt="%H:%M:%S", - milliseconds=True) + coloredlogs.install( + logger=logging.getLogger("toppra"), level=level, + fmt="%(levelname)5s [%(filename)s : %(lineno)d] [%(funcName)s] %(message)s", + datefmt="%H:%M:%S", + milliseconds=True) def compute_jacobian_wrench(robot, link, point): - """ Compute the wrench Jacobian for `link` at `point`. + """Compute the wrench Jacobian for `link` at `point`. We look for J_wrench such that J_wrench.T * wrench = J_trans.T * F + J_rot.T * tau @@ -42,10 +47,10 @@ def compute_jacobian_wrench(robot, link, point): J_wrench is computed by stacking J_translation and J_rotation """ - J_trans = robot.ComputeJacobianTranslation(link.GetIndex(), point) - J_rot = robot.ComputeJacobianAxisAngle(link.GetIndex()) - J_wrench = np.vstack((J_trans, J_rot)) - return J_wrench + jacobian_translation = robot.ComputeJacobianTranslation(link.GetIndex(), point) + jacobian_rotation = robot.ComputeJacobianAxisAngle(link.GetIndex()) + jacobian_wrench = np.vstack((jacobian_translation, jacobian_rotation)) + return jacobian_wrench def inv_dyn(rave_robot, q, qd, qdd, forceslist=None, returncomponents=True): @@ -77,13 +82,13 @@ def inv_dyn(rave_robot, q, qd, qdd, forceslist=None, returncomponents=True): See returncomponents parameter. """ if np.isscalar(q): # Scalar case - q_ = [q] - qd_ = [qd] - qdd_ = [qdd] + _q = [q] + _qd = [qd] + _qdd = [qdd] else: - q_ = q - qd_ = qd - qdd_ = qdd + _q = q + _qd = qd + _qdd = qdd # Temporary remove kinematic Limits vlim = rave_robot.GetDOFVelocityLimits() @@ -92,17 +97,17 @@ def inv_dyn(rave_robot, q, qd, qdd, forceslist=None, returncomponents=True): rave_robot.SetDOFAccelerationLimits(100 * alim) # Do computation with rave_robot: - rave_robot.SetDOFValues(q_) - rave_robot.SetDOFVelocities(qd_) + rave_robot.SetDOFValues(_q) + rave_robot.SetDOFVelocities(_qd) res = rave_robot.ComputeInverseDynamics( - qdd_, forceslist, returncomponents=returncomponents) + _qdd, forceslist, returncomponents=returncomponents) # Restore kinematic limits rave_robot.SetDOFVelocityLimits(vlim) rave_robot.SetDOFAccelerationLimits(alim) return res -def smooth_singularities(pp, us, xs, vs=None): +def smooth_singularities(parametrization_instance, us, xs, vs=None): """Smooth jitters due to singularities. Solving TOPP for discrete problem generated from collocation @@ -119,7 +124,7 @@ def smooth_singularities(pp, us, xs, vs=None): Parameters ---------- - pp: :class:`.qpOASESPPSolver` + parametrization_instance: :class:`.qpOASESPPSolver` us: array Shape (_N, ). Controls. xs: array @@ -140,11 +145,11 @@ def smooth_singularities(pp, us, xs, vs=None): # Find the indices singular_indices = [] uds = np.diff(us, n=1) - for i in range(pp.N - 3): + for i in range(parametrization_instance.N - 3): if uds[i] < 0 and uds[i + 1] > 0 and uds[i + 2] < 0: - LOGGER.debug("Found potential singularity at {:d}".format(i)) + logger.debug("Found potential singularity at {:d}".format(i)) singular_indices.append(i) - LOGGER.debug("Found singularities at %s", singular_indices) + logger.debug("Found singularities at %s", singular_indices) # Smooth the singularities xs_smth = np.copy(xs) @@ -153,7 +158,7 @@ def smooth_singularities(pp, us, xs, vs=None): vs_smth = np.copy(vs) for index in singular_indices: idstart = max(0, index) - idend = min(pp.N, index + 4) + idend = min(parametrization_instance.N, index + 4) xs_smth[range(idstart, idend + 1)] = ( xs_smth[idstart] + (xs_smth[idend] - xs_smth[idstart]) * np.linspace(0, 1, idend + 1 - idstart)) @@ -163,8 +168,9 @@ def smooth_singularities(pp, us, xs, vs=None): for frac in np.linspace(0, 1, idend + 1 - idstart)] vs_smth[range(idstart, idend + 1)] = np.array(data) - for i in range(pp.N): - us_smth[i] = (xs_smth[i + 1] - xs_smth[i]) / 2 / (pp.ss[i + 1] - pp.ss[i]) + for i in range(parametrization_instance.N): + us_smth[i] = ((xs_smth[i + 1] - xs_smth[i]) / 2 + / (parametrization_instance.ss[i + 1] - parametrization_instance.ss[i])) if vs is not None: return us_smth, xs_smth, vs_smth From a3271cd9ae058962aed5dae36f77eadbe214689a Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 28 Apr 2019 22:04:16 +0800 Subject: [PATCH 08/22] update non-zero velocity tutorial --- .../tutorials/tut3_non_zero_velocities.ipynb | 128 +++++++++++++++--- 1 file changed, 106 insertions(+), 22 deletions(-) diff --git a/docs/source/tutorials/tut3_non_zero_velocities.ipynb b/docs/source/tutorials/tut3_non_zero_velocities.ipynb index 96d0fe7f..e914bdfb 100644 --- a/docs/source/tutorials/tut3_non_zero_velocities.ipynb +++ b/docs/source/tutorials/tut3_non_zero_velocities.ipynb @@ -6,17 +6,24 @@ "source": [ "# Non-zero starting and ending velocities\n", "\n", - "TOPP-RA can also parametrize geometric paths that respect initial and final velocity:\n", + "In some cases, you might need to retime geometic paths such the intial\n", + "and final velocities are non-zero. For instance, suppose you have\n", + "multiple paths and need to effectively *piece* them together.\n", "\n", + "This can be done in TOPP-RA by setting the `sd_start` and `sd_end` arguments.\n", + "The initial and final joint velocities are respectively:\n", + "\n", + "$$\n", + " \\dot{\\mathbf q}(0) = \\mathbf p'(0) * \\dot{s}_{start} \\\\\n", + " \\dot{\\mathbf q}(T_{final}) = \\mathbf p'(1) * \\dot{s}_{end}\n", "$$\n", - " \\dot{\\mathbf q}(0) = \\mathbf p'(0) * 0.2 \\\\\n", - " \\dot{\\mathbf q}(T_{final}) = \\mathbf p'(1) * 0.2\n", - "$$" + "\n", + "We first randomly choose a joint velocity limit and a joint acceleration limit." ] }, { "cell_type": "code", - "execution_count": 49, + "execution_count": 4, "metadata": {}, "outputs": [], "source": [ @@ -28,15 +35,9 @@ "# misc: for plotting and measuring time\n", "import matplotlib.pyplot as plt\n", "import time\n", - "\n", "ta.setup_logging()\n", "\n", - "# Random waypoints used to obtain a random geometric path. Here,\n", - "# we use spline interpolation.\n", - "dof = 6\n", - "np.random.seed(0)\n", - "way_pts = np.random.randn(3, dof)\n", - "path = ta.SplineInterpolator(np.linspace(0, 1, 3), way_pts, bc_type='not-a-knot')\n", + "dof = 2\n", "\n", "# Create velocity bounds, then velocity constraint object\n", "vlim_ = np.random.rand(dof) * 20\n", @@ -49,40 +50,123 @@ " alim, discretization_scheme=constraint.DiscretizationType.Interpolation)" ] }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Let us choose a random geometric path with three waypoints." + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "# Random waypoints used to obtain a random geometric path. Here,\n", + "# we use spline interpolation.\n", + "np.random.seed(0)\n", + "way_pts = np.random.randn(3, dof)\n", + "path = ta.SplineInterpolator(np.linspace(0, 1, 3), way_pts, bc_type='not-a-knot')" + ] + }, { "cell_type": "code", - "execution_count": 50, + "execution_count": 14, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAX8AAAEICAYAAAC3Y/QeAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nf6WUCkD/D1ohPEtbNZiXAAAAAElFTkSuQmCC\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "discretization = np.linspace(0, 1, 100)\n", + "plt.plot(discretization, path(discretization, 0), label=\"p(s): Path position\")\n", + "plt.scatter(np.linspace(0, 1, 3), way_pts[:, 0])\n", + "plt.scatter(np.linspace(0, 1, 3), way_pts[:, 1])\n", + "plt.title(\"p(s) Path position\")\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Suppose we wish to solve the path parametrization instance so that the initial velocity\n", + "and final velocity are as below." + ] + }, + { + "cell_type": "code", + "execution_count": 24, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "Parameterization time: 0.0123839378357 secs\n" + "Initial joint velocity: [-0.64895262 1.74807581]\n", + "Final joint velocity: [ 0.69035488 -2.29904985]\n" + ] + } + ], + "source": [ + "qd_start = path(0, 1) * 0.2\n", + "qd_final = path(path.duration, 1) * 0.2\n", + "print(\"Initial joint velocity: %s\\nFinal joint velocity: %s\" % (qd_start, qd_final))" + ] + }, + { + "cell_type": "code", + "execution_count": 37, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Parameterization time: 0.00920295715332 secs\n", + "Actual initial joint velocity: [-0.64895262 1.74807581]\n", + "Actual final joint velocity: [ 0.69035488 -2.29904985]\n" ] } ], "source": [ "t0 = time.time()\n", "# Setup a parametrization instance, then retime\n", - "gridpoints = np.linspace(0, path.duration, 200)\n", - "instance = algo.TOPPRA([pc_vel, pc_acc], path, gridpoints=gridpoints, solver_wrapper='seidel')\n", + "instance = algo.TOPPRA([pc_vel, pc_acc], path, solver_wrapper='seidel')\n", "jnt_traj, aux_traj, int_data = instance.compute_trajectory(0.2, 0.2, return_data=True)\n", "print(\"Parameterization time: {:} secs\".format(time.time() - t0))\n", - "if jnt_traj is None:\n", - " print(\"Unable to parametrize this path\")" + "print(\"Actual initial joint velocity: %s\\nActual final joint velocity: %s\" % (\n", + " jnt_traj(0, 1), jnt_traj(jnt_traj.duration, 1)\n", + "))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can see that the actual initial and final joint velocity equal the values we set earlier.\n", + "Below the full joint trajectory and velocity are plotted." ] }, { "cell_type": "code", - "execution_count": 64, + "execution_count": 35, "metadata": {}, "outputs": [ { "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAA7IAAAEKCAYAAAAvhmnFAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nhBBCCCG8iiSyQgghhBBCCCG8yv8DchgvtxdmeEoAAAAASUVORK5CYII=\n", + "image/png": "iVBORw0KGgoAAAANSUhEUgAAA7gAAAEKCAYAAAA4pPkMAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nSnBFREREREQkIyjBFRERERERkYzw///mZrd5g5jqAAAAAElFTkSuQmCC\n", "text/plain": [ - "" + "" ] }, "metadata": {}, @@ -97,7 +181,7 @@ "initial_velocities = path.evald(0) * 0.2\n", "final_velocities = path.evald(path.duration) * 0.2\n", "fig, axs = plt.subplots(1, 2, sharex=True, figsize=[16, 4])\n", - "for i in range(6):\n", + "for i in range(dof):\n", " color = \"C%d\" % i\n", " axs[0].plot(ts_sample, qdds_sample[:, i], label=\"J{:d}\".format(i + 1), c=color)\n", " axs[1].plot(ts_sample, qds_sample[:, i], label=\"J{:d}\".format(i + 1), c=color)\n", From e9eb9b9b20c9edfecf9372308699f50461b0a16d Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 28 Apr 2019 22:24:54 +0800 Subject: [PATCH 09/22] minor change to make cvxpy solverwrapper passes tests --- tests/solverwrapper/test_basic_can_linear.py | 16 +++++----------- 1 file changed, 5 insertions(+), 11 deletions(-) diff --git a/tests/solverwrapper/test_basic_can_linear.py b/tests/solverwrapper/test_basic_can_linear.py index 3f23be11..7b7a32c6 100644 --- a/tests/solverwrapper/test_basic_can_linear.py +++ b/tests/solverwrapper/test_basic_can_linear.py @@ -84,21 +84,15 @@ def basic_init_fixture(request): @pytest.mark.parametrize("i", [3, 10, 30]) @pytest.mark.parametrize("H", [np.array([[1.5, 0], [0, 1.0]]), np.zeros((2, 2)), None]) @pytest.mark.parametrize("g", [np.array([0.2, -1]), np.array([0.5, 1]), np.array([2.0, 1])]) -@pytest.mark.parametrize("x_ineq", [(-1, 1), (0.2, 0.2), (0.4, 0.3), (np.nan, np.nan)]) +@pytest.mark.parametrize("x_ineq", [(0.1, 1), (0.2, 0.2), (0.4, 0.3), (np.nan, np.nan)]) @pytest.mark.skipif(not FOUND_CXPY, reason="This test requires cvxpy to validate results.") def test_basic_correctness(basic_init_fixture, solver_name, i, H, g, x_ineq): """Basic test case for solver wrappers. - The input fixture `basic_init_fixture` is known to have two - constraints, one velocity and one acceleration. Hence, in this - test, I directly formulate an optimization with cvxpy and compare - the result with the result obtained from the solver wrapper. - - Parameters - ---------- - basic_init_fixture: a fixture with only two constraints, one velocity and - one acceleration constraint. - + The input fixture `basic_init_fixture` has two constraints, one + velocity and one acceleration. Hence, in this test, I directly + formulate an optimization with cvxpy and compare the result with + the result obtained from the solver wrapper. """ constraints, path, path_discretization, vlim, alim = basic_init_fixture if solver_name == "cvxpy": From 591d1e93a7bbf2958e9723f436cdd7db43595b76 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 28 Apr 2019 22:26:14 +0800 Subject: [PATCH 10/22] update test config on ci --- .circleci/config.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index 9185d92b..18df8493 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -93,7 +93,7 @@ jobs: command: | . venv3/bin/activate export PYTHONPATH=$PYTHONPATH:`openrave-config --python-dir` - pytest tests -W ignore::PendingDeprecationWarning + pytest -q tests --durations=3 - store_artifacts: path: test-reports @@ -143,7 +143,7 @@ jobs: command: | . venv/bin/activate export PYTHONPATH=$PYTHONPATH:`openrave-config --python-dir` - pytest tests -W ignore::PendingDeprecationWarning + pytest -q tests --durations=3 - store_artifacts: path: test-reports From 7473732ae2f9c64038de85b162afb2ec875e2708 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Mon, 29 Apr 2019 22:25:13 +0800 Subject: [PATCH 11/22] temporary bugfix in second-order constraint --- docs/source/tutorials/2_can_linear_constraints.rst | 4 ++-- toppra/constraint/linear_second_order.py | 9 +++++++-- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/docs/source/tutorials/2_can_linear_constraints.rst b/docs/source/tutorials/2_can_linear_constraints.rst index c5b1caa0..aeb76e47 100644 --- a/docs/source/tutorials/2_can_linear_constraints.rst +++ b/docs/source/tutorials/2_can_linear_constraints.rst @@ -86,7 +86,7 @@ object, readied to be used with TOPP-RA. See below for code example: way_pts = np.random.randn(N_samples, dof) path = ta.SplineInterpolator(np.linspace(0, 1, 5), way_pts) - c = toppra.constraint.CanonicalLinearSecondOrderConstraint(inverse_dynamic, F, g) + c = toppra.constraint.SecondOrderConstraint(inverse_dynamic, F, g) instance = algo.TOPPRA([c], path) traj = instance.compute_trajectory() @@ -173,7 +173,7 @@ the final constraint object is :code:`pc_cart_acc`. def g(q): return g_q - pc_cart_acc = constraint.CanonicalLinearSecondOrderConstraint( + pc_cart_acc = constraint.SecondOrderConstraint( inverse_dynamics, F, g, dof=7) diff --git a/toppra/constraint/linear_second_order.py b/toppra/constraint/linear_second_order.py index 09327a39..ecf6e77b 100644 --- a/toppra/constraint/linear_second_order.py +++ b/toppra/constraint/linear_second_order.py @@ -1,8 +1,12 @@ """This module implements the general Second-Order constraints.""" +import logging import numpy as np + from .linear_constraint import LinearConstraint, canlinear_colloc_to_interpolate from .constraint import DiscretizationType +logger = logging.getLogger(__name__) + class SecondOrderConstraint(LinearConstraint): """This class represents the linear generalized Second-order constraints. @@ -73,6 +77,7 @@ def __init__(self, inv_dyn, cnst_F, cnst_g, dof, friction=None, discretization_s if friction is None: self.friction = lambda s: np.zeros(self.dof) else: + logger.warn("Friction is not handled due to a bug.") self.friction = friction self._format_string = " Kind: Generalized Second-order constraint\n" self._format_string = " Dimension:\n" @@ -115,8 +120,8 @@ def compute_constraint_params(self, path, gridpoints, scaling): a_vec = np.array([self.inv_dyn(_p, v_zero, _ps) for _p, _ps in zip(p_vec, ps_vec)]) - c_vec b_vec = np.array([self.inv_dyn(_p, _ps, pss_) for _p, _ps, pss_ in zip(p_vec, ps_vec, pss_vec)]) - c_vec - for i, (_p, _ps) in enumerate(zip(p_vec, ps_vec)): - c_vec[i] = c_vec[i] + np.sign(_ps) * self.friction(_p) + # for i, (_p, _ps) in enumerate(zip(p_vec, ps_vec)): + # c_vec[i] = c_vec[i] + np.sign(_ps) * self.friction(_p) if self.discretization_type == DiscretizationType.Collocation: return a_vec, b_vec, c_vec, F_vec, g_vec, None, None From 51c5460a4f31c7cd7b1da255b47ba3236c87c5a9 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Thu, 2 May 2019 23:52:22 +0800 Subject: [PATCH 12/22] various changes, mostly cosmetic --- tests/constraint/test_create_rave_torque.py | 2 +- tests/constraint/test_joint_velocity.py | 2 +- tests/constraint/test_robust_can_linear.py | 4 +- .../retime/robustness/test_robustness_main.py | 5 +- .../retime/test_retime_wconic_constraints.py | 2 +- tests/retime/test_zero_motions.py | 4 +- .../test_basic_conic_can_linear.py | 4 +- tests/solverwrapper/test_ecos_wrapper.py | 2 +- .../reachability_algorithm.py | 6 +-- toppra/constraint/joint_torque.py | 8 ++-- toppra/constraint/linear_joint_velocity.py | 8 ++-- toppra/constraint/linear_second_order.py | 47 +++++++++++++------ .../solverwrapper/cy_seidel_solverwrapper.pyx | 2 +- toppra/solverwrapper/solverwrapper.py | 2 +- toppra/utils.py | 4 +- 15 files changed, 59 insertions(+), 43 deletions(-) diff --git a/tests/constraint/test_create_rave_torque.py b/tests/constraint/test_create_rave_torque.py index 80d3b000..6cb195e4 100644 --- a/tests/constraint/test_create_rave_torque.py +++ b/tests/constraint/test_create_rave_torque.py @@ -21,7 +21,7 @@ def test_shape(barret_robot, dof): np.random.seed(0) path = toppra.SplineInterpolator(np.linspace(0, 1, 5), np.random.rand(5, dof)) a, b, c, F, g, _, _ = constraint.compute_constraint_params( - path, np.linspace(0, path.get_duration(), 5), 1.0) + path, np.linspace(0, path.duration, 5), 1.0) assert a.shape[1] == dof assert b.shape[1] == dof diff --git a/tests/constraint/test_joint_velocity.py b/tests/constraint/test_joint_velocity.py index 3fe46ba7..1888f363 100644 --- a/tests/constraint/test_joint_velocity.py +++ b/tests/constraint/test_joint_velocity.py @@ -89,7 +89,7 @@ def test_wrong_dimension(self, velocity_pc_data): with pytest.raises(ValueError) as e_info: pc.compute_constraint_params(path_wrongdim, [0, 0.5, 1], 1.0) assert e_info.value.args[0] == "Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})".format( - pc.get_dof(), 10 + pc.dof, 10 ) diff --git a/tests/constraint/test_robust_can_linear.py b/tests/constraint/test_robust_can_linear.py index 6f26c93f..2ea47cb7 100644 --- a/tests/constraint/test_robust_can_linear.py +++ b/tests/constraint/test_robust_can_linear.py @@ -28,7 +28,7 @@ def test_basic(accel_constraint, dist_scheme): assert ro_cnst.get_dof() == 5 a, b, c, P, _, _ = ro_cnst.compute_constraint_params( - path, np.linspace(0, path.get_duration(), 10), 1.0) + path, np.linspace(0, path.duration, 10), 1.0) # assert a.shape == (10, 2 * path.get_dof()) # assert b.shape == (10, 2 * path.get_dof()) @@ -38,7 +38,7 @@ def test_basic(accel_constraint, dist_scheme): # Linear params cnst.set_discretization_type(dist_scheme) a0, b0, c0, F0, g0, _, _ = cnst.compute_constraint_params( - path, np.linspace(0, path.get_duration(), 10), 1.0) + path, np.linspace(0, path.duration, 10), 1.0) # Assert values for i in range(10): diff --git a/tests/retime/robustness/test_robustness_main.py b/tests/retime/robustness/test_robustness_main.py index 0ed82967..319e5078 100644 --- a/tests/retime/robustness/test_robustness_main.py +++ b/tests/retime/robustness/test_robustness_main.py @@ -80,7 +80,7 @@ def test_robustness_main(request): t3 = time.time() if visualize: - _t = np.linspace(0, jnt_traj.get_duration(), 100) + _t = np.linspace(0, jnt_traj.duration, 100) fig, axs = plt.subplots(2, 2) axs[0, 0].plot(data["K"][:, 0], c="C0") axs[0, 0].plot(data["K"][:, 1], c="C0") @@ -101,8 +101,7 @@ def test_robustness_main(request): parsed_problems_df.loc[row_index, "duration"] = None else: parsed_problems_df.loc[row_index, "status"] = "SUCCESS" - parsed_problems_df.loc[row_index, - "duration"] = jnt_traj.get_duration() + parsed_problems_df.loc[row_index, "duration"] = jnt_traj.duration parsed_problems_df.loc[row_index, "t_init(ms)"] = (t1 - t0) * 1e3 parsed_problems_df.loc[row_index, "t_setup(ms)"] = (t2 - t1) * 1e3 parsed_problems_df.loc[row_index, "t_solve(ms)"] = (t3 - t2) * 1e3 diff --git a/tests/retime/test_retime_wconic_constraints.py b/tests/retime/test_retime_wconic_constraints.py index 4fec303f..49cb4f2a 100644 --- a/tests/retime/test_retime_wconic_constraints.py +++ b/tests/retime/test_retime_wconic_constraints.py @@ -45,4 +45,4 @@ def test_toppra_conic(vel_accel_robustaccel, path, solver_wrapper): traj, _ = ro_instance.compute_trajectory(0, 0) assert traj is not None - assert traj.get_duration() < 20 and traj.get_duration() > 0 + assert traj.duration < 20 and traj.duration > 0 diff --git a/tests/retime/test_zero_motions.py b/tests/retime/test_zero_motions.py index 6b8df5e4..cc0dedb2 100644 --- a/tests/retime/test_zero_motions.py +++ b/tests/retime/test_zero_motions.py @@ -41,7 +41,7 @@ def test_scalar_zero_motion(scaling, Ngrid): jnt_traj, aux_traj, data = instance.compute_trajectory(0, 0, return_data=True) # Simply assert success assert jnt_traj is not None - assert jnt_traj.get_duration() < 9e-4 # less than 1ms + assert jnt_traj.duration < 9e-4 # less than 1ms @pytest.mark.skip(reason="scaling is deprecated") @@ -70,5 +70,5 @@ def test_scalar_auto_scaling(Ngrid): # Simply assert success assert jnt_traj is not None - assert jnt_traj.get_duration() < 9e-4 # less than 1 ms + assert jnt_traj.duration < 9e-4 # less than 1 ms diff --git a/tests/solverwrapper/test_basic_conic_can_linear.py b/tests/solverwrapper/test_basic_conic_can_linear.py index bb28b17a..35ac966f 100644 --- a/tests/solverwrapper/test_basic_conic_can_linear.py +++ b/tests/solverwrapper/test_basic_conic_can_linear.py @@ -20,7 +20,7 @@ def test_vel_robust_accel(vel_accel_robustaccel, path, solver_name, i, H, g, x_ineq): "Case 1: only velocity and robust acceleration constraints. Only linear objective." vel_c, _, robust_acc_c = vel_accel_robustaccel - path_dist = np.linspace(0, path.get_duration(), 10 + 1) + path_dist = np.linspace(0, path.duration, 10 + 1) if solver_name == "cvxpy": from toppra.solverwrapper.cvxpy_solverwrapper import cvxpyWrapper solver = cvxpyWrapper([vel_c, robust_acc_c], path, path_dist) @@ -91,7 +91,7 @@ def test_compare_accel_robust_accel(vel_accel_robustaccel, path, solver_name, i, robust_acc_c = toppra.constraint.RobustLinearConstraint( acc_c, [0, 0, 0], discretization_scheme=acc_c.get_discretization_type()) - path_dist = np.linspace(0, path.get_duration(), 10) + path_dist = np.linspace(0, path.duration, 10) if solver_name == "cvxpy": from toppra.solverwrapper.cvxpy_solverwrapper import cvxpyWrapper diff --git a/tests/solverwrapper/test_ecos_wrapper.py b/tests/solverwrapper/test_ecos_wrapper.py index 5f076bc3..83798db9 100644 --- a/tests/solverwrapper/test_ecos_wrapper.py +++ b/tests/solverwrapper/test_ecos_wrapper.py @@ -14,7 +14,7 @@ def test_linear_constraints_only(vel_accel_robustaccel, path, i, g, x_ineq): "Only canonical linear constraints." vel_c, acc_c, robust_acc_c = vel_accel_robustaccel - path_dist = np.linspace(0, path.get_duration(), 10 + 1) + path_dist = np.linspace(0, path.duration, 10 + 1) solver = ecosWrapper([vel_c, acc_c], path, path_dist) target_solver = qpOASESSolverWrapper([vel_c, acc_c], path, path_dist) diff --git a/toppra/algorithm/reachabilitybased/reachability_algorithm.py b/toppra/algorithm/reachabilitybased/reachability_algorithm.py index eb73cd57..4c21931d 100644 --- a/toppra/algorithm/reachabilitybased/reachability_algorithm.py +++ b/toppra/algorithm/reachabilitybased/reachability_algorithm.py @@ -57,7 +57,7 @@ def __init__(self, constraint_list, path, gridpoints=None, solver_wrapper=None, # Handle gridpoints if gridpoints is None: - gridpoints = np.linspace(0, path.get_duration(), 100) + gridpoints = np.linspace(0, path.duration, 100) logger.info("Automatically choose a gridpoint with 100 segments/stages, spaning the input path domain uniformly.") if path.get_path_interval()[0] != gridpoints[0]: logger.fatal("Manually supplied gridpoints does not start from 0.") @@ -76,8 +76,8 @@ def __init__(self, constraint_list, path, gridpoints=None, solver_wrapper=None, # path scaling (for numerical stability) if scaling < 0: # automatic scaling factor selection # sample a few gradient and compute the average derivatives - qs_sam = path.evald(np.linspace(0, 1, 5) * path.get_duration()) - qs_average = np.sum(np.abs(qs_sam)) / path.get_dof() / 5 + qs_sam = path(np.linspace(0, 1, 5) * path.duration, 1) + qs_average = np.sum(np.abs(qs_sam)) / path.dof / 5 scaling = np.sqrt(qs_average) logger.info("[auto-scaling] Average path derivative: {:}".format(qs_average)) logger.info("[auto-scaling] Selected scaling factor: {:}".format(scaling)) diff --git a/toppra/constraint/joint_torque.py b/toppra/constraint/joint_torque.py index f372838d..b1b761b0 100644 --- a/toppra/constraint/joint_torque.py +++ b/toppra/constraint/joint_torque.py @@ -66,16 +66,16 @@ def __init__(self, inv_dyn, tau_lim, fs_coef, discretization_scheme=Discretizati self.identical = True def compute_constraint_params(self, path, gridpoints, scaling): - if path.get_dof() != self.get_dof(): + if path.dof != self.get_dof(): raise ValueError("Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})".format( - self.get_dof(), path.get_dof() + self.get_dof(), path.dof )) - v_zero = np.zeros(path.get_dof()) + v_zero = np.zeros(path.dof) p = path.eval(gridpoints / scaling) ps = path.evald(gridpoints / scaling) / scaling pss = path.evaldd(gridpoints / scaling) / scaling ** 2 N = gridpoints.shape[0] - 1 - dof = path.get_dof() + dof = path.dof I_dof = np.eye(dof) F = np.zeros((dof * 2, dof)) g = np.zeros(dof * 2) diff --git a/toppra/constraint/linear_joint_velocity.py b/toppra/constraint/linear_joint_velocity.py index e349b358..e10ee20a 100644 --- a/toppra/constraint/linear_joint_velocity.py +++ b/toppra/constraint/linear_joint_velocity.py @@ -27,9 +27,9 @@ def __init__(self, vlim): self._format_string += " J{:d}: {:}".format(i + 1, self.vlim[i]) + "\n" def compute_constraint_params(self, path, gridpoints, scaling): - if path.get_dof() != self.get_dof(): + if path.dof != self.get_dof(): raise ValueError("Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})".format( - self.get_dof(), path.get_dof() + self.get_dof(), path.dof )) qs = path.evald(gridpoints / scaling) / scaling _, _, xbound_ = _create_velocity_constraint(qs, self.vlim) @@ -60,9 +60,9 @@ def __init__(self, vlim_func): self.vlim_func = vlim_func def compute_constraint_params(self, path, gridpoints, scaling): - if path.get_dof() != self.get_dof(): + if path.dof != self.get_dof(): raise ValueError("Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})".format( - self.get_dof(), path.get_dof() + self.get_dof(), path.dof )) qs = path.evald(gridpoints / scaling) / scaling vlim_grid = np.array([self.vlim_func(s) for s in gridpoints]) diff --git a/toppra/constraint/linear_second_order.py b/toppra/constraint/linear_second_order.py index ecf6e77b..1957428f 100644 --- a/toppra/constraint/linear_second_order.py +++ b/toppra/constraint/linear_second_order.py @@ -9,40 +9,57 @@ class SecondOrderConstraint(LinearConstraint): - """This class represents the linear generalized Second-order constraints. + """This class implements the linear Second-Order constraint. - A `SecondOrderConstraint` is given by the following formula: + Conventionally, a :class:`SecondOrderConstraint` is given by the + following formula: .. math:: A(\mathbf{q}) \ddot {\mathbf{q}} + \dot - {\mathbf{q}}^\\top B(\mathbf{q}) \dot {\mathbf{q}} + - C(\mathbf{q}) + sign(\dot {\mathbf{q}}) * D(\mathbf{q}) = w, + {\mathbf{q}}^\\top B(\mathbf{q}) \dot {\mathbf{q}} + C(\mathbf{q}) = w, where w is a vector that satisfies the polyhedral constraint: .. math:: F(\mathbf{q}) w \\leq g(\mathbf{q}). - The functions :math:`A, B, C, D` represent respectively the inertial, - Corriolis, gravitational and dry friction terms in a robot torque - bound constraint. + In the common example of robot torque bound, the functions + :math:`A, B, C` represent respectively the inertial, Corriolis and + gravitational terms. - To evaluate the constraint on a geometric path :math:`\mathbf{p}(s)`: + We evaluate a constraint on a geometric path :math:`\mathbf{p}(s)` + with the following equations, which are obtained by simple + substitution: .. math:: A(\mathbf{q}) \mathbf{p}'(s) \ddot s + [A(\mathbf{q}) \mathbf{p}''(s) + \mathbf{p}'(s)^\\top B(\mathbf{q}) - \mathbf{p}'(s)] \dot s^2 + C(\mathbf{q}) + sign(\mathbf{p}'(s)) * D(\mathbf{p}(s)) = w, \\\\ - a(s) \ddot s + b(s) \dot s ^2 + c(s) = w. + \mathbf{p}'(s)] \dot s^2 + C(\mathbf{q}) = w, \\\\ + \mathbf{a}(s) \ddot s + \mathbf{b}(s) \dot s ^2 + \mathbf{c}(s) = w. where :math:`\mathbf{p}', \mathbf{p}''` denote respectively the - first and second derivatives of the path. + first and second derivatives of the path. The vector functions + :math:`\mathbf a, \mathbf b, \mathbf c` are what `toppra` needs to + solve for path parametrizations. - - It is important to note that to evaluate the coefficients + It is important to note that to evaluate these coefficients :math:`a(s), b(s), c(s)`, it is not necessary to have the - functions :math:`A, B, C`. Rather, only the sum of the these 3 - functions--the inverse dynamic function--is necessary. + functions :math:`A, B, C` explicitly. Rather, it is only required + to have the sum of the these 3 functions--the inverse dynamic + function: + + .. math:: + \mathrm{inverse\_dyn}(\mathbf q, \dot{\mathbf q}, \ddot{\mathbf q}) := + A(\mathbf{q}) \ddot {\mathbf{q}} + \dot {\mathbf{q}}^\\top B(\mathbf{q}) \dot {\mathbf{q}} + C(\mathbf{q}) + + + It is interesting to note that we can actually use a more general + form of the above equations, covering a wider class of + constraints. In particular, one can replace :math:`A(\mathbf{q}), + B(\mathbf{q}), C(\mathbf{q}), F(\mathbf{q}), g(\mathbf{q})` with + :math:`A(\mathbf{q}, s), B(\mathbf{q}, s), C(\mathbf{q}, s), + F(\mathbf{q}, s), g(\mathbf{q}, s)`. This is the form that is + implemented in this class. """ diff --git a/toppra/solverwrapper/cy_seidel_solverwrapper.pyx b/toppra/solverwrapper/cy_seidel_solverwrapper.pyx index 42f3baf5..fa20be74 100644 --- a/toppra/solverwrapper/cy_seidel_solverwrapper.pyx +++ b/toppra/solverwrapper/cy_seidel_solverwrapper.pyx @@ -437,7 +437,7 @@ cdef class seidelWrapper: self.path = path path_discretization = np.array(path_discretization) self.path_discretization = path_discretization - self.scaling = path_discretization[-1] / path.get_duration() + self.scaling = path_discretization[-1] / path.duration self.N = len(path_discretization) - 1 # Number of stages. Number of point is _N + 1 self.deltas = path_discretization[1:] - path_discretization[:-1] cdef unsigned int cur_index, j, i, k diff --git a/toppra/solverwrapper/solverwrapper.py b/toppra/solverwrapper/solverwrapper.py index e6e26443..0ba87fc9 100644 --- a/toppra/solverwrapper/solverwrapper.py +++ b/toppra/solverwrapper/solverwrapper.py @@ -42,7 +42,7 @@ def __init__(self, constraint_list, path, path_discretization): self.path_discretization = np.array(path_discretization) # path scaling: intuitively, if this value is not 1, the TOPP # problem will be solved as if the input path is scaled linearly. - self.scaling = self.path_discretization[-1] / self.path.get_duration() + self.scaling = self.path_discretization[-1] / self.path.duration # End main attributes self.N = len(path_discretization) - 1 # Number of stages. Number of point is _N + 1 self.deltas = self.path_discretization[1:] - self.path_discretization[:-1] diff --git a/toppra/utils.py b/toppra/utils.py index 6fd40834..b6b9eeeb 100644 --- a/toppra/utils.py +++ b/toppra/utils.py @@ -21,8 +21,8 @@ def deprecated(func): # pylint: disable=C0111 @functools.wraps(func) def new_func(*args, **kwargs): - warnings.warn("Call to deprecated function {}.".format(func.__name__), - category=DeprecationWarning) + warnings.warn("Call to deprecated function {} in module {}.".format( + func.__name__, func.__module__), category=DeprecationWarning) return func(*args, **kwargs) return new_func From f724f5ad91a4ee4970d121914a21e72497b2de34 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sat, 4 May 2019 12:54:02 +0800 Subject: [PATCH 13/22] update Ci config to show test reports --- .circleci/config.yml | 16 +++++++--------- 1 file changed, 7 insertions(+), 9 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index 18df8493..b7e03432 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -92,12 +92,11 @@ jobs: name: test command: | . venv3/bin/activate - export PYTHONPATH=$PYTHONPATH:`openrave-config --python-dir` - pytest -q tests --durations=3 + mkdir test-reports + pytest -q tests --durations=3 --junitxml=test-reports/junit.xml - - store_artifacts: + - store_test_results: path: test-reports - destination: test-reports test-python-2: docker: @@ -143,16 +142,15 @@ jobs: command: | . venv/bin/activate export PYTHONPATH=$PYTHONPATH:`openrave-config --python-dir` - pytest -q tests --durations=3 + mkdir test-reports + pytest -q tests --durations=3 --junitxml=test-reports/junit.xml - - store_artifacts: + - store_test_results: path: test-reports - destination: test-reports - workflows: version: 2 - test: + test-and-lint: jobs: - test-python-2 - test-python-3 From 57ddf833904ea89e82a2aa2553c347c3259817fb Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 5 May 2019 05:29:54 +0800 Subject: [PATCH 14/22] bugs in second-order constraint fixed --- .pylintrc | 3 +- examples/robust_kinematics.py | 2 +- tests/constraint/test_second_order.py | 56 ++----- tests/interpolators/test_rave_trajectory.py | 2 +- tests/solverwrapper/test_basic_can_linear.py | 2 +- toppra/__init__.py | 5 + .../reachability_algorithm.py | 6 +- toppra/constraint/__init__.py | 4 +- toppra/constraint/constraint.py | 3 +- toppra/constraint/linear_constraint.py | 4 +- toppra/constraint/linear_joint_velocity.py | 39 +++-- toppra/constraint/linear_second_order.py | 156 ++++++++++-------- toppra/planning_utils.py | 2 +- 13 files changed, 146 insertions(+), 138 deletions(-) diff --git a/.pylintrc b/.pylintrc index d0088b6d..1110ca94 100644 --- a/.pylintrc +++ b/.pylintrc @@ -343,8 +343,9 @@ good-names=i, logger, dx, dy, dz, dq, q, x, y, z, s, dt, F, g, a, b, c, - N, ds, q, qd, qdd, qddd, + N, ds, q, qd, qdd, qddd, qs, qss, qsss, us, xs, vs, # special toppra-specific variables + constraint_F, F_vec # Include a hint for the correct naming format with invalid-name diff --git a/examples/robust_kinematics.py b/examples/robust_kinematics.py index 4006e3ca..60dbf862 100644 --- a/examples/robust_kinematics.py +++ b/examples/robust_kinematics.py @@ -66,7 +66,7 @@ def main(): plt.show() jnt_traj, aux_traj = instance.compute_trajectory(0, 0) - ts_sample = np.linspace(0, jnt_traj.get_duration(), 100) + ts_sample = np.linspace(0, jnt_traj.duration, 100) qs_sample = jnt_traj.evaldd(ts_sample) plt.plot(ts_sample, qs_sample) diff --git a/tests/constraint/test_second_order.py b/tests/constraint/test_second_order.py index f7620712..0ade6740 100644 --- a/tests/constraint/test_second_order.py +++ b/tests/constraint/test_second_order.py @@ -28,33 +28,30 @@ def F(q): def g(q): return np.array([100, 200]) + def inv_dyn(q, qd, qdd): + return A(q).dot(qdd) + np.dot(qd.T, np.dot(B(q), qd)) + C(q) + np.random.seed(0) path = toppra.SplineInterpolator([0, 1, 2, 4], np.random.randn(4, 2)) - return A, B, C, F, g, path + return A, B, C, F, g, path, inv_dyn def test_wrong_dimension(coefficients_functions): """If the given path has wrong dimension, raise error.""" - A, B, C, cnst_F, cnst_g, path = coefficients_functions - def inv_dyn(q, qd, qdd): - return A(q).dot(qdd) + np.dot(qd.T, np.dot(B(q), qd)) + C(q) + A, B, C, cnst_F, cnst_g, path, inv_dyn = coefficients_functions constraint = toppra.constraint.SecondOrderConstraint(inv_dyn, cnst_F, cnst_g, dof=2) path_wrongdim = toppra.SplineInterpolator(np.linspace(0, 1, 5), np.random.randn(5, 10)) with pytest.raises(ValueError) as e_info: constraint.compute_constraint_params(path_wrongdim, np.r_[0, 0.5, 1], 1.0) assert e_info.value.args[0] == "Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})".format( - constraint.dof, 10 - ) + constraint.dof, 10) def test_correctness(coefficients_functions): """ For randomly set A, B, C, F, g functions. The generated parameters must equal those given by equations. """ - A, B, C, cnst_F, cnst_g, path = coefficients_functions - - def inv_dyn(q, qd, qdd): - return A(q).dot(qdd) + np.dot(qd.T, np.dot(B(q), qd)) + C(q) + A, B, C, cnst_F, cnst_g, path, inv_dyn = coefficients_functions constraint = toppra.constraint.SecondOrderConstraint( inv_dyn, cnst_F, cnst_g, dof=2, discretization_scheme=toppra.constraint.DiscretizationType.Collocation) @@ -76,6 +73,7 @@ def inv_dyn(q, qd, qdd): np.testing.assert_allclose(cnst_F(q_vec[i]), F[i]) np.testing.assert_allclose(cnst_g(q_vec[i]), g[i]) + @pytest.fixture def friction(): def randomized_friction(q): @@ -85,45 +83,17 @@ def randomized_friction(q): yield randomized_friction -def test_correctness_friction(coefficients_functions, friction): +def test_joint_torque(coefficients_functions, friction): """ Same as the above test, but has frictional effect. """ # setup - A, B, C, cnst_F, cnst_g, path = coefficients_functions - def inv_dyn(q, qd, qdd): - return A(q).dot(qdd) + np.dot(qd.T, np.dot(B(q), qd)) + C(q) - - constraint = toppra.constraint.SecondOrderConstraint(inv_dyn, cnst_F, cnst_g, 2, friction=friction) - constraint.set_discretization_type(0) - a, b, c, F, g, _, _ = constraint.compute_constraint_params( - path, np.linspace(0, path.duration, 10), 1.0) - - # Correct params - p_vec = path.eval(np.linspace(0, path.duration, 10)) - ps_vec = path.evald(np.linspace(0, path.duration, 10)) - pss_vec = path.evaldd(np.linspace(0, path.duration, 10)) - - for i in range(10): - ai_ = A(p_vec[i]).dot(ps_vec[i]) - bi_ = A(p_vec[i]).dot(pss_vec[i]) + np.dot(ps_vec[i].T, B(p_vec[i]).dot(ps_vec[i])) - ci_ = C(p_vec[i]) + np.sign(ps_vec[i]) * friction(p_vec[i]) - np.testing.assert_allclose(ai_, a[i]) - np.testing.assert_allclose(bi_, b[i]) - np.testing.assert_allclose(ci_, c[i]) - np.testing.assert_allclose(cnst_F(p_vec[i]), F[i]) - - -def test_joint_force(coefficients_functions, friction): - """ Same as the above test, but has frictional effect. - """ - # setup - A, B, C, cnst_F, cnst_g, path = coefficients_functions + A, B, C, cnst_F, cnst_g, path, _ = coefficients_functions def inv_dyn(q, qd, qdd): return A(q).dot(qdd) + np.dot(qd.T, np.dot(B(q), qd)) + C(q) + friction = np.random.rand(2) taulim = np.random.randn(2, 2) - constraint = toppra.constraint.SecondOrderConstraint.joint_torque_constraint( - inv_dyn, taulim, friction=friction) + inv_dyn, taulim, friction) constraint.set_discretization_type(0) a, b, c, F, g, _, _ = constraint.compute_constraint_params( path, np.linspace(0, path.duration, 10), 1.0) @@ -140,7 +110,7 @@ def inv_dyn(q, qd, qdd): for i in range(10): ai_ = A(p_vec[i]).dot(ps_vec[i]) bi_ = A(p_vec[i]).dot(pss_vec[i]) + np.dot(ps_vec[i].T, B(p_vec[i]).dot(ps_vec[i])) - ci_ = C(p_vec[i]) + np.sign(ps_vec[i]) * friction(p_vec[i]) + ci_ = C(p_vec[i]) + np.sign(ps_vec[i]) * friction np.testing.assert_allclose(ai_, a[i]) np.testing.assert_allclose(bi_, b[i]) np.testing.assert_allclose(ci_, c[i]) diff --git a/tests/interpolators/test_rave_trajectory.py b/tests/interpolators/test_rave_trajectory.py index 457e9292..2391efd8 100644 --- a/tests/interpolators/test_rave_trajectory.py +++ b/tests/interpolators/test_rave_trajectory.py @@ -48,7 +48,7 @@ def test_consistency(request, env, traj_string): spec = traj.GetConfigurationSpecification() N = 100 - ss = np.linspace(0, path.get_duration(), N) + ss = np.linspace(0, path.duration, N) # Openrave samples qs_rave = [] diff --git a/tests/solverwrapper/test_basic_can_linear.py b/tests/solverwrapper/test_basic_can_linear.py index 7b7a32c6..ea91bf6e 100644 --- a/tests/solverwrapper/test_basic_can_linear.py +++ b/tests/solverwrapper/test_basic_can_linear.py @@ -15,7 +15,7 @@ toppra.setup_logging(level="INFO") -class RandomSecondOrderLinearConstraint(constraint.LinearConstraint): +class RandomSecondOrderLinearConstraint(constraint.linear_constraint.LinearConstraint): """A random Second-Order non-identical constraint. This contraint is defined solely for testing purposes. It accepts diff --git a/toppra/__init__.py b/toppra/__init__.py index b0bf70b9..c7ab63ed 100644 --- a/toppra/__init__.py +++ b/toppra/__init__.py @@ -6,6 +6,7 @@ This package produces routines for creation and handling path constraints using the algorithm `TOPP-RA`. """ + from .interpolator import RaveTrajectoryWrapper, SplineInterpolator,\ UnivariateSplineInterpolator, PolynomialPath, Interpolator from .utils import smooth_singularities, setup_logging @@ -15,3 +16,7 @@ from . import constraint from . import algorithm from . import solverwrapper + +# set nullhandler by default +import logging +logging.getLogger('toppra').addHandler(logging.NullHandler()) diff --git a/toppra/algorithm/reachabilitybased/reachability_algorithm.py b/toppra/algorithm/reachabilitybased/reachability_algorithm.py index 4c21931d..b892be2e 100644 --- a/toppra/algorithm/reachabilitybased/reachability_algorithm.py +++ b/toppra/algorithm/reachabilitybased/reachability_algorithm.py @@ -59,10 +59,10 @@ def __init__(self, constraint_list, path, gridpoints=None, solver_wrapper=None, if gridpoints is None: gridpoints = np.linspace(0, path.duration, 100) logger.info("Automatically choose a gridpoint with 100 segments/stages, spaning the input path domain uniformly.") - if path.get_path_interval()[0] != gridpoints[0]: + if path.path_interval[0] != gridpoints[0]: logger.fatal("Manually supplied gridpoints does not start from 0.") raise ValueError("Bad input gridpoints.") - if path.get_path_interval()[1] != gridpoints[-1]: + if path.path_interval[1] != gridpoints[-1]: logger.fatal("Manually supplied gridpoints have endpoint " "different from input path duration.") raise ValueError("Bad input gridpoints.") @@ -389,4 +389,4 @@ def compute_reachable_sets(self, sdmin, sdmax): logger.debug("[Compute reachable sets] L_{:d}={:}".format(i+1, L[i+1])) self.solver_wrapper.close_solver() - return L \ No newline at end of file + return L diff --git a/toppra/constraint/__init__.py b/toppra/constraint/__init__.py index 106bf6f0..1843db70 100644 --- a/toppra/constraint/__init__.py +++ b/toppra/constraint/__init__.py @@ -1,8 +1,8 @@ """This module defines different dynamic constraints.""" -from .constraint import ConstraintType, DiscretizationType, Constraint +from .constraint import ConstraintType, DiscretizationType from .joint_torque import JointTorqueConstraint from .linear_joint_acceleration import JointAccelerationConstraint from .linear_joint_velocity import JointVelocityConstraint, JointVelocityConstraintVarying from .linear_second_order import SecondOrderConstraint, canlinear_colloc_to_interpolate from .conic_constraint import RobustLinearConstraint -from .linear_constraint import LinearConstraint +# from .linear_constraint import LinearConstraint diff --git a/toppra/constraint/constraint.py b/toppra/constraint/constraint.py index 7e93eb18..94f170ae 100644 --- a/toppra/constraint/constraint.py +++ b/toppra/constraint/constraint.py @@ -26,6 +26,7 @@ class DiscretizationType(Enum): class Constraint(object): """The base constraint class.""" + def __repr__(self): string = self.__class__.__name__ + '(\n' string += ' Type: {:}'.format(self.constraint_type) + '\n' @@ -81,6 +82,6 @@ def set_discretization_type(self, discretization_type): else: raise "Discretization type: {:} not implemented!".format(discretization_type) - def compute_constraint_params(self, path, gridpoints, scaling=1): + def compute_constraint_params(self, *args, **kwargs): """Evaluate parameters of the constraint.""" raise NotImplementedError diff --git a/toppra/constraint/linear_constraint.py b/toppra/constraint/linear_constraint.py index ba6bf434..27e36df0 100644 --- a/toppra/constraint/linear_constraint.py +++ b/toppra/constraint/linear_constraint.py @@ -1,8 +1,8 @@ +"""This module defines the abstract linear constraint class.""" +import numpy as np from .constraint import Constraint from .constraint import ConstraintType, DiscretizationType -import numpy as np - class LinearConstraint(Constraint): """A core type of constraints. diff --git a/toppra/constraint/linear_joint_velocity.py b/toppra/constraint/linear_joint_velocity.py index e10ee20a..5be8d7da 100644 --- a/toppra/constraint/linear_joint_velocity.py +++ b/toppra/constraint/linear_joint_velocity.py @@ -1,15 +1,16 @@ -from .linear_constraint import LinearConstraint +"""This module implements the joint velocity constraint.""" +import numpy as np from toppra._CythonUtils import (_create_velocity_constraint, _create_velocity_constraint_varying) -import numpy as np +from .linear_constraint import LinearConstraint class JointVelocityConstraint(LinearConstraint): - """ A Joint Velocity Constraint class. + """A Joint Velocity Constraint class. Parameters ---------- - vlim: array + vlim: np.ndarray Shape (dof, 2). The lower and upper velocity bounds of the j-th joint are given by alim[j, 0] and alim[j, 1] respectively. @@ -21,21 +22,25 @@ def __init__(self, vlim): self.dof = self.vlim.shape[0] assert self.vlim.shape[1] == 2, "Wrong input shape." for i in range(self.dof): - assert self.vlim[i, 0] < self.vlim[i, 1], "Bad velocity limits: {:} (lower limit) > {:} (higher limit)".format(self.vlim[i, 0], self.vlim[i, 1]) + assert self.vlim[i, 0] < self.vlim[ + i, + 1], "Bad velocity limits: {:} (lower limit) > {:} (higher limit)".format( + self.vlim[i, 0], self.vlim[i, 1]) self._format_string = " Velocity limit: \n" for i in range(self.vlim.shape[0]): - self._format_string += " J{:d}: {:}".format(i + 1, self.vlim[i]) + "\n" + self._format_string += " J{:d}: {:}".format( + i + 1, self.vlim[i]) + "\n" - def compute_constraint_params(self, path, gridpoints, scaling): + def compute_constraint_params(self, path, gridpoints, scaling=1): if path.dof != self.get_dof(): - raise ValueError("Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})".format( - self.get_dof(), path.dof - )) + raise ValueError( + "Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})" + .format(self.get_dof(), path.dof)) qs = path.evald(gridpoints / scaling) / scaling _, _, xbound_ = _create_velocity_constraint(qs, self.vlim) xbound = np.array(xbound_) xbound[:, 0] = xbound_[:, 1] - xbound[:, 1] = - xbound_[:, 0] + xbound[:, 1] = -xbound_[:, 0] return None, None, None, None, None, None, xbound @@ -46,7 +51,7 @@ class JointVelocityConstraintVarying(LinearConstraint): Parameters ---------- - vlim_func: float -> array function + vlim_func: (float) -> np.ndarray A function that receives a scalar (float) and produce an array with shape (dof, 2). The lower and upper velocity bounds of the j-th joint are given by out[j, 0] and out[j, 1] @@ -59,15 +64,15 @@ def __init__(self, vlim_func): self._format_string = " Varying Velocity limit: \n" self.vlim_func = vlim_func - def compute_constraint_params(self, path, gridpoints, scaling): + def compute_constraint_params(self, path, gridpoints, scaling=1): if path.dof != self.get_dof(): - raise ValueError("Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})".format( - self.get_dof(), path.dof - )) + raise ValueError( + "Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})" + .format(self.get_dof(), path.dof)) qs = path.evald(gridpoints / scaling) / scaling vlim_grid = np.array([self.vlim_func(s) for s in gridpoints]) _, _, xbound_ = _create_velocity_constraint_varying(qs, vlim_grid) xbound = np.array(xbound_) xbound[:, 0] = xbound_[:, 1] - xbound[:, 1] = - xbound_[:, 0] + xbound[:, 1] = -xbound_[:, 0] return None, None, None, None, None, None, xbound diff --git a/toppra/constraint/linear_second_order.py b/toppra/constraint/linear_second_order.py index 1957428f..52d4e70a 100644 --- a/toppra/constraint/linear_second_order.py +++ b/toppra/constraint/linear_second_order.py @@ -23,13 +23,13 @@ class SecondOrderConstraint(LinearConstraint): .. math:: F(\mathbf{q}) w \\leq g(\mathbf{q}). - In the common example of robot torque bound, the functions - :math:`A, B, C` represent respectively the inertial, Corriolis and - gravitational terms. + Take the example of a robot torque bound, the functions :math:`A, + B, C` represent respectively the inertial, Corriolis and + gravitational terms of the robot's rigid body dynamics. - We evaluate a constraint on a geometric path :math:`\mathbf{p}(s)` - with the following equations, which are obtained by simple - substitution: + We can evaluate a constraint on a given geometric path + :math:`\mathbf{p}(s)` using the following equations, which are + obtained by direct substitution: .. math:: @@ -38,111 +38,137 @@ class SecondOrderConstraint(LinearConstraint): \mathbf{a}(s) \ddot s + \mathbf{b}(s) \dot s ^2 + \mathbf{c}(s) = w. where :math:`\mathbf{p}', \mathbf{p}''` denote respectively the - first and second derivatives of the path. The vector functions - :math:`\mathbf a, \mathbf b, \mathbf c` are what `toppra` needs to - solve for path parametrizations. + first and second derivatives of the path. It is important to + understand that the vector functions :math:`\mathbf a, \mathbf b, + \mathbf c` are what `toppra` needs to solve for path + parametrizations. - It is important to note that to evaluate these coefficients - :math:`a(s), b(s), c(s)`, it is not necessary to have the + To evaluate these coefficients :math:`\mathbf a(s), \mathbf b(s), + \mathbf c(s)`, fortunately, it is not necessary to have the functions :math:`A, B, C` explicitly. Rather, it is only required - to have the sum of the these 3 functions--the inverse dynamic - function: + to have the sum of the these 3 functions--the so-called inverse + dynamic function: .. math:: - \mathrm{inverse\_dyn}(\mathbf q, \dot{\mathbf q}, \ddot{\mathbf q}) := + \mathrm{inverse\_dyn}(\mathbf q, \dot{\mathbf q}, \ddot{\mathbf q}) := A(\mathbf{q}) \ddot {\mathbf{q}} + \dot {\mathbf{q}}^\\top B(\mathbf{q}) \dot {\mathbf{q}} + C(\mathbf{q}) + In some cases, one might have terms that depends purely on the + path: + + .. math:: + \mathbf{a}(s) \ddot s + \mathbf{b}(s) \dot s ^2 + \mathbf{c}(s) + \mathcal{C}(\mathbf p, s)= w. + + an example is the joint friction. This term is referred to as + `custom_term` in the initializing arguments of + :class:`SecondOrderConstraint`. It is interesting to note that we can actually use a more general - form of the above equations, covering a wider class of + form of the above equations, hence covering a wider class of constraints. In particular, one can replace :math:`A(\mathbf{q}), B(\mathbf{q}), C(\mathbf{q}), F(\mathbf{q}), g(\mathbf{q})` with :math:`A(\mathbf{q}, s), B(\mathbf{q}, s), C(\mathbf{q}, s), - F(\mathbf{q}, s), g(\mathbf{q}, s)`. This is the form that is - implemented in this class. + F(\mathbf{q}, s), g(\mathbf{q}, s)`. This form, however, is not + implemented in `toppra`. """ - def __init__(self, inv_dyn, cnst_F, cnst_g, dof, friction=None, discretization_scheme=1): + def __init__(self, inv_dyn, constraint_F, constraint_g, dof, custom_term=None, discretization_scheme=1): """Initialize the constraint. Parameters ---------- - inv_dyn: [np.ndarray, np.ndarray, np.ndarray] -> np.ndarray + inv_dyn: (np.ndarray, np.ndarray, np.ndarray) -> np.ndarray The "inverse dynamics" function that receives joint - position, velocity and acceleration as inputs and ouputs - the "joint torque". It is not necessary to supply each - individual component functions such as gravitational, - Coriolis, etc. - cnst_F: [np.ndarray] -> np.ndarray - Coefficient function. See notes for more details. - cnst_g: [np.ndarray] -> np.ndarray - Coefficient function. See notes for more details. + position, velocity, acceleration and path position as inputs and ouputs + the constrained vector :math:`\mathbf w`. See above for more details. + constraint_F: (np.ndarray) -> np.ndarray + The constraint coefficient function :math:`\mathbf + F(\mathbf q, s)`. See above for more details. + constraint_g: (np.ndarray) -> np.ndarray + The constraint coefficient function :math:`\mathbf + g(\mathbf q, s)`. See above for more details. dof: int The dimension of the joint position. + custom_term: (:class:`Interpolator`, float) -> np.ndarray + This function receives as input a geometric path and a + float path position, then returns an additive term. See + the above note for more details. + discretization_scheme: DiscretizationType Type of discretization. - friction: [np.ndarray] -> np.ndarray - Dry friction function. + """ super(SecondOrderConstraint, self).__init__() self.set_discretization_type(discretization_scheme) self.inv_dyn = inv_dyn - self.cnst_F = cnst_F - self.cnst_g = cnst_g + self.constraint_F = constraint_F + self.constraint_g = constraint_g self.dof = dof - if friction is None: - self.friction = lambda s: np.zeros(self.dof) - else: - logger.warn("Friction is not handled due to a bug.") - self.friction = friction + self.custom_term = custom_term + self._format_string = " Kind: Generalized Second-order constraint\n" self._format_string = " Dimension:\n" - self._format_string += " F in R^({:d}, {:d})\n".format(*cnst_F(np.zeros(dof)).shape) + self._format_string += " F in R^({:d}, {:d})\n".format( + *constraint_F(np.zeros(dof)).shape) - @staticmethod - def joint_torque_constraint(inv_dyn, taulim, **kwargs): + @classmethod + def joint_torque_constraint(cls, inv_dyn, taulim, joint_friction, + **kwargs): """Initialize a Joint Torque constraint. Parameters ---------- - inv_dyn: [np.ndarray, np.ndarray, np.ndarray] -> np.ndarray + inv_dyn: (np.ndarray, np.ndarray, np.ndarray) -> np.ndarray Inverse dynamic function of the robot. taulim: np.ndarray - Shape (N, 2). The i-th element contains the minimum and maximum joint torque limits - respectively. + Shape (N, 2). The i-th element contains the minimum and + maximum joint torque limits respectively. + joint_friction: np.ndarray + Shape (N,). The i-th element contains the dry friction (torque) + in the i-th joint. """ dof = np.shape(taulim)[0] - F_aug = np.vstack((np.eye(dof), - np.eye(dof))) + stacked_eyes = np.vstack((np.eye(dof), -np.eye(dof))) g_aug = np.zeros(2 * dof) g_aug[:dof] = taulim[:, 1] - g_aug[dof:] = - taulim[:, 0] - cnst_F = lambda _: F_aug - cnst_g = lambda _: g_aug - return SecondOrderConstraint(inv_dyn, cnst_F, cnst_g, dof, **kwargs) - - def compute_constraint_params(self, path, gridpoints, scaling): + g_aug[dof:] = -taulim[:, 0] + constraint_F = lambda _: stacked_eyes + constraint_g = lambda _: g_aug + custom_term = lambda path, s: np.sign(path(s, 1)) * joint_friction + return SecondOrderConstraint(inv_dyn, constraint_F, constraint_g, dof, custom_term, + **kwargs) + + def compute_constraint_params(self, path, gridpoints, scaling=1): if path.dof != self.dof: - raise ValueError("Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})".format( - self.dof, path.dof)) + raise ValueError( + "Wrong dimension: constraint dof ({:d}) not equal to path dof ({:d})" + .format(self.dof, path.dof)) v_zero = np.zeros(path.dof) - p_vec = path.eval(gridpoints / scaling) - ps_vec = path.evald(gridpoints / scaling) / scaling - pss_vec = path.evaldd(gridpoints / scaling) / scaling ** 2 + p_vec = path(gridpoints / scaling) + ps_vec = path(gridpoints / scaling, 1) / scaling + pss_vec = path(gridpoints / scaling, 2) / scaling**2 - F_vec = np.array(list(map(self.cnst_F, p_vec))) - g_vec = np.array(list(map(self.cnst_g, p_vec))) + F_vec = np.array(list(map(self.constraint_F, p_vec))) + g_vec = np.array(list(map(self.constraint_g, p_vec))) c_vec = np.array([self.inv_dyn(_p, v_zero, v_zero) for _p in p_vec]) - a_vec = np.array([self.inv_dyn(_p, v_zero, _ps) for _p, _ps in zip(p_vec, ps_vec)]) - c_vec - b_vec = np.array([self.inv_dyn(_p, _ps, pss_) for _p, _ps, pss_ in zip(p_vec, ps_vec, pss_vec)]) - c_vec - - # for i, (_p, _ps) in enumerate(zip(p_vec, ps_vec)): - # c_vec[i] = c_vec[i] + np.sign(_ps) * self.friction(_p) + a_vec = np.array( + [self.inv_dyn(_p, v_zero, _ps) + for _p, _ps in zip(p_vec, ps_vec)]) - c_vec + b_vec = np.array([ + self.inv_dyn(_p, _ps, pss_) + for _p, _ps, pss_ in zip(p_vec, ps_vec, pss_vec) + ]) - c_vec + + if self.custom_term is not None: + for i, _ in enumerate(gridpoints): + c_vec[i] = c_vec[i] + self.custom_term(path, gridpoints[i] / scaling) if self.discretization_type == DiscretizationType.Collocation: return a_vec, b_vec, c_vec, F_vec, g_vec, None, None - elif self.discretization_type == DiscretizationType.Interpolation: - return canlinear_colloc_to_interpolate(a_vec, b_vec, c_vec, F_vec, g_vec, None, None, gridpoints) - else: - raise NotImplementedError("Other form of discretization not supported!") + if self.discretization_type == DiscretizationType.Interpolation: + return canlinear_colloc_to_interpolate(a_vec, b_vec, c_vec, F_vec, + g_vec, None, None, + gridpoints) + raise NotImplementedError("Other form of discretization not supported!") diff --git a/toppra/planning_utils.py b/toppra/planning_utils.py index 5c11b431..c950297d 100644 --- a/toppra/planning_utils.py +++ b/toppra/planning_utils.py @@ -147,7 +147,7 @@ def create_rave_torque_path_constraint( qdd_full = np.zeros(robot.GetDOF()) active_dofs = robot.GetActiveDOFIndices() - def inv_dyn(q, qd, qdd): + def inv_dyn(q, qd, qdd, s=0): with robot: # Temporary remove vel/acc constraints vlim = robot.GetDOFVelocityLimits() From 655c7673b9da9fd1832ead4fb3d96286f3a259e0 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 5 May 2019 06:13:23 +0800 Subject: [PATCH 15/22] add missing files --- pytest.ini | 3 ++ tests/retime/test_correct_velocity.py | 64 +++++++++++++++++++++++++++ 2 files changed, 67 insertions(+) create mode 100644 pytest.ini create mode 100644 tests/retime/test_correct_velocity.py diff --git a/pytest.ini b/pytest.ini new file mode 100644 index 00000000..b9357dfb --- /dev/null +++ b/pytest.ini @@ -0,0 +1,3 @@ +[pytest] +filterwarnings = + ignore::PendingDeprecationWarning \ No newline at end of file diff --git a/tests/retime/test_correct_velocity.py b/tests/retime/test_correct_velocity.py new file mode 100644 index 00000000..b7688de3 --- /dev/null +++ b/tests/retime/test_correct_velocity.py @@ -0,0 +1,64 @@ +import pytest +import numpy as np +import toppra +import toppra.constraint as constraint + + +@pytest.fixture(params=["spline", "poly"]) +def basic_path(request): + """ Return a generic path. + """ + if request.param == "spline": + np.random.seed(1) + path = toppra.SplineInterpolator(np.linspace(0, 1, 5), np.random.randn(5, 7)) + elif request.param == "poly": + np.random.seed(1) + coeffs = np.random.randn(7, 3) # 7 random quadratic equations + path = toppra.PolynomialPath(coeffs) + yield path + + +@pytest.mark.parametrize("solver_wrapper", ["hotqpoases", "seidel"]) +def test_zero_velocity(basic_constraints, basic_path, solver_wrapper): + """Check that initial and final velocity are correct.""" + vel_c, acc_c, ro_acc_c = basic_constraints + instance = toppra.algorithm.TOPPRA([vel_c, acc_c], basic_path, + solver_wrapper=solver_wrapper) + jnt_traj, _ = instance.compute_trajectory(0, 0) + + # assertion + initial_velocity = jnt_traj(0, 1) + final_velocity = jnt_traj(jnt_traj.duration, 1) + np.testing.assert_allclose(initial_velocity, 0, atol=1e-7) + np.testing.assert_allclose(final_velocity, 0, atol=1e-7) + + +@pytest.mark.parametrize("velocity_start", [0, 0.1]) +@pytest.mark.parametrize("velocity_end", [0, 0.1]) +@pytest.mark.parametrize("solver_wrapper", ["hotqpoases", "seidel"]) +def test_nonzero_velocity(velocity_start, velocity_end, basic_constraints, basic_path, solver_wrapper): + vel_c, acc_c, ro_acc_c = basic_constraints + instance = toppra.algorithm.TOPPRA([vel_c, acc_c], basic_path, + solver_wrapper=solver_wrapper) + jnt_traj, _ = instance.compute_trajectory(velocity_start, velocity_end) + + # assertion + initial_velocity = jnt_traj(0, 1) + initial_velocity_expt = basic_path(0, 1) * velocity_start + + final_velocity = jnt_traj(jnt_traj.duration, 1) + final_velocity_expt = basic_path(basic_path.duration, 1) * velocity_end + np.testing.assert_allclose(initial_velocity, initial_velocity_expt, atol=1e-7) + np.testing.assert_allclose(final_velocity, final_velocity_expt, atol=1e-7) + + +@pytest.mark.parametrize("solver_wrapper", ["hotqpoases", "seidel"]) +@pytest.mark.parametrize("velocities", [[0, -1], [-1, 0], [-1, -1]]) +def test_invalid_velocity(velocities, basic_constraints, basic_path, solver_wrapper): + vel_c, acc_c, ro_acc_c = basic_constraints + instance = toppra.algorithm.TOPPRA([vel_c, acc_c], basic_path, + solver_wrapper=solver_wrapper) + with pytest.raises(ValueError) as err: + jnt_traj, _ = instance.compute_trajectory(*velocities) + assert "Negative" in err.value.args[0] + From f7da126eff3a8782f0e53b8f832b9ad572acc2f8 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 5 May 2019 06:14:15 +0800 Subject: [PATCH 16/22] ignore profiling result --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index 3610bf6e..6555ace1 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,6 @@ +# profiling +*.prof + # Byte-compiled / optimized / DLL files __pycache__/ *.py[cod] From 37cea6d11a34035e95b222d75f1b5d2e50424dc6 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 5 May 2019 06:49:51 +0800 Subject: [PATCH 17/22] minor change to requirements.txt --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 6f7c5947..593da84b 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,7 +1,7 @@ cython>=0.22.0 PyYAML numpy -scipy>0.18 +scipy==0.18.0 coloredlogs enum34 matplotlib<3.0.0 From 3e6a0f57c0451a75a32f1f634e6d25cf5499c944 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 5 May 2019 07:11:10 +0800 Subject: [PATCH 18/22] add command to check coverage and publish --- Makefile | 9 +++++++++ setup.py | 2 +- 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/Makefile b/Makefile index fed9fff7..d5aad1e6 100644 --- a/Makefile +++ b/Makefile @@ -6,3 +6,12 @@ lint: doc: echo "Buidling toppra docs" sphinx-build -b html docs/source docs/build + +coverage: + python -m pytest -q --cov-report term --cov-report xml --cov=toppra tests + +publish: + pip install 'twine>=1.5.0' + python setup.py sdist + twine upload dist/* + rm -fr build dist .egg requests.egg-info diff --git a/setup.py b/setup.py index 3f511e29..0e32e4a8 100644 --- a/setup.py +++ b/setup.py @@ -5,7 +5,7 @@ import sys NAME = "toppra" -VERSION = "0.2.2" +VERSION = "0.2.2a" DESCR = "An implementation of TOPP-RA (TOPP via Reachability Analysis) for time-parametrizing" \ "trajectories for robots subject to kinematic (velocity and acceleration) and dynamic" \ "(torque) constraints. Some other kinds of constraints are also supported." From b6d9531b642c038bcdc388f0e63110b86c7a4053 Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 5 May 2019 18:44:50 +0800 Subject: [PATCH 19/22] add instructions to publishing --- Makefile | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Makefile b/Makefile index d5aad1e6..2a255c7e 100644 --- a/Makefile +++ b/Makefile @@ -10,6 +10,12 @@ doc: coverage: python -m pytest -q --cov-report term --cov-report xml --cov=toppra tests + +# todos before publishing: +# - increment version in setup.py +# - increment version in doc +# - create a new release to master +# - run publish on master publish: pip install 'twine>=1.5.0' python setup.py sdist From e6e1b83f683b3bb8d4d9a493df523adf4f3f8d2e Mon Sep 17 00:00:00 2001 From: Hung Pham Date: Sun, 5 May 2019 19:26:56 +0800 Subject: [PATCH 20/22] version defined in separate file --- VERSION | 1 + docs/source/conf.py | 11 ++++------- setup.py | 4 +++- 3 files changed, 8 insertions(+), 8 deletions(-) create mode 100644 VERSION diff --git a/VERSION b/VERSION new file mode 100644 index 00000000..b6a83a76 --- /dev/null +++ b/VERSION @@ -0,0 +1 @@ +0.2.2a \ No newline at end of file diff --git a/docs/source/conf.py b/docs/source/conf.py index 689a8364..77b5b54d 100644 --- a/docs/source/conf.py +++ b/docs/source/conf.py @@ -19,6 +19,7 @@ import os import sys import toppra +import pathlib2 # sys.path.insert(0, os.path.abspath('../../toppra/')) @@ -64,13 +65,10 @@ # General information about the project. project = 'TOPP-RA' -copyright = '2018, Hung Pham' +copyright = '2019, Hung Pham' author = 'Hung Pham' - -version = 'v0.2.2' -# The full version, including alpha/beta/rc tags. -release = 'v0.2.2' +version = pathlib2.Path('./../../VERSION').read_text() # The language for content autogenerated by Sphinx. Refer to documentation # for a list of supported languages. @@ -116,8 +114,7 @@ 'fixed_sidebar': True, "sidebar_width": "270px", "page_width": "1240px", - "show_related": True - } + "show_related": True} # Add any paths that contain custom static files (such as style sheets) here, # relative to this directory. They are copied after the builtin static files, diff --git a/setup.py b/setup.py index 0e32e4a8..7f2d79ec 100644 --- a/setup.py +++ b/setup.py @@ -5,7 +5,8 @@ import sys NAME = "toppra" -VERSION = "0.2.2a" +with open("VERSION", "r") as file_: + VERSION = file_.read() DESCR = "An implementation of TOPP-RA (TOPP via Reachability Analysis) for time-parametrizing" \ "trajectories for robots subject to kinematic (velocity and acceleration) and dynamic" \ "(torque) constraints. Some other kinds of constraints are also supported." @@ -45,6 +46,7 @@ if __name__ == "__main__": setup(install_requires=REQUIRES, + setup_requires=["numpy", "cython"], packages=PACKAGES, zip_safe=False, name=NAME, From aef91cdb78cc9ddda5d898c991abd1ff18a8f3af Mon Sep 17 00:00:00 2001 From: Hung Date: Tue, 16 Jul 2019 00:13:46 +0800 Subject: [PATCH 21/22] add docs --- docs/source/FAQs.rst | 13 +++++++++++++ docs/source/medias/faq_figure.png | Bin 0 -> 66074 bytes 2 files changed, 13 insertions(+) create mode 100644 docs/source/medias/faq_figure.png diff --git a/docs/source/FAQs.rst b/docs/source/FAQs.rst index 62a67578..548f04ef 100644 --- a/docs/source/FAQs.rst +++ b/docs/source/FAQs.rst @@ -29,4 +29,17 @@ As a general rule of thumb, the number of gridpoints should be at least twice the number of waypoints in the given path. +2. Minimum requirement on path smoothness +------------------------------------------------- + +TOPPRA requires the input path to be sufficiently smooth to work +properly. An example of a noisy path that will be very difficult to +work with can be seen below: + +.. image:: medias/faq_figure.png + +All toppra interpolators try to match all given waypoints, and hence +it can lead to large fluctuation if the waypoints change rapidly. In +this case, it is recommended to smooth the waypoints prior to using +toppra using for example `scipy.interpolation`. diff --git a/docs/source/medias/faq_figure.png b/docs/source/medias/faq_figure.png new file mode 100644 index 0000000000000000000000000000000000000000..dcfbebb330493acaccab53b27662c9474463c1a4 GIT binary patch literal 66074 zcmeFYWmHse_%=F7O9@CxDJjz3AtIrqpmcY4$57HC4bmd;Q<0FCmhSEtx?$*{2F}C( zJ?}Z+&syhvI_b0cX73Lbl~OS=HO;~Zsq3YB*Mx0e;?;?bg|@oVnId$fjoyO$h_9@ z%GzJ_belhKx<4*X-DpBYWE(SA@V3o{Bs}>P_#v;b(6=@w&Uaon;GikZU~bc6r2n9f zT|YThsXq*2Z1MV{YHcQRt*LmOQFjc12se52b%UXXQMasHSQxWEvDpz*&S!^ri8jfY z9D@$Li1-HXIHY92t1I~fR1&4!U{{Jukf3aXCcN|7yr#?*+laqubB%gcDPCSLdHt^tv885qu zD5$7(+u;vYaG|&2sA_7;efpHz(*FeP)~Tw#zLJGSQA__34mkFNgarLEAn02`0a7m( zY$|Se`^s}xR@-fVF>)4&L13FTYOuo(`-$rV3?Ac34w-yY-?NYz2 zGPmn7COf}=)s)-lCzz6FIF4q#@62$;Y2o9kCGND#vk0{k4H+{NRdC%cT#Xo$;d3wN zG`cI0?BoV($%x9ifzY>~jpEBq2r5koY6*!P80kbp!6{KW2o|Y1vh4jEPr^eMTs-q- zAH9_sqO(HH>t0*Q@jYBw38yW}&ks5~bCWpD7(PP6p|nZ8>+lm9CN@i5+QNCtmrHu# z1%-~=7j+X(M3vv<2Vxjr&?okIi6&HdNdGIbL<-LC?Qb2^IutiGXR@oLIPci=%HDK8 zA*7fN7J%HXGfS@2wjkLF#Lu3fqoeOH)F%xGTvT>+bU01xdtNn&C19JkZshwp^4`Eo zihhg_z*bZkk@t zmu>yImtH_Wlb=2(ddjTwX7b&V_dZt!?^;DT`oa6Gh#m^`gI{Z7h3~JxdZ<`ivv_-Z z@6Xr94`vFUMjPI)R>eEl>(%L%=9f|9cWWiT;^8<))O#OK-&p=;f^NMn&1fm9FT_?IOavLIG=k-T0THyhR1|ceZi-Gi@PLsB^Bf!$DQNcC7=o+vw<@%i{(0H#C()gdLdBB$j-w=p*3`6f+X?(Wx$0aro z8{kEim9E<=?(XO0pV)W;_WkOE3mP)HbQSfkI<>zm#?e#`eoT5ylrAPnST=1mo>WNQ z^}~}aIs&aSj~eCnqPAtwv*kwLq3Qe+#9}x{$=sX~?8Mr5?%f#+t!eFi#r%P(c2Q5A ztC=S8yrB?ADAiFHw{&ZUmad$RVj8%u3;mVg{tnYbOcMX4yIW&G=5slxU*<*hNMg@HycXT3 zj~~`9&A=xzD(Z2L_a;TaakQb+TCCu817Cvk!vcC&p?S8Xoh@jkF7Zv4o$FOGQQAgi z6un~x$#km|9U-3w&UE?95E+%}*ql-3e_%V1C7c9BPD3~P4exjmOTJ|-?};hW@EvXQ zu2n@ze`WMbaHCdsws3N;jJ_DqOT>`so$_g!0?ouK*aOcuSk3pS;-R?+HYxNX}cZ=m?XCOlC_=8^PB93-lzhYL5PmWCt0 z%r`JJMt)PDyBEfYr||XZTR$JP928DD5B{qLD#C=oe9*qg)<>p%;tp)v?6@m-$9XF* zy>}5IicG}3q_nvh0kv(zlc3+lwR#tlCO8)tRD>(3q@t8>hp{jyMV+|5W$xEa4(>(6 z+sJm~ySV(HljebwZgnogSE?mRRy@3WdZNvjc3U&9k$Dm1qDgTG6gF?o%-1q9QYfkn z&(9F`)}=1j4Kc>N50}i6U*D%-6&m|7x3}AlCNoK5sQaw*2PFBxPD2G0V$fzE{o7>j z_d4ko1+`@h{vpi#K9fJ$!M4Lpz3NaJS~J(qc0#iCYy1Y($JgZT-O zMPWl_?sWn69fzDuM_KR%!;=IlZgNO52@`SJv$i<0_zKH6B(5C8V(`F?^Ji}|d9MFr zf{IaeD38g{c)&+>(6M&$2kc*l^X-3CD>D~*!Upke$=(Vj*JlHPOJ~lnNHa57PLp2F z>Zr^PF^##RLU(m!%&GvMxtukEDE38}3~glW&#J!l43FM?#oRkPx^<>!5TBNI2Zu~{ z{+8*OJFaUw6TwvWhS?9NCF!OIcY0hz27)%>Zcd#($n?pNZyLUJn^U&%&+J{zl&hO3 zald3DrK-}ew=!Lc21uD(yO$6PIpb>W9*zi1zrBN@$%bL7!k_<~NW$eUJ_>-@C5_E&C!uiw^oT(J^uu}MvOMmX@KSFCmzMYsoG zjM)j(wyG5^=$gZj3oc3~-a4PfGq;Ozt(CmOIR(3SXy~kC8OgNq{2e@JTJ2m`KMq$x z7GK{i==sdMl?e1xlrqt^Nu#KC#7orOIerlz=o{$#LFHAPigeV-eF~xM6Lm)Tf_D6^ zxiN{FlZMhK2i=xg-AidmyUey)yYBL*oq)t4CHjD&$F7=GJJ-vl)jc(>ayq0RbRdu@ z>8bLk0I|tV`+aC-*amIyxu-%g{|J2LT#_u;T{y6yF#hMaPXiXj+`Y!3vNKKuUd~l# ztGmtwi<}@W$2pW~4*t9~qXKB;xPYMa{w7a2&C+=}Tjv#i)raO{Z>yhwu2m_A?_D@= z)hR`N>r&oJ2xNopZ*TUv`{U-(^g+S1dq)mM*S5jB4BlnJpQI~vyM^y|`pH~Pe?j&* zRfM!;u#Lvy)Kh`k`iJwMmEq2+Nq4a0Jp<7NEyJK67An{_r%CB0+v%A7w8Z+XxEJma=*;^};s*@k2m1w}?z)J(se3C*;aGYy!)iw7Y!IO{-)W*lA(W zo*S)<1zq8OvCb}UeD~GvU%{K9ojKCXt5CJpjQ%m@uQXI*{PeyxW#LOQ2`RKHp!$L? z{M5d5?Hm8>9f!5NuD{^TQpx5>st;}%X!ux~0nVg5^%ceb1K)$uQWwQyL9kFOiJu|r zDzpY=y26Rlh=x||@fy#au$5BcxNj9?7``ZFX}TpicTMgURrXGQ5w`v?p#U@V8Q0LU z$(l&@IGSmikBF%r-=li|f<8F2Sv{h+1ADJ&Nbc^>S$=ikTgtukhF7-RzG22r>t2v7 z`2r|}DJjzXSEbi!8RNtL)~8t-S6tV!Nc+AKEJOZ?NZl>XpD!{OZUY?)S?n;@5Ha-f)AlJJyK zdBv?ez(8YYF`|)gZA1t-Pg5XMiS6%_;Nv=Ytj)Wn^Ygp+LveI;7VC1Rc9{C2hUy+T+dyL`3wtO*d6g78h9<5eS!+ye;?P8)p-Zvrlhb4 zC%#+s=QL45Yq5SSUBHOWI68(*M`+AkGOYe94`<|e1vNfR;aSkuxGLoCC9GDelZ5~L zioCdXcxb7m_5S#z{hy%{hc@uF*=!(C4&pm4M4>vs!C1ENa0$oF{6uOyPS)6AUqS~#Co9$^~sWQI*; z{-n)|utHPqAkYbWCM9=WpGd6qDuUVG2KQV}6l6paxzTxS(fYpClwWgT8q_mzb8pSQDZ#k@BYR+K+nL}vJ#6h=~1cIka%T|dj48?f# zg-i!V7seA|wZq`2n}*!jfxm~TD0GO0sW6vH3s0n2K~zq5>kgnr^$3ZAPm>#jq<$@} zl#~KY5&$=D0WUPY51-6Nlq%wwKTmIh3O+VF(LcJV)b68bt4{`^7wsr}BP*Rk%l4%b z6ERD-U@#w8etA_u)hSHv&ztX{*gHWa`0Fw+@;_}F_Q;jdMIfJ0z~c8=Hqjqj|4s@yl=n3P z4{hI44&5zjBe}O3GBZ2zKE43?~XTp{)*m!(Bt(t-qlL=H26^50U2@9061KW1^jUS#Tum)A5ye=z>pU^ zX;#MFd0xSGYXOzUqvZoiYp3RxQ3d*4zs;P6A*4hT@)TPq=>8oePmmkmwJc;!y&A<# zEK(WQ^jg~R&DH@Yjp&MRXXaj*?7ant!l|717TdWO#O|jH*9iRBm7i{v04$Yh&*&JY zl;R(7o9bTn_)L|NKfg`oSGyht43AVDc~KxyA7C2KP~5crh?7hKSX(QrkT!fMwpUmA^Wiuhp2-KWOIk4hf#hYn@YU`n|wWaj=NB!pt^LbP;s z`s|@cOa{38Y-BlbTCWBsJ;jOxdk& zRBwUc@q(2#8k5$~X}hL3iTS32E@Rt=8cA+|3iiWGF`}hE;neMTQaHJBUJ9D)cq+3Z zLe^a`)r&sv1S&^7o++fcFl+ta6{q%QsJwO_Kb25zrTui9zv zoVvQ}^f;*SyRo4%Vg0iKe%FFbXqCcT@z_a~(O?g|cnr0oq6o~pgl4aNUnOlZqNp|( z&kmsoBf^LrgW&$A0pN?e)zhnWcC1@4wWq<0Pl1$_517 zVb=}XS{XP&mK-#>Y z_g<9~^}2vwJo!#6M@Re)=r@i5rJ0c#!$ldeu zk&#S^EQHZXrfW6>Xeoi&oSIoD5`a-Uin(FoI`JXK^fo&7j^m6|=y=9}WX7RY9%z~4 z9o9|b8>3xm;S6s=xZEQVuJiV_R}Fj_d4H*!X##Cf=!1%mzEUYN34s>+wVhcY>=5pL zdg4g1Z08T%Mf`9Vy&7+^`!_l!I#n3egM~dO5eTuJE;T=xtG?rS6D$Kag2a4)B)29e zlf1nU)T;B~d13r%Znr`B)<7KavyvAUMFT3|+;r(7NPn8RLu-pWlB8R` zriiTgJbaM-=6NvQ2@85L9Te3^!-)hc1;0x(uM4v60)Fm?!aIvXD*>I2e1}E-I1u7q zcmV3fTJod39&&OjWaZ4jj5IsQt#z{tF4k$NKaH<|#;C@Q?iv}PEwinKnEEEOamD2) zT>X>d9UvFE*csx0^64dRFp!$3uf)LP@KEo9atIXfzbcBL%REZr@AwyNJM71>S&~BW zfC*LZ|3uyy2o6r_e_#KPF}265Al{zN)QAfbW__*61gV^r@o`{-03zpgz11*-v?#0Pbft}_ORqaU(F8I+G32H3d!_~@GJiKNK^~p2ic2XPRd_!%Z zvVry(5h0A&>@UqhnUZu0Jj4g2q-o*Ik&J*nR8sTnqtwVQn@TQIg;&0YWe;%RB8=u| z^!&`R3p&npjyH9F#APn{y(*v;e0*yU^1`9s7X?6YFO0@Bp&RF#3l}F->cNl7BAGth zdo)L}vgywy*n?~SI*6efT-g0*ay3}L<)+`xHFN2;GqUsW$%{svw=4X@Tj#F0=a7eW zHEWye4V9fsZ+@Bbb5&sJS{EDWFS1L)PfgT^pdETLvJV%)1~|EB{PmFSkZ!s(sL9K= zg+wH@?=<{g?$kR&fb?D^cm{O$BtDkMzUe7_A-@|h_xzvQmlPiDQc2T?Nh1GxzTpR| zHg|^7Kr=%K(s8nUt*6SGXC2OHnD${1G;Gwaf8GVaPh?`(ig=`s(m` z;hL7WNR+pavOG}Ux6a*v!UH$4zw#+{K?op;>M$*Npv`Tb3GEv<5A!EIURCIcXkCO; ze`OND4Jmqud5AL1lH1LND)$X1kZ?5OyUx_Q759+8*)F4w@??Ji#}fx}=-ma=lJDWmoFGKVM`&)Q{+_=* z?+hNpcZ&vkog|fHR0BYxm7oW(WqDbhy%9{DPNwW z+SJR5>@`~*n=djYs0F3S3`WVnr59Zk$Vk3EaDm?Xmp=PV=9^$8IduXc<90Pq|N6mV zFL{G1b1Q?QdfRpM%+9wt%U}!AFs1otrHu}^9TDjb^t>~7f+tB-T?2*ITmG>NpILy4 zux;acyi1G!2R>-iTHAmqgzc|6!eD){=Gv4fRCc~kLNh1vYxGb-71I@W^)Q`5nT{E4 zpK(4&O^d3srR#9HEr9Lguq{gGm%f(TzR9|I9pv>YSJ+GEF^EYVef@I;ctAdR4&mcg&metci)4dA_wdbU2 zADs*T)vW}`*7##}j!O}s)d4tJc}tH0t^sHeRxjb-|NNH%WU0dWXP^|Bc;UHNFgtZ_ zJyxFW9x&r^o@FjNy@c8qUpR?^WKU|@-xtTgL^b*@d(VKi&aP!&ubuo9N>vJA{Nv*?$?3z$>c(WE_IAkHoZI}0n<=e`lc~f)K!i+w*eG= z-}?Zy07^fjI%UR#*F;gM9Qnfi9quya>@U{6=X6ubCKl@yD&(N@Sc2`ExjrMTxkX|n zoe)RFh`N^ViO@j!k*sac1sJo|_g{W}l}$A}DO82;$tFC1{Sr2==$exBUxz9YFP*}0 zG$WgfTf5chvAWtHi!PvG;j7&H35M59@VW=^%vKUP)tnpSamV{m)3pP!J783A2e4`; zhJkm0whxf zB6WPpkUo&e4p8JVjh*jqH#6u`!+~k^4Vglh%IrXoVD^XE@h7yfWp4;>nN;Y{>=ws$ z(Eu9BT$SpA@D-|>B!gJ$e^r>P(mK)nuHN_~?wo+is4I~V-~IE#5Xhr%pV-@&POPwQ9WvH z(Nu%`tNxiOGQli<#TBhMri&O-$BK*H(!x)!Lpqy}EQ3KrlImr)gS_e}mIEY&%C9(e z3tFERbf;b$^z5*jrhZHO?s#0EdBNbs0JYRXQ0+M1Z206iuff%*n9C-^D#g)gse zfQC7JAO)zF^Mu@P>@Ziy{S=!4Y*b8MUmMdA`8$+VA`RNLK~t=*JBJ^}iB&V@k?@5u zvH{jUl;&4Sc3Rr=Oy{pj#n<}X{z{=+1Jv#d0d?nAL>pqelWzH* zQk=P+HJWOdo~0{6Y`32}pEfO4;Ib_}w?Xg+kiee;*a!mchiTWg4~x{7%5-fZj944& z@6i34B;+bzoB*}o`X#)>qSk4=h2+ojTyOC{m^Jots<3Pz0FWE~zv|3KV#2=X!4=kug zAm?iZRXx9(S{=@blt>xmg;t;Xai3i5LxBmA1U6j<-cPQjtNR;q$_0AYAx&Q#P~! zMU&ue-aF80_NYbz9~O zifc#NrUz-5F}#HIrT=8J>EvBzln{T&4rm%L9mpNV>4CL)d#Tn@n)_;J8_jF)rJx)EZ=KZu6|U4Dz%Y`uk#i z`_Mv9yxGX(vI!%rTMm-8AVg9*={X2gnf6lSA@htGX@7lGMW(vz{z~lVKchPHgRb|L z;bYWzd{lc>9tGYBr-dJjd6)oNJf4ER+ZMlzl(h8t=gr=VuaTc1P!A%P1-pW_TFLc<;?k`ywn6-B(0PFN{T+0R*c4@|!6qTy z8>gBJ=QC8f|1uPt2~UsGp8#PkU6IL$iX*E#vxDG|)}Y>TeK7G{1#Wlpm4XcOwM4o2 zbuQfb_~Yz=R$>@`$0|;S`(j7o_1z$iU$MuwGj%K+ZUtc3J5U?vcK@bV@Zt4y&HtTg zw|}^fcbd%ls21;c zldZti6P?wMl2K0_6^M=2KV1N%`CeUwBWFtsrlvzR&BO-07}|CgABts?gz0k{!Ay!d z=SIY&a<&5~wg8^80AXUuyCfOVwDSE_Jph7*s;YBt9NxbCAA_I(NyfgXA$a&xtO(y$Z#A;aGqgDDC7*JAMe#tQ~NH<(BoEb%=6 z0$rx~51b^k*_FG7H%oxQMdB&MT;m+^_Xp?c`K_+EEloaQ4L0nE4>Z_+d&T8fy?^rO zfo@7vSMq}NVKVpGmU$e0vP^MwGE@+*kU=zfJDC(V#R@xFlz!k5r_(VGn5fZ{10M~) zb|y(Ky#|VACJpC9FQ%HbeRq_R-p)nDW%F+C*ay!fu{}ZwpPBEUzyu?d?q)0X>FC#g zgxFq8mDqq#fZ@eM;&JFC`Tx^!1Oo~||E*PS;bJi!j%3yrE*wQCK)%@dnGxh9^-qX> zU&`K=o*3b@j?AXF{j;fbI-Z=}*D+LZGqF+)H6WzWrWjvK_fX>ji1E0Cpq3c$UY;Rk zH|dvZk;XF2p^3brYD$|MjiAK+ckC0JU&&d?yj%*a)CMGdWz=KLm3cFajF7_r^Yprt zSsFaO7mzwobiCF)mGLTnUAHJ`R4f=yq)y0b4PT{H%>(G=$O^Z{^dkKj}SYe+K zFwD`H+F8=W#XgCgov+tNYL)0XyrOfFI7!RBPH(U_KLGrf1}F+Vdx^M2JQMa(VJh%G zo^QBi+-|K`dDdjbm&N3S3D|7nf^nd|apBI~YGlO4C%JwDC;quA)vr3f1%Ph_%Zk|$ zR`ZS_VM0audiyw+uF^zumAZHNBy6Kc=o^a>g<8s6`#^Z>X(4S+Sg*+#z7}DE8klT$ zWxeN}z476n&*5Zlc>a1TuD={;__7)RYb@Iu8dYSF+{wtu&c4+&H^r$Q`LNhIDn1BC z_FdQ@>baYS0_OG_P~V^Rgk?*%sKM0N{WmZN=XSXVB5P zd=pMHCnTi~2E*Amy1PjIIJCMvfDKn$JnH~-{ta#$ zLOS6Op@rT$KiG|c>=)(^{l6u@td*sLU&WQsZK)$LSq5AtuIE$)xU)dv!O)|5g@5@q zN;x~X<16P=qnfPiQ)w^~z}vuAv>*o6JyxC?-2Ne(0548y_JA%yS~+lRoum~L6Fr-7 zJa>8aTJ({YzW(5J%boj!<4O9>oAC2=_q{1XVq)GiW?%^j$3+HW+qhQ&r-ReWx1zj?h1mB~y%&0x&t({kS1k&;2_})J4Gh}~8wv0$h?-j5qWYmPd7pGQC%jL>mN;K4ly3%O-gfJn&*-IC-Oj0XGe4&rslMKZEAw2O> z)c?q&U7T=O5S^7AMDw>!XAmmpOoJzUBo|1tz+EPAak%LF;S#lc{y;`fF88S05JPSU zf{Pl(>C~dbv?Sl>x6>*wIM{=m z4^bLvLV%qPFo%}BXEHKoX29L};syO9&G^jXse|u7<+srKBZEDRrGOo((qd3#r6wW* z3+VUCf5o5pb3q$ykd!`5(gUSqMImx zV#VU-8@&}_N)mtqKhq=7vfVw0Op&OVR$`mWorZAJ2mV*we{VWUxF5#Md-Xbam20gGsy!WF;IslugL#xJNg^KbZ2EAT^ zY^rH_PhQgoA%AAf=&$o2rWIMaE?T25WB^a7)z71Yms8Iq2ooaPO?X{rnJp8OsRw~` zMYyKy^L4?z7U*=qTY*1A03WK6_!;G2{C)APf?}P$(EqL&}g95f3}CDuvU9g-E2v2CyIq1yud2 zAoJvxkT~@a`oNkeIL-bGo{>R zQ#+!!u?|F=t^E7i6wLr=;MYU}Xd2cfz6fB&2!qrXy#i>#TNJ0PXSji%8XRj~fSLdS zrZnN=E$jbfa)LYWAE`}#LwhHXY8sFB{3lYXZyIC( z@B)I7aeO(CdCpKOE&JoZwTV{DqQDhowXagjkTK_xcvW>=_nj>z`4<8Hu>USk;q<`B zy(S0jqWunEySAV;!F%wpazp!QjSeAcP~X6dFo%|@PmP_Pb**P_e`wh=*P10I*JZ$dC^Ti*R!VYToWhFOF{$4QKXX6QrZaCOid% zF;4X3mA|4}#_>l@@nSd8;sAtjTTBb$np$0ZmN$Hkp#i7c%`FZ@`9|DcxB08GVvb#= zGyDUX=Ka%T3M+t$EC4uTkTRL+15@YMrJ3X zCoQImI=J(|t!KZ2Jo>)Xb)0c;&;?|Xfm>E4=x3} zzrQO-qU2qVMC#tm$78n6JXN}nis*?1wHKITqi0RNfvGgf&G7HenJcSOw?|*ZSbQeR z7{Q6AMzD;wGirN^mCn&yi{5o(*Am1*x~!485fNF^dNydMpDaPqY!a>$Oo02Sak1bvBM>k?@H0CxCG7d;hkXC|x^$ z#-|CwD(NYtJNVJE5O7!R9Uz8nA@|xR$0{FyiRjH>0bY9^@W=#Sx>Z9#dr`;1uKu&X zsRscLsmOvtPmR)X16XVWEPB#mw6%j=4MG);Tjty+5m-zFpdy5_&5Oiyl;0Y#My)UfaCGQ>2*j{=QbV>+!tQ!Hz-15U7umXD~d zB)NmrKQv6`QJkorIbBJ(Yrh$2-(5*-5esQ5(;No~E~wTvyeOFX;SmnAbPN4N1>jML z5|~zNtdAQiG60C!O3cF~EmFMfW5p_cy`o`ORIl4L;=e!Hv5iP4YzXipaCtk7{WrzQ z`~gB`3CP(hkWe038r}=O6cY($6ja_gki!Q?z`lHIL*TQB=&3IcpRco05+M8C+XaL) zB?VDnyEyYW4?+3uzWC7K*Ye*`ElstK0sSP|eYMm8loTK^Qs%xye=wd_9L@CxTt^0{ zfx!5nJ2$ik<)FF#J1xw$-#w(2)zvUe1FWR9km$*h-xmP-ECGL3Mm^s_=zJp$Cm54e zAUjO~7Cv2%_xu88OAozR&r-+{ZE@?>iHwLje~%W&(mHlYxI9EdWscYLx-8x6Ew+}0SzA0?Mo zH0+c59Sq^w)xcs3zQOlw13Z881mN_qoC79HB=|KF{-Ja2)XDJkrg%m( zS(lyeVgl-qukMU_WdG)?JaHDH0#6H!%+4yfo%Q7EZ=XMV@Xj&n?g2lY-bF8kqG7Vn z>tXGxAF1X4Jt-O(H_;^|q@b)WJOIAH1kf22(6IyH=Yn%^*jkV*1XUxxAQunH@vZ1P zbrN>ztw~$N{+Cx;3EYn+Bf;|{hO!1!6yDBYL@FVL!UdV6Jy@TVr25{_{&~{Dc(T~S z#L?_q585P}J1a7?_z)^9lST+QSKM z8rVSL$}=Iyz`J)ZD-rnr(rQy!rA)Vu~i_R}rglSy zQhu_e>NsQxwO+y%EI$HD-B!6N!i+B)BBYkjed_P7_jb0ojZQZQf&Hg{&zhE>6|3K|dil@yAsMgZWskhB-f6kv zu5fc#X?$9y*=A;7%R1U77kRda(qrf?Y}@R|O!{k(RxDGuZJO18Si+O~e=+8UX)Qn6{$?i_*;WwT?3!4@_t7{{pv3$>q z30sm|L8+W3m| zUb*r)>C0_`0O{Qc^?OPCva&+En}#zXk=fc6^95S0i(;bOoZjMq3)a{V@*}Ti|0bl} zA&Rw1K7E27<6G$ez5aef9`+jQ$SKf3t?5YMudnPQBD%9<$IK%UH1WfmSrI`q-w?e8 zzu`U%Afw50SHge$B0Zh_-#_J+FWz4Qf*!qJt0)k=ZgN~X_j>r^cMz%VK6-=s zA$I;JgwOiopU@DuuX}$s8)9oc@~H@yE5EzH3pbEsPV+lCeOlV&oD6-O&b`f@k3>B@9}mf(oX0mMft50te^S>l`|L?yyGR z4$@RwuTy>l-{rJW*|(>ihDbH~r$lbA2=+JNlD86{8nQW&n{9-!rg^9D$;@|q4htM) z=xL>!ePw?7ly8{w?v`i_u166sIayJS43;!F?uYK%pQi9^R&OIkdnjL1hB^01wqrwy zgv1;KhhYfQxjoy+ck(9ZTP*_L9BI(gO6WM)vn7f{#LF6mOoqW2d_Q1zI@NTlP&4M; zUh0Ikw;m!EZo-qn;&bC(BaZBdFnn{{vzNconR|4pSytRwf?GLllu!`%F}20$FDF4j z(-VU`{E7Y0W$L77uApL@o6KBK&`(f_$jfU9(Kg@EfE<@QyBZ|LiFUjuhcp=Yka|Mz zBP3enpWFWW^^izh8Fkycd$I>2>Kr<)yPSS_f$S>c(pNdu1s?1aq6e6Q$76zJ8~H8v z-|GdFzn}<4_t|Qf)8U#_q7YY6g&h#I(rUJ`dfqgw=Yhf4noj4PxE=Hm4k@`h(PywQ zkMDE0VAEI7Fd=GE#tau|5q~xP1Y5?}z?y{fKiR6NanX!lpTZzsPIdE@P`-0@LW z$)D3nqrA(zrv3MR(cuAgafukLMs$k@#@gEKNoDmkH}}3|%@wrG>iD!*tONCvh}HuF zDc?dvTLRL@fi86Mlm>SK3xdS>5(jXbp`O{Pf7gaE%&@ksNzK?@Yg&uw&sUmPvXUMx zw^Xki-981&8+wwxb!-9t%IO6zrs>9gUPA_UPm$6?hnyC;9B$op*ZN-`Tmw!wjW>%l zR&2pj1v%&i%F^PG^rdmov+_mv`x% zKMbKGn{sfXC%Zs7%M5S1!Tb8_mDfR#q4Qw&y@;{EXRig+Kx;Qo5#J`&zcd%(7%g zIgN{p(AwR3_A8^zbm-XKJSK|#jf?s9XIa+*+5U6q@}c_qxKI@`CU zD=2`B^VWpA8+gH5?JE9k_Iu(tWRJ+KoqJu5Pq#!A)JO7zt}&bTn__%#no6Wc9T7lK z*1eXt7mpD?Ke%>(MLlO@TX(|h3GhRxC3_>y%ng>^m7$fm%f*eZv|rgdxWfTyn7sp; zh8>2b`1hx+zAdNdl5ukAm3VYS{y~3QC^3Be2u{Cx{cymL%Zh{y$ZxNnh{6l6wg^U> z%yA%*hBvPwJr{y{{l50fwIAV0@1J~rOBz5?dP}G!+kC$p>T@rl@;H#p=-=(5>XdfF zso(-q9P7~#1<%r||_5v6b-Js?Vn^Y$XS@Qs_B-6!g zRHFr+b~FeN+5XP(@0;nigQMj5|i_u>QO_S1a$mKfy;#gfU)45;uKr zAJP{B`&&gqdxM*wkU)=Uk3%h-uQ~e1IYmfHG6)`d<23bzA-}Aw8L7Ko*63%J(^x^C(?GrJanp<+8x$>p=dCF%&yYS) zXB)TtN+Ph~{Q)-J22jm7Y_hYFYYJ0Um;f*a{JAZHtSGg>^Mjl2s!g@>KIC0&A>T zI-{OOiFW?36Gg-BAYSEY(9VFzlRaWVTg7(Eb#>3}X-K|@Jq~6XWVq@h zF|)9!8_10QxHkpAqe^6;npvytu-*DO;*T!0d5E~htPI$K_&>gEiQ%E)U<T(VcqEJt^+!Y223D8{Ww0p_F;ADFt?UhUonrPJDNs3u=V zaOLRL%U{V3o}6FPJ`?$!I#L{e+~ggrD~F$__ztbLV=U?fFZ07+5AiJVe)GQ38dv9y z5l5W5Dp#BhO2PKAA&GI1tflg=fxfleeB6cI$=Y?Pzgn;CDeD`3DLvz8yKeg4e#O5{ zf2^dlE=2NU+y=W5ng%{B9~IrX&_&AXi}`NyXZYve`f)?qnT=lpe#{lU2@--rszp4z z;ZyF9nhssIr?1X3#NkaOk#RT#YpWMZtDhAy5<5mo-j}<3bk-}**3#YzFev!N=U(Ew z*>Kf_F(u_qadFki6l)OG`U+NvdVFhy-Wy_yJ{SC8w38U2KVYnA$8S+5GCOo9&E;zpeyPcGMc#JMrS8wKyjLg%nNGoOc?CYI=v*G=l=OPU0 znc;{v_f3W$EWOtA2YL(tO;>W}oIkVh-p^rBu*=~8{6)^dYsyw;D^i`;eITVtRH)Wl z9I{wE@XaiC&Ki!n)Y5(|8Ne)}H6dP~QYO={B5U3-zW~3$i!0HRHqltOh4+$RfD_1n zW@2|@*KL+U@1{pZYD-$<^3-P~wEXV;S1KPgOGHc2mTMUIHYH1@DaYS>#@8rlHc>xu z&19C(l*rjQU&!mJWoy>w+a@a-l~RL$MgQ@J1n2}OCR^+BTVT@3<>V&w;fLzgRep5zd(mund%-B>%&>2E>R>wS$=hl>a5r_pq}aX*E3_x0(ENHwz(>Ub(bOz!2zP z3@<U;4+VYdT~LZY2Ku0n0lffQa%JY!@#R>3l|2(_ zYMo|@V#Z%Q7Tp%LI9ch>H&^Ayzp&*+sIw*S9}oYvZ5oZLS$3Og8z)^q0Sj65k>+hr)EnI(JddcmrzHKSzd^-9qg+yG5)#huV9dUyQ=l= zY3vO_p;yXuff?albJqM{lx*2IdkLn70kCbia$kmpMSLFgs$9(KP6UzEZG|bCN;;Mf zJI2t^Qwo8nzv8I5U!II*q`8TFaDXvctQmIDieV*&=7(b*_NSTZ{prw^Onb6?kCIEN z$<4!GuvO*ge9R_yx!Ng%Y^K7+W2xCB7_gZR*z33=T_;ES6!Axn2P?)(>G&0hG^e@L9zHD9c)8Z9r6U5N?#{vS-e zgL_`>6D=I4v8~2vY}q%G9d=(&3Ow-B@ zeZQW9ptISDq4L8jWJ*6IJ^2Ce3C`0#)@DmyWbVYA*#Nt-{oeb`V~@0ttI?MnxbL2= zN)-LAvYPATKl{e=snii;G*&T$D1LsI;--z{G_W=ux-bsq?0V$@sc5j4sLvCl?=ZoO=Gzj?B| z&`9bP_;}rnGVzXQVq|1D?LmT@6N?4E+A{ptv0|<&EM2U8$IgoP4l`tWSVTr)?>f(Y znavwQb^^lK*ibMZR9?XIaSO}Is>wUx*FZStCe33vcCq%1gdbF-ZoJV5Ctq(y%E9DO znLWy3i_Cl?vp`HdQdLFW&X}idenKODXzZXI^WmJ%uL7CaxL?yeVpB}T%#EGLPZx;%X^u4<- zkLaN(Q^UY(?oa*WS-JPBfB4=Mt+U!ne$gmPG2E$)k%90E5o%-?%V>fXtu?7XPl1ZF z9cs1_;+( zR~t~^^x^gYw#}@sRqT^3`EjKLjf6dwz-@g^(Yd~Jf|F7Ahr|{wW7A)(j#U*x3ntXk z?h01PZ?trn@r*juf&7=tt&dsyK5|GB$1QG@+$uceAfr)Nzp~`%#n3QK+M0;q<-naP|H5BA&0;eFxJCo(2wkfq?!6?^_kWl!N47o^5`@;RaH}Cv07R zW~a!9_rNOj&%npb;qw$ce|)Z?L8L@3Dr$Rr)L4m}-0n9-(}zQlJDg zg=|PPu|l@D&Z_l>~-%GpVI%1LZS)J5-PLoF&YY?{$C0<*!IjCy(`)d{I%mLbllGX)sIYw>)(k zO%4mz8^Pc+}>tkx7*%iCbW5w>-e2{{2 z?cXyN7-GCx37(l6xt~Vd@bozIU`0eS?ujBK4lJ`a8ssM$A!*oc#41sY=d7Sk8|-(rzqL?V zR_Hixn+FSgzifVd9>y)4qb{?>3lK^TF5qE-J9gH(%;D^7rNdLCpa3zV)jo^gbL_O@ zT%Qg_P#MCCIE;3isgVU~Tja42->(49fE>cK1 zVc3)FzroMzEy9!X8x}K_er?KFQVA`8y)lnIQIr{qE7kJ*k64&kF^^(48Z*u2ONd!m zi=JZ$(vlt~5+=*X&}|7nGrcHdk+Co%ik0R5=7U8G$JB*WiyvZ=iHdi8;m=^Fn=VJ<4cFj&V!Duz*fF}*qF7~f zWih3XkB!~N-!RU4@M>?SAG_f@!Ww+9)Jf*B#o7^n;Yi`IT|lktH^s65h*V6F+3Io+ z!d->wgs06dmldJi8ll%#EyBNfCox`cwaf4QyT#itAhD*J3hkBu}6IKT^V#?B?P;Crp{=w`iSwxG6V)swK zh*bJWztn1TVpuv|=31rLbScF8F#=cNj z??xNP&p%#xfUwx0oGuc5aN~&%#*j)_X8gqqfFo8S z?gZS6cJv0RtNqzQCw%RfA3(nUgC8+x(Pxq+b0ipej?sXN@T5R=^u82LHaxhi)QZd3 zosoUSW@RTLIvwMHa;^bz1}!(d?rDN^T86K7Q|7U{K* zJd*`$+O0D`Fo67@f0qiR>5M(6LyVe|XTCGGg2~do+v0}rq)Fl75S|;v$GtvAA|l`J zJcO04;ft;Qm7W!yw7TUN>h}lh_g13|P5!KRyJ4V03o@_I*ZHlc0|r;r>GX?E&*73g&GR}|ve$ka3ld!tw1n zpS81*Ti0v0c=D~3^SIjSvu`mJi|!f!cOv~i{F1znRAwF$bdzF47rHe)?3+b-L z{L^lR&t?jQ4i-n4-gbHlXA3^R(;E@Mk7)b;O45)1A`j^=pvjX0I{BV@I%=339f8_Z zFG|EjbfVOqe4q_j=4>}O+YboVMUkbeVq|3(2V8%?NclI`^|fXAQRfpa=O6V^gVeC`Jj;+QCG$-YLhHBZhH z;g>SW8`cEz_NGnTXxZ8YsiiY8X&~UMFuzy%uMi2r6KNs={KttiZiztseM-ccZ7(SHV{KR%gK4qgf4fMkxvxd6)QcfB0 z@0{ZaObnLn2vN~ET_!FijR56D|fe*zyPKqOFDIO7t>n zO<-01k0yG0jn$Q-mP~B|)BwAh*cow&z2}2e^cS)_m#yG<;YMF9WKU>DX!Hy`$piyq zBzI5L_0yi(Ko4f#x2htF@ca5JoSW4~O!!Ukp%kF1ja_=wgU$|W)R+m3ElnQ~A487R zCCjur?b?@=D(q8+GtHhqe_9m;fC1Mae?Evh>An_n%P+3t@#uEzjjP)Q9At6TwP3JT zVe16qv_UIJr*mX5TRRN?8azl=>SBtoe6!1`iN~@&S{#xmv_H_N;IQ$AjB4}v;sA-d zuGWv&J>0Y-NzZjY~a{`q)PH#b=jrOj%9xX6u-HdB={`BTl;u9o3W8TdO>m0IPD zDG#$uzGgQZ^8X;zB*K0pQWFALFiKR{J@Y}*mbt3EQ(&4@c@$(U)Qklvo|zor$4SnZ za$v>dN0Dw0cs5X~JobT4C=?s0oeGO0_$f8E<~f9q43ys7#9`u}RM>USa``7&suUD| zT^?0Qz~5_Y8w=M`S*UOwgjp}mlN8O!oS)MHg3aD&@(N_(Y$XkBG8i@grHlql#lKb9=RB5K5=v2|Lc(A9)mJX`!FJ z)nxEI?}sQ+n)~Tbq%pMmS(wpPv-v;dpncxu<1ct9W9+RDYSJ{cn7l_Vqb41{*Pi>} z8+qp+&UpKM^U3EbXJjq9I?uJIQKR@bbpf@8_lm-}6Ku^_W>Y9TYVjrpxNOX@<7jzk!zWSIyA!Ez9bodwqCZV%*UvmB z==97>7q1p$p@=$Hevc_ENR$5ul1KKS)7DmJ-4?!E+tNaO-7&Z+WA~di_l~6l6~@VW zQ5j@4CPT2;v}!J!fto!;*QuL${fYWJ1*)pe{O=5cHVhpa0djR#Z3sOu5hn*b2)zJ2 zJi$uO*4#Qa_XV`4=|T~s-;g`r4?1+pmgzg2^2;pZ3kEpaA`hUuJ3l^OoD)3@^B>&u zMnpMGj5z;T!Z?5$Tv3;tYHzYsuAR}k`-H7%j zA?=Mn358T@I&8br?LI=Mu?R+16&CQQk<6aRE)eI;{rLV)z|T=_q%@G@yY(5B+$r*? zfQ()-lSs|w8+AZ(#3kH|bQFjj80D5YeC$%4S=2;&J0bjVmMj!MB|En?R95aiH_SP;Sj;*P=Yd=!?8_OzQt zrC-HMFeVxYg+8>_&~xMop< zJy?~a#NO>rFblq36LOVSw2Fm-r~KPvG|Fm!H^c6yz%cdhVQ-#CLikkN5XSgwmT90r`nOHS7nQUvn7?5Cg+3Lj|dA{91CfvE&q+Lz>%Z+JOtSR z@W^78GE`AkMkdt`j#CnJAFdoa*CY8Hxi8#)Bf=zZ@8?d1@k7f0?`W^_sMugqRIyHe zBX)xv@#M(8Zo-(ofVwvmid;oTSG`|fqce5O zLu%MPhE*JYaV9EUXm`L`rk*VeE0)-8u~yhh{}EM04rQChdIA5Q*anI@Mf zHo%lPXD|l;eYm@l(kWEG+dil6V92H9XU;m_79@k&XC~<6yWF+JWWYbG_{d*Tt#!as zT140wG`d@{sdW~fJK?-OW8iK3e#%+dbSXF!=w(4I2B23@-v>H&`4_B34^juA+Wb%r z#>sQT8C(0Qyi2J{6q4gltnC#7`*I5B4_T*~{k-|UPTgHSx=jt|JJZE@Z=tAMd$2t) zQBlW{ts0IPlf-Qaq~*IiH!8GU2O71IocV54;HC)%-z%&5`n<(Eo~d(h2=JvB_WZjN_W!Rzg7gK?)&-$74U}WT z_PTf|oz>Yr{nX7`X@LSlVT{c>z-k4yC5bM!IGaxh>8jpk34I?H(#Py8$SFN_j)ep9 zVsD`>dAS|S_%*BwsvzYDF?v>I_`-6f62DXc&)W7(Y5}&EA;e@?0Ms6w80)nd zLW1^-^!vovDFou%YA-Is1_}5qlEw751NkzGE;77U6k^1S0@m~ z%A|L;i#yg*q#zU76D=1DE^p_Qb{VJaxJ=={e zdW?*4grWY6$%35OF53GKnRl<_279l_vdpMQ6#4n%$QM#M$bk@kJUW^|B1(6*Iu+}6_{ zbJV$VG1Z1A&pMxfl1e`i6!Y<%^^%IA6Voo%V6vIe;Nhv9PRXDUxg_1bpsBAP+L81A ztB}7p1%>_riXXB5tPi>BWM+D{WpTpdUT7jdmdx6hk9hH6mHwL96@$R_{;Al+ADd%7 zC&Zz{L*R0*yp1Cbgzyy}3>TIyH5p&xV0^)U=6s*?{%+aQMlW-yxOPfXLgUDN|%GvYHUs#S9n||o|xyI9JY3UnNuH^Cq_16(|zc0Xr8S0aW~sm zMk@fdGz2{GB~ihBb)G#{B$bQIFK_rC|Hh!rNZC&t^B&RjlamwY(9o^TdhRc0;h;UB zKSp8x!g2%`q`((GvLwkkRswc{$h3MPb^Cq@7WVGc-z>+Db(QS!%ivkkel-PXu518R{;C8^Wb@*EP|xk*CwKP@h(t4M#b zK2a!hG*hMuFlvgG#vFhclF-^#XJxh1b7b_$5ta~u8z?3^(*vO;i-pQ-N3zRATS=KA z@^_9Z5e{FAo2aI~wARI;@ao)y!Fm0l=>K^ENS6)uYKwCv^}Bl(FnMw9>Fa1xV{;*U z^4+CgeV$lC#O>nlM`>`A?enf|v1)!eqsd8Xo~NWNSb7VbMxXA8(5^M~y4;ZXThmM?DviLD2AaX8ZNZUHP5C=fWxGNx}8 z4_It!FR}pov(C982Y4m%_a^qWfHnY`16=lS;k<;TQb`Rt&F-O)vpsS`QK9_s6f4bc z^!X{xjcIW8jFa3U*0R4$ZAq2nY;77_`P_)~$fZ~>$$0}yRO;25&^m7z`ntXdgB#h%kqCS8BzNMnJ-7aUZ+TCFlY8%% zPgo!JL`0Y=l9VKhVt!_t)-^@liq0Q!jtHQ3!_YYVAV!v0H>-5`mJL7)(K7rL(nOhNw)1T9^a%&Q~@bdoy%fR!HO&9SGZUt`jJ)mM?CQB6k$^$Pg#Mf zvw-otR6*1E47$>xfeEN?s%hu^qYv3`o&A_fL2x~*IhF?J;nss%xDoGWfA`LzKFR#| z#K_Rup~SzreVv_R@6j~5v9y&7GR_J|%12J(fG+s=*AjXX%nf?I(ro_;tRs$MNwhhc z7vZnPqLRORp*Ro%9SU_cizi$cYr2E%??ZKd-^cwkP1Q0L~WQ-j8hnn)%D1^D>1(EM2R_dhO5@v$54(aNltpXe7;Ogg!Vf>)Ct%JZ#57I1qO5PP+ zM8)|+r=yP~Suo$dV^&be{=@j4Ig(6hfK<5IXRyghdLbcTsM>G=hm)`ZNwz(8k%rul zAtQ7;x)M7*WA-cb1>IrN_fS~5Qiwt%W!zDbNxK<^+X@pZCMJp77v94+M*F?z|J}cF zgra$&Ke=&IbRT9dGyzy0+CZy(l1R(q`>t&WHDB!_jrp4{eW<(6hP* zE8aG^ZpPdCS~LIncFL_FCqlet86-b*#g<<6G~P|=Yu{XBMOJi{E^9zFvBGCyKXLu@ z4XG6dnlh5!89Byal33A4kvqHHx-cqKMIg*Nf*Z%b-GLq-fjU?xKkw;JYfB0Ssxr{t zo@d=55XW{XV&l%;RjydzrfCXgrb*ssunk;%;kg)mXGTMtI9=-X-ItuOJPf#le||g< zzWwyUFO|(7sm*V7ocf~igjNJ7)-a?8s9QvMv#kcExQu{mDZd213Zt?(mEM&Id9^Gi z#r>I;5r(9j+JZWJT3jE*D$|3t;u?U55b&!WT3SiYhfDdz8FQ8^@YCU=M^BcP7Khi6 zlcF6O71=DnDcv!R4UbYh{Qz1?!O+5H#~pzOe(vJ zQWAG#uso0fcrt2o@`T;PwCNsM<#LnsxcFJz+A*KCac8rWxKyF9PoO7EW^I?_Y@-^XTBCaXK+ zO&AEelo1cTSDNr`eqj0t6a*k4Mc4`iquj3nD|cT6Ev1<&hrFYhspF^6N_RDDX06^j zW~3mFSG!4zuO?7~Pl~l7sB{QjT+K#4r?+3Z>#h-bo*ifTnk6TYpoo?6F2F&t2CZ82 z(;T-~)#j}_RVT>cWdk_3mH`&K2#nq-@X6-=-XYug-CF1Q#k=VUmTB8%LIv(aKiDc zmb$EK4(m6NHh z({IR8Kz#w=u&q=_1IQi2BMV8fU7w((b2*yq`Y+eSpMjxyk+H)w8w8;+xrTb({25`A zM(noVUEdHv{*64nA~_gBP`+Fjn=50Y*Tsz-iq?0+Bu#mj-v9e6jl(8j zI08enNkzevf8c?q@|d6p|C)G1uwvgN##U$gV!o7dF)S&(dU2QxgDx^WA1qmXJSVev zfGm>X=#-G%d$EhxMH>CKR8cCxCUB>he+T06eUFXpqht5IsT**zu}l?@&jC5=Wb+Q7 zrhVXiA@Y2mV$G3xC7hu=o6zQvUy`cjC3I@jXbaWCXDxqeMYguR?$*IdXoDH~dcG8!a&XuCw_?q7^;UbfE&mazr@_-@{b!Z1VZ86T?t8ungu*LogBE^wmT0^Jzm%84!#y=|VrgE7pTGta zl)U`%<5jH9*QdqN-N_ur;@)t}`#aiFHjmkgI^W4l+|t$gf4p4JnpSGj9!_rBw7r z_c>e5srb>0F{Pz)5d4&h0x1lzK0U7iFpUlr*33uG43<=>n8;s)W%qskiFfh)wqisndHtPSJSyOz1-UG11H z>dYw69?cRcPHwux&;6~dRII%3E`wjtyNje)^uE>dOLj{_s*dSD)5oWq?XFTeY-iUe zu{KV0ZLTkc=OiwC1ZMGmS0~ki@^C0Y z<>zO`;zYfNrn?3#2CL@N{HM)MTt+`3Mb zQPBFm<+V*QvoSw&zHux?{-a{9LR;jX~)bf270GRnqGg*@Ra*j(3 zn)$OxhB$^w@KL2152gkDjMB%B#3CvU9SmhOJ=;n?orw(Je_-hV5$0VkMRIZMM_Ax9 zctr?98xf)UYqZ2D#8%JQ=kwpJrRY(uICYWJ#QD5Ludr?SO8t%=iOac$kSK&xVLyjJ z92pZ0GaJBM(?yuJ3yCF=^?Bz2ZVmWAYv*~(f+! zCeKmEn4R67N+|&8=nn3GBETL((d_B7)ig|B6NA`|G+z`ZmqW->5DrgXQl?RbjF50h zcRI8yg(KKPiNRIx;TKy`OXrJr^)+g4nCKyq&&2Qcg6mdIO=xxaitsuiViz!>1)d8W z^3xFB)5xTsgz`z(?LL7(B^sDn4gwXR?>U>0sy^TNU6;-!;`@RyF5|RwN<(~b+wBxA zvi+RvVIg{xtJJ{i4%I<$;tSm|U&mMER#VR!BmKJsgsB^Hp$RAVGOalSUeD{(`yE$ic`j`+Z;RH@nCJM;SD5*Jw+@ z^a4$VgB%b1-Vua6`d+oN{UspGCuUvawXB;H}dz?h@iRG42M&yv48>oqxF7icNV{vxTKI#DF?zF^ei^ zPBrCpWH4W)T@rIg#2L14^>0qk>yLJ*M`s((WleZkPpMUNLz4Zhg}xz&yZuzuKXCNw zhxWW@qzEe?_hV;N{j1L5;>1!5EMIg;Zg}1?roGIoT1Jk^>lS%69qg4BGM;Maxxx_b zrYr$}iX6m0_^Oey|8##{RUy-~Yq4}Ve8w7%vm)jc%sV*gE17ipbzoQhG!w1Xmj*<3 zi#~LAKfdr~MigqBWiw>JM;4epEn(@=#K1d6^lh@!@)ZW$^WG$g`#T8mKbVb;|ExAo z-#e&hbC+=Wmn>FxFTQ{?+S>z;EC^w2133sVWR)M2?sDnQ~A(YobFLg zJHv6LN*(HaZSrXWzYRZ2&^UDNjfXbh(r{@wA3f04t(_b~O!e}lk)2Yf8BoD5-mKBH zYibhEsVP+47pCK}>$ug#mR0PcCh6?2spuQ7d@JE3uTOB4@Jc0ObDjc%&?vv*vS9AP z9#FSh{Va){7nRuCXn`?rY@yeSQd?uc;uW8>gvnt9)m28l{GtAR{OIZdDY@^jFBaMB zw{5SfjXcgrf=es>RNqz=(r1In|b`uz5 z8S@8(pp8(<;q4kdqrMPsP03X34B@Dnu({Sn6emZUzZ`^PGb7l|x5;|8&t~-B!!Knz z?@A@6y@JQyU_ge7Wz0@E!FhPHy3&KWsj$b@(-X7fsnJ_LUaeAW77CAaJ19vBZezB5 z-=cR1BaMxWgg4q;S{)C@+L35Pz1z>YZTeyizgtkNRnpsh{$!jY^4Fo?3%yKciW}$r z{2tZ+wD~7OzYIv0Po8BQ;?812kP$KKLCE>_6emHx1~V8M8?eGxoo`uJBSZJ_={EcL84w;4Lm^>il2tPNtI?gVA^# zWq^aoX03^wm$xHNZX6vcXVBR9h*5o2l=ht9gwa+xgmm~8Zn_{P%9`Z#Ysk87^!(## z_7v75`FA{5!y5|4Ti9xk!gL?yu&D9S5t8A#8gXhoHmnuTxA4UCg8AO9TyRv?W15ER z`{UU=y?jp^(U$0OlMT>?!qVF7Tvre*T8*AC6jE$JUtzn-%VXiQUC8-S^2s*o!Tn*8YDi46Dyn!3FV zfAdvkX4amg2s{O3C^ywNsbXPM>!|!pZJ|uy;F?~hx&7ngbZ)(cFPvoB@|wN*JH5MH z7m)h?pZY#xIyyS53I+xSzn6E2(j}LB5lCKtc41ck;)NTCnV4y~AQxi8bqM@tJ&Nm

<@FN&CwBx;+a!}&7IKmc7ndi9&FcG+ptct z-Y@$4K{!hLBg*YYEcuC$`MW$-nd>q*_Q3(k<^lU_9=Iphh&|r5@I81qiK@d;S;vYH zfvMNOyHQBtG;*u1+AJbNtPGQRuY<5pBf@;aDX9cKudf1pR~%oO&@&?=VHs>zj=KXe zZG1#~h4Uwz4!aP>!!dLQXUr6woalp-A|OepGte^aB#_ohhuDjM(4)tfSzc@KAVewe zZrUoXpNr_1O0LSw%KMN#tAYUqq7U`kQ-B2Yz;tFA7d-d74yWmdZ%t4c zSEb#|Y%+qZ{zpS7o7+XB!5n3+$!2e-KeT2Msw+G|5mle{jHdyK0nKb@g5yUjR@$My z>rJ?1(a{xFn3TH8;zo#E|Cy2PdyYV;Bx=wmN_KC)8!^A=!fX0!gl1c^r@z%?K+|m? zxm0m42Q$pp2pJ~6SCpLzDhQ#gsjQ`TihOc*{P-{P25wg!B%__1;h;gdquQ)Q@^Pqz zyrMucAzui-E0_fJ@j_g-cvTu{0{$SSn_WnogdFRFT!>qu7!a`gllf3!jg#qAmXx_U z)nbL(-t|s@y5lEo0J4DJ0#eO)Xc}jt_f0N85OM z$N6g&*y#*D5e0v&J)FH0En^fPUgjto5b?W`;f{(H)L$Vp$;9%_apWF>+mreG&c0ND zcx-Qrw}J;#QwBb3lRkEt&Hs8X`#YL-hC3a8dTj;dH`i4sKCP#nf z1W{hk??~W3peoA^K{=6xRY%J+`MP(K4vXNn;W7{1fY5L@FYXjS*{xR;FRm z=}OglXCf2_n?9_D`9Rp+^zwBK67dJnGogrZa7>&o0-5Xnc$DcCw+BB?pAEvw_dPys z4ePp&wm-J}^Zrx1v?H)g6vHp;?m)f$@$g!914NfJn=Tz%z>Jg`*8B{?DsKQ+<2ZFog2TE8kE^t z$Gl<^S@_CZr-oZE!^Y##uk-Y|YW!rKs=M=5BCrJYNVmeF|7@;ljG%8{K3X#r2e{nD zsJSuOiqOz|*DpuQvG__e6epv^uegFf5VbRCL^whV*)k)bu_Xlj8b?SyG}I}?9BydM zW(=z>E&n#{Y!4=`z|B~S3}LF@hHKBnk+rge{E{SzYIyIGYF1NA4K3clYWbhS1)RT0 zk?%{R%4a=q6ZEv0uyyD9j;-Exm9cVztg2Ft?YsV>zA#Te`jS^%u7@m-|>TA3rchbM`XgWzB7u0%Sj=W0oMNHaqNAjoy*@%9h` zc(LoWR^2syk_%(WWr2ZA_KtnF+x`LU02b8|`VacP+(6V>exmNy;2)%y!zHHD_Rfxx zDO9V(nHLm>>$D{;U+}~&2v3O^8V5SGI#T_qn)yz7Fk%R@{`HO)$=wKwQYR(9cstCc zub$;Atz3cWpX;ff?{@K|U(j1)C!lP*fy#gm%R8O>_ID2?EYq=)kg>dH9!J-?e&}|Q3mr|h5 ziv>9)^$*UtF5@Jr`3OW&{G&OHH1(257XI9gg#6f#WNti2t2?j7R!78zdKZE)kD!J0 zvYORGz!SdJN;(OeG-{HDhsW6U3kPc9;lCnm-HtiXu;EtM%vvDU+E;#*hJ!ktgE5u+ z8#E*)rc6XwlG6b-Glvg$wLu5ys(m@H{TGkCL9b~ody`xb%$26<1PgyLRO|i;Zt;)^p)kKM0#DQyyFH7?6y`Eb~pM{e-Kne0&$Nc`eFrq1_L<2-HG}nvP*4imy>TD zcY9+Tz@G`iO|YcfZm`m1!>?T~p|F`B3%Kb!d;^{jj|6Hvnlj1Iv`eb>BI9>L_iC)r zP~F*WxM7B4Kn>1Mq-Ia%S)x#j*1MwhbGt^OqNrTnv4KBaa{>HJu3h^iknypp_y6E3 zN0#Iudc1Pof@Ld*+dUB$y}lZ8I8(uDYm;Eo5B!(e&sSfBic$Rdb|&AAV?m$Wj6Hyq zqf{nQpM4i&0=(dL1m8~49X0C-c$~Ek){TNo6ebr~5P*K?Wyt#au3YdXE-iPUwBad9 zO`WvdjD@D4KvtC!lt>9f$Uz7)J)Wwlffd6&Cd02Z!FM00{kv{C9gnF~#KUvRS*BT` zFC2|Glbygu2Y(1-OvSq&YX9&M(xfhDU7QFs2&vxX7JPf5-#+0o2RhF&lAS2&uGIVf z+m>Eu(4CoiSijjGb)E5>wu&f)TE%~}2>?T)^h3SNfhb*eNTIW0rYixhT#KNPUGHd< z2lKQqq(~i&*8;V?tBWcEz1Mfb+}hJGXkq|jF%X(eze{I^;t*H62C9h5Z_Bl6PG!N=@mXNemZ%;4i9`i4dIBIl_Mq6O`ngxW$?ka#4#UFZl7pLhF*5{|* zu6o`Gwe`!Ce!H6m-)Nin;mxyBIKuly=Tu! zCC{?H_yP{wrh~%bg?B`HO zePtST{~lRXM>OYZxcis%4%QPT`PUp13(+z$J%@!;Go*J%6GcDjpbj?Lfh!esA6abf zTYEAam?oDQrqKaW&+QU7x^-pNOzOM154n4VAWNTf3Xfh@XDdd9;rlDwJ!j)S8 z&+{BU5Dk~hcdek+qA1F6;%P;G-zd#0El5Mca$JJ?#|`80MZn#J?uheo+QQPNX|be# zZ9IrW)U|RIoE^-hThSJ0e@_K+D2Kb(QgB1JZh4CV&>HA7uY$Up&n6Bl* zRPXx*_XSwuuV3z9(wQ-&$_F}>NF%P+D|-F9BEIl2En!^sY*-anx zQ(`Rg|9JtlGMuJ7B^X_f2*_YU*r}!#9uHtwi*&?@Q)k;#ctTf~cj8bbBKpFpbNFV) z_LC4jWEZmE))8X%Tov*EeHdSRVos}dV-xa59szJhMu9JXRH0PE!`1uAi@~e}2psWUTk_tMhyrNY>gmT7=YMLi^{Vsk7beZ? zW1)nhfT?U7MeM{bs}%)*c6*%n0qpGAKNXYX8IDUc8_SW}kU>r7^~}0VTjrx}5mj6| zQ*kH&3TL=;GuAayRJ`J88ot1ss9j0}>Wd`9BrLi$%6JVH-k zSYfq&0OL1>{KsR?10YdMQwmV;0>kFw^T-#vw2!i%saAk{W zs(->poy@M(^tk-|GNb9z(_kNS67z0uzGd|54z z2mzw7kt&bC*B9G*LcW(^elU%1H{Gr%OtI;B$~wu(yGPN!3A|1gHMjAQ)zlVT1Ux~6#lz__@X5FwMieRS=R%PhRLmNa zfmf>{Ubh~O5DFyOc(lev5RXG&ji-9lsT`_&J(x`itO1 zL+t&jQ0o#uXC^4uQ>}MpH7JggT>r8~x1k?jf@nr zXTLbeIkP*q7aLewE?+39(&)XeN4U+ufVgo3%`e;VBZooY=Tnz5lmpv7q>MHdAmJWcD_p4yIVy( zj#WFF%3DO`v~*tefAljpHXSIJnp_rWLTMN0*xr5~I)B#pVfR%|^(4QLTs+orSxQZT zliwpsPBL!)J09stTDerUb&5O+kKmx&fDGUiX$FSf$E#@uG^b#@C$IRtImN}vjO0K| zBkSv(DAsq5@KX8w=qOPDX?X-ffuyNdM~RK6*wNch?x}jdKIHcYgHJm>)qJI#JvtV7X_NdQ~$+4T3Y4@nhq4rA4Y-CDjfQ zsIl+0soB(n=Blu!(We75k4MeHb7kn>+)dDl7$+cqo+5r(83~EV{)^5O-?>%8`pFo0 zl{)}_cP+ zD3S`J9sgW;HICU{mC8JIU+SgOXM^3P$TTLX&OCRR7}CRzAJTonuUg7M3LXY}p1Hi) z@cA%t(xFCrKh~?W>h^7SmwHnOKAUgirJ>j1t~_|%V0~gTXEdc+b9KvNdRm7x zmKifOkQbTyD>>Rr&+e(ZvC83Je8w~%^8ZQ@K=+2hg_P$0-tE{Jp?)xxGJ}CT>T|NE& zWk?>*B+b=j6~{nrkhXH;a|;U-Szqi?bJ49TJUZWJLKk=UPJEgCS>(sVOx9dJJT=L0 zQ|mgg0xwDTZ$$PRd4w6FI~^}30(bC3E^2PX<|zB4NxfAd|4I>w>)kY1N(^!Sz2Jk-(Mp_fayAQ z6-bmDz|D&<;mY1x)1kaK;*?gC(`qgy_t`b0N;H+YBJ-M`TUr>VA;%KyDYeg zXJ@4IK^c4}Q0*8+JHFrjMhMcyp%eSH;fB_3NgfY}xh>#I`wBpVCfi`(c!A*}AQWdB ztivU)HiJ4JmLOHs8v`zBxS4Cg}Hx z`Nn3W#*J+^wrwYEY};z=G`6kAR%6??&)xH#@BIH<*PZOn&dd+9iyY~*7`rw0>T!Mh zo8Kw&rf&!3*}|Jt--b_qclAe`mf5WG8kkd5BU3@SJQ5G`IQjx8SV$8 z+tG(9wq4L*MoffR(|WdhTI>j+ZUw}d@n-r5XN_iJ|2ueNShm4gtmtj=fmqlbiW`+J z0e`Ed$bpm;-aePTL*7)^EVOWp(D~d}lfz2I*`!S8u&Zokn{ueEurs>#Jp} z5i6{J8)2fEJmPi7G|FKoI#)))6p6iP^%`QNF2(fd)e2Eeemn3)q_dcJ0-iz(HMZUN zd&3=@3ZuVDBZi&5>EtI2QXIDnK^ST8ToEekah?{jwY?VHWkrm+x)qaDa8JZgb)K%q z{%IT=i9e7=<3`7H1r$odbRY0n)GBGBS?KiTfcS;wCZt!dD!B~>pfKrn*~XWM2CeR@ z4I=nO;;G$U`v;ZRM^56HH?IU}eT4k)XEy>gh?Vk>Wj@{mOior%*2PHV%v+4fxc}c{O?*u+t-Y@DmEO$jO?T=Y{ zUV&bS_~N3(nTayP&ViSekFDC6XATTtOlH6cUZKY>YIS5y2C6{A z7|Kh1Jq*ToKgE3FEmf z25S5pIgb*qh3b)@gP4oaGRhYg&TlwCzyQC1?raWkwMJvqTIUM*FC0i2trjc6kbRM6l55$@0BhU;v zOd+ZozOVh7nR`_~^^Ffb0WY4 z8A7&y=+=_|mR`lsa7kHNvUOKZDupf&_**3jIf#~xdh7KC0=~+Yy(3hU=t01MR8qwk z*@&y;$;vvAb@;a*PSOXp@g<3w0ZK>;B9264DRCxd8X1y z*^7t&oKquu*`pKNe*a^GeT;VOTDEji=6K_?8vI;yD53I?tf`( zq%7=1)*10hbV0Eto!ccmoG>7Hd}HDz(I9wSP+9-JKv6`&{N$nosvu=|HQ=xr#rc)9*_ z(c*Hz{*@)|#05N@r{uV>N ziA^7TSy9pGrrN^aaSpG9!)7cbQy=<`(EEquy2;e3ETQ>O`e5I7x2IF|#pm+HDi7Z7 zn=thBexp>8M@v>wd3i1BcZo5amw;Ebo1-%LS3;B%G=JDnA!v2I;rEUHG7)%39Q6aKbB9!& z><n+^n2-xd=YZ2vFOk=V0<*y zJg6>c?RYf@r$mqyg>tJg9o%}!Zu5l0X$EzWpPWL{yjW= ztiz)zj#gPjF*BmnmcU}b2N1aj<%UwK*FBWLYdbJMUv|qsx81`M5xF4~28?bJ@2)s= z*3}CYl6pOOK1G#e$T18Ee0<+HwFhl2R}&lBcPW~J341G9HL;jXnnlRCWD_lf42Ayv z2Jcvl;rmMH&SI|Swdpl!<7MA*o&T^;M@>>&J=QFbi6=E~FRl3en&XOJ+mYGeIcUW5 z6Fj!OiqvX*u@P&lu=_*m;?(}js!guS4vP`w22kQx+t>n>!pS(WZO4-5@z8k))4w4~5k?84Pw({A_atD{Tw7|PO!C89XGriK)F&}cNSM2bfx zwjpU89uM+i>fo(=FO>VN6HPW{&!O7N5o)YJflMo+*Iy zJfG)YKFrrW=54-X%*LazF8=SgJN+sT-eNW7Z7ns>B~-FkREH(24Gji)5oxsG+h;{U zFz7FuXy46a!>~xXdph%eX3~N8XqWG73(==dGeEynK+|5lo!Pq-Co@{BP!8&-c2|B| z2cM<~F@(SH`rA-L!($OZD-L>o$LQ+IKXv-Vjx-#Qs>^YQ#(>ZFeIkmrTgUU1!j5L+ z&%Tk(s3qbFVPQbVfLF6seDALd+R6O*Y|E(Htu6{Z6Gz2?@jQ$EI|z zj}W<5fB+oNu|3n?EX_&(zAxe1Z?U;4 z6jIPj=<#dH^M~*EfI%W7=Xbwjc@H6_yrt8H#u_}myN~ zO5rszxZKC+ml6};GI`VDO67Hb;43B^KfK_LR>&puEyPyE`(X3DkHu(~$KF1hrC`R0 zmu_uz&G53fV18sf-^M-nwxN5~e2d5D3BA7NW4jgW)L8p}o5=4k<9S1+=>QH1>)wH% zexQfFQ9@Kp!25lr^O0oL29p1Vkwl(nJ+2qeiQB;A|}JaP~-XbbZiO9r{eh< z@4JgaVfSKz59cm^ae~|1?)ulhcgXVW_&AdQz*Q6CPaUyWxa^2?le)h*U5P>Q`ab^Z zpC4=+`Xdb8aj!SDz`?O-w4?op*o*#Z5Z=<#JNAKR}wfn>7ekh@Z-JJw?X{(Q#LWvyOeBHFz9U-Yq ziYU!#^G>P;@7vI#xI|yO|t+yXHvc z7LSU|Q2v8mtY`qATl zYx2!CAA+y7Obi4-v-7F4J08^^jPbXJ=+E=uDXKwKq!z4h52q4G<<-+3r&xau$L(0J zVZKmdJZ*Y&R4!Cgz6CyBx4M(3FKJ-t=~3}c>eNW5(3K{ZZC5uJ#>JWUZ;DJfE-u;* zrJTf>rU4DGP}B0&(HzWWo(S00nK$Og?jTs)?HdB8yn3lVXvD1GYHkVyn|_A^pM@kV z%1Q5|CE62+j>3vp5sIwLY0vLo-7PfIyh#G=hV5!HmcYBpl78olDgVe0x2m`G-x( zV7m33;4eMnidk0lALQ*>0q(?LRgWF))DVje4w$jF(iI-t&$VkUPzH%ZmxCIR(cqqK@pX-s&RxD^ zc_P2%v!j0Y4O$I-XU9*APk`a8 z%QJDq@-;HhBlUbHfigrTB4v(Tdyw zLEss~Tn?#hTH#GRw(6->xVT{X?ij#+F=h;1VV9N7J8Vv{ACFNaUKqY(D z@kt>}w1Cg0+QyZpO=_?f%F5I`Qpd_z@7C+(qQp!(R@Ae~{j}|Qfwj?uD6**_6|pJ( zWfGF)G#Y<@DiqKG~&&$PBo!_eS zVOH?xVTFFbOa)yWDYA?uNe^f$2yV1rf`3D|l~vg{`5CMyf9twI z;yjKM<@+u+k}n3i<|yCz3eZWyGwR>)lc%xu1@rh8JtTqdp{HdfJZMlD1#+XMkgRWG zb9{3|jE*O6z;+$)ptBS%Jq%Xs?Fr%-S*|}jLHOjT9nN$2KQD2_>T7;r!RI9Y@~_xQ zOXXkf%7b9jK4dB#9gG8bj~8j;&LzbxisIe`BOSxhbQ87}oz1>3h$Q z)ji0NQFK#m4?BouVP;!lc%<~l*^nm8P<(X2NbK-*h&2wK65PDng%L zANl+YR<)aq1s+So-I`&8thUxcEln7J_68oa6V;I>QKk zL^f~ex<3EK9{;B`C*{h+e^_;M7ByO__W&KLg4@d-Uu4x$X3x7NHlZ+lIEKY+ua53^ zwvKEm3+-JShN21EageLtqLMx#J_$zpnh73Jys zk~kLUL@NcUW?(MHA6lg%k_z7ejfL zExLxCah8I+1wSQ!VfFSeRdkX7Eh4d@%_5X=)w=ER5A+*8!xP}*eit_mHtq)6(3e2; zcqyr?E}wqPtVeasY&=Y$Mvztx%Xr!0R=@pBx-(({*16MLo6%VVzfPL&H+BZl6a9(h znL~l}kJ;{OoRqM#_?wrP+GINvpA{`!Jyh>{iC~u~;ED9iVs6Oif;dpK&HFS#G-@kH zMEEx%qm9+xPqRILCPY7l^yprc{;4h@{;_+;^*rL-g!utd{W@q$mLs2ctZq0vP4Wc- z{fCK3uH{U?@DzU~^NVZiEZc0XKQxrltKI}b1WR$R@58Uo%hKCUzX zCfA&8#+tDE(*eymES_xeWf9#NZWW&cAHlSxJozp+?e%Dy+06{$MwqMt4AV|?R`(lF|aSB;?`@T=1O^3cGn)Xf?8 zbttM^xYx1Sx&JeXBS*t-$e{tYFTwWC=7Jl4$Z z{=YtRHw4H=aL))ZYhk!_3t|SH*L=4Fx z9lji@YpOjdf+FguT#=P~lj{(2i`qq&+akk#Y}G9o(c%u-zF@m6jUY&wR6!u`qa;a< zHrtRG&zgYJJKxYg3M3MrmoP>-Y=!4}qn1p^P8y{Jl|_?GUOGGd*O;vbrtHpFGA;Xd zXk?^JHO-8L`7bNvzK~483YNsil=f*kdOn6(1?SR@5lk|poRnK%eLX6s*6vKND4kPy zd6{*1Z@b-qC2Vaa*XJNuzVJv8aJzlyEkFA1lndj_$CfK}CN9I{lE7~W{vFNGe(KNV zf;K}-vTy*ya1`}@gV~EL_iyH*c;vB| zULpxWZ!h2VJw!R8_~dN?RU_eZJJh`FbV_)8U+mU(v-fqy`uSZDOa8+N6fM=eQVJ1< zRH4f)HL^3X2i*JwLe24xc+3?_VYM$8*?U25P5?;3k8XcYB* zq<@*rI(=)@L84poNZ?Q>G8fD+Fhh(jFm{_4Bg!YgUHzatsFM7$y4A+n1b@8~PEyGg zZ%xiU9mwM;4*n}zrI7|o9?^20N)4@!%HgIceo0vg0IQM#L_RGmwOkCHqQ^TFRPS#n z($YWS;j=F}(vDdM8FOWSbWY8?Fb6j<8Ke9M?IjVN|2*Do)lmt6(7)|Nna6H6)OG*s z1<>}!dbwDK%i%eUkh4wgdioOiXoj{po`ET^u5$U93kp|?C_ti7`6Ss;FF^Jk&tl+&qB%iV9mJ{OVZtQFL8p* zr_4&;tUpj_dC1|rxgzLGF;u|)jaT#R4^Ms=Kha|D4kGe;u#;`Yumh6X^AB%Q08@1( z5UT5LVfopCxk<7P!jVTZo8r$hRmn?i7ZyE79zM<_RH(rVd}ih|U<1{Kn>X{S)p6RD zi^G9xj2RF}v}P~}g}(gbX6#z>`1M9j{prS%Rx{Zyo-Lijyt>JvpYao^-qq!{5<*`c zc#ES_d<5YAzGPZr)m?q)A==?96+2eL6-Res^7A*moleoLW@{o5liXLe3nquZUGOA# z^T$?&x7VC>T6FIf(;$SNpqU$zl)A?D#;1i>IhyBpKNG`ypSSU8AQ6!t4qyXJUjEgc z=wcV4Pl4Ug;UIpxPIFXS(UOVzaHechDj~0{xAs@$ip|IJZ}EgkH)a$0dqZNNGpmJU z%)p`R_sHf2tJcP|YBm$u4Cwr@%MwLEo-xZhsNlb!^GPNgE;4RG9wVykBsLTw9b?|t zmRDUE&9&W?-&$&-YN&F`-{D1nOz587rrspu^6wdpcEooz8-j0kX%Y=`GaQEdtsO!#1tky4M#ju9+$;*-X z^OXm)e%%zKQkA-fOBZgT*~xbDZu_TKBYkl2s&e?%V!g{rkF;H(iZ(!j??3R=3=HkM zF6st#erWA)N~4t)Tn+*cAo6p>n)KPm-W*iFx?f&SS?FfQ04i2KmQOT$lM5k^RfL9? z)JqV|KRSb(CITzcr=p42PBzZ;IihlbmpJm#gwcD1C`Z|j!Xflb`XEdX~%PnK4`+LeDakD8^;zgtv;N& zJTb-IYAVP&-HhAc#8Ih^9Cgev#W&A9hw)9kNmL>GS!P_rAx{6nWR|QygP7=2-Ts)c zj!N;yn)JZ?8FaMsR{OOj|BghtEkC^EgI^UJVAa~;pXx+8oeh%-m3|TFC#=goeDX;T z_J?!M>T(=kxf9QLO=jLk2!H?z6OeAgSFdBW-*mydJlI&o8}_ft`<6dv83Q_4F?Xt6 zWkAGH7g9mpFjG3%5{~+WfYQjn66faMxxg2oBzY9c08#)vBL}|E;K|=K1MaU30VRc# z$ScbAQ>LeAR^emC(?YAUKP^Q95SsyBr}Va!>*huhUx4Ve)|l%3J^W?oRvOK>$5-hM zY;A@tpxg+&hEo)1+ASJ4{1$#IIUHV)*iY(Z7BavV%#~dtEnDoe=_l2KMxy!1(|jR7ieVH0bQX`Y)DjO7!Cm z;@fpG##MVOg-^2zmT$XK#ItEE?ZDCVD$jzoU3IR?majSfo1HZjO`h-@ScyorS9xub zA3#)wz@{tPXUG&Lc>kd2G?&Sa+J4*=%KNg_^s4y!#j%KPJ#eceEtDLmHNq)&}nxjZZk6SI~qTf zo(T@%2xc~Y0*k~VxtAY(QH4-a-L)nDO8MVkKfgJ%US=`@5%VH}_PxcSw~IT%0v(k%E2R8M)Z+XE?K=9I zTsXE54`NShIVt{cgYPJi9Uh^mHx}wDy;TiJvQfwZqx7`)--f76rM7}p$Dqdgh^p5OIx0uc2FI%c20dfuWX zgIgWYJ!jz@KH z|7^Sk0X`Ig*pTBBWhQmSL5~ht=OApF?iW|_9}HmaP+Jr;sgw!_k*mGbsN4nEWgtSM z*6=$RN&`MO*urWCfQnNz-M{cMXw2mm)Ns8U zU#Z4gTe~EmEvjPeX3~?G#1Uz5aa4t9h3+-^Og6?mIA1=JaqmK*Y$+>)crpx|q_^?3 z;exOCUd?rRZ5tlGH<2A}d5Z<&eZ4Pu=CRLNJe`s~ui+N0^7KVG9xx;7_!^R8=WzcY zR@q>SBca;9TBa)fcLd} zwpr+22vDtDrRY|EO^&M$)pAiBY|IBMu4l*{roI6Fng81mj-yk(-uuRl%caYn$IPlr z4*niVbv+k8K9&C4yqO=#^BAtq$~FA?1fmh37eeP@dzvfBxV_y^PV8tr;q)Q0T9C*8 zo~z!Mk(gYmE4}d7a?6QL|FdKfM=kX6p8(tP4qmxIUXIyUw@LkaD-W>DfmCWQomJB2 zZ+4xSfEXl9h#UR|meawJ>2g_mdGuFmQ)~W8iAs=+cZ44dQOgdk6MoFYQCn+Qb~~^qVobl%($bFWL42E~8vnI5opcWS$(EnHZrj1w(-u}l4|c%1AD-)m z6|x6VI)Ay$I%Krn2>3IXSn~Of>|GqAYUlVuij3lB|LXV+)(#K5n2O2a!zJc0iRqw> z3UHeJrMhLbTl)^2Xd8=}$TWZTIS%$XV&W6s@{EA`-;k#>#+&LB~sT~`k#PG zN~TpYVU#D)U6B&q!Q*0z$0nSY{`nl=A`6E&4s+y$OyOF#TEAxXAxFUY z<@bewUj9GZi6gyu*%ivVZ$A+POLU2AX@j1g+{h(&Zl?r_Rm;@~xEz8)i9BEvNBYl} z>+wB3*mj&Ke)PUg{aZS~Jox-^<0T2GNH*gv2Z*rQznMi@k)q&XEv+DEfuJZ(LWPa{QA|su)_;b;O zMhu|{d(Me@C17M&#i|B_xatJh=%b@HFKWB8?fs0EdagXbz%*zV1}?bk3PpQ~FkipQy>v#=ae0|%{_YANJ{51^Xi`CcW={pShlWo}#tRo~W!D5#Z zHllr2x@F%AW0ySZEj#(m?xfS#)v+gd`2ZHd>GF3fcis|dQW3W02SkJ>Z<-u+$bd9k?}t?2M5i@4tQuWdl= zYSAk-FMx+9{Q=nIDdj|y$;k^)H4^~L-j?Ey?~g)EI49A6J$NZ`Elmdj2}GO<^&Oul zy9nzNm3Bsm;l8BcV7u@8ei-2dd(G9Q3P`WJ&^XZ3cp(X(yFqSF{|VtMJBQ{1eGx!{ z#lyV=LuU_=mxSYoggT2lv54q{i0J#P_1Cyq(dwHAzvwi-VOcwrj%mw-x)m!?li-zr zTiNvzdm==tzW9lk8tCL$6zQx+fTlv|AAZa^J;}rOlriEULPBPCpRJqK8`fuC57N-m zmS0+`hSQC4*0X?oAse%=9uKoQdN&$)kWHpt5y=f?wBfsWqxc#TJ=&kG2oNBR5uydSqY3iB^({Bp}PhYim+hqwY{an9vkC_6QX{4bBA=#UY!xDF^JCq z2>g$|1PVnOK2IE>4L=7a&e<_EC*2y|zY?KlgG__%f^Tsx=?Gp6=O;*nTnV;0KWBz)x`v5Mt z>h%BpoBUuRV`y(Aaf-)op+fWN>Y<|`yuYW{H>Rl0}j7ydSl$RA7LTETr%mt?y5LEJcmuu8~^!q zVFBouGkFHFYBe;>Euq?xN$as#CZ`KCAAz`Fa#iDxQxwgbdvb`)^xMfeGT+^_`{O6TrW!Kh&~z~~GoRenBjjL%efCPSz`#$ z6Gp;w74yR#-~?p%sKHXVvHTAElGVho6VN$t$1&dB2yT1dptQ!Ej>x{ zG&4!{-oS}KkMWH+z@+@cy9B9rTy7bVmF^_+gO`ip6#$1*?NJ^-o!1u4O7J^JB;lIM z1ZE@T+ufYJCZBYDeLXI(8zV68&Zh5mJplDsJ#RH*g};%$%Q~>>Bi#!_ z44!LE9I63br^{`gS^qaexLQ0<)kxM!?6ZO18&yu#H4DoRSl~JlVFix!L(q&x@!q27 z-@NQ69oMQ@Rqrh-M&-M6MHEwv4LtIKteqURI5FI*i;0u>C%|a7b-72Hd@;6nZLO_3 zIzhv<{Oo3ow)v45qU+T8$>9ROdwjZr;;GiP!Pi;P(x~l-WhcL1FFQgoM!nlr?K%Tg zZtZrq!&BQ*^1W6&lRSRzqW`S>N-nl#+u}Pj+WH)RqnId&yOI1_mSkXO@fAUvLX0hU z!Pk8SjebrJ;^{}7C7t}mzXFs5Cao-|m@8ASO)Tf8&6l3+W3}=kyZ~#tISZU zCIm&k4sqw^*%)F4S^1YShVmTw@C)e7h1LVJg;mkM1Du83Si!}3BYQpB$}#L^$NZR5 zF7bctW4DJHjiMRE>FT##rKK_MH3(0K*;=#z$jbfQ)`JxI3)eS_A=B=t+ohEsWe(`Y zJp4WPS;Fqmk7U2G(g0mR7_h^qo=?IvnK!h0y}S%U-<;js0?s-0eIH&{8Y29)2+yjB zGL&e*HnNkGSOpssD>qOOsQvSEo_=kt^OK1#RCf`&da}0z4`sA(^K$o=e&inuUMXA_ zV`HiP)K*2fkAzsRe1*S!(=qe|BbEB)g0pSG=a8^{Ulh!jU|gI8kc3=>mxK5K8hbF_ z*%DRIZy1D}O)wkc`Vn>b?o6rCCXlG^Au(en(ln+uC>?!y&vfX$^~*F3XmK@OB*0lB z1clA=LWi~ccz&u+!9Mn7W&oKBt|vVKSn^z2Xh)h3NVYc%y7PSXF~@p4ISvh<*y2`M?6`_MPFdS(_tAZ;3zoj zGMYfF6>`1thN9Cn@#p`@7mY-z>vj@o?-a*&B^{cF3J0K+1^wfpPvJarA>gw{=WBGR z4OZesMykVs!lQm!gK#0w%!A@orX@ko$4XOmi7}YanfBJf6Nv7-)+` z`~jHI5iJN+3cCHfi$kyhe(3#O>*`}gl$~PFQDO>~h;RvBKXyeOzP+^rb?kge2@!O} z1I@IiKNibS~lP?`A0GKuP&^~Ryq)dd@4 zzzu!cw`&-H;+iU@Qw{}EP7$;hTVr3kPQ-DJ^5DGjDwx8JCz?_GFCf88UyO=vvf((F zP@X7EMU;t-ob>>|+y9Q54r|}>!d4v*sxM4YyqjP$DG&R)5}NzEQoupriZCj z8$|e`f*hsIOud@wfBqY6RZ<-T0t~Veewie|O}t+l3Cn;>>-%)4d4DF|DCWL=Q@_#~ zuDEF6e{Eq*CX#GA?s-e4xs%@Q zuFwDBy1<)r$oj9XhQIpKxg_IP970)TI{?&)8CGF=H4b&G;@5?fmF(KCh^xn~k-W-( zrZ-@`=TF$~=Od*+dxeV@EYXZ2!{bfS)9_F5Ergf!P))yXV@e-gyd8s7*3mixYZImI3OdIQm8K ztUN+O6yG`p)s#4mYwlgu`haF0%F{^~zz;C&zsTjK3{1?(&PgPjs6(PGp7bos0G!Pm zGd@tsM~i~M|5-s7sj~qkVMbX8gAme85yvy(fTs%t&Q*>F2Y(jckdY!Eh=r03|uD0L^ z$QU0Z0ZIRumWJZqV_u36 zGg2zr(0f2BMIDP5PI*jJ3tyZ!PbP1q_nK)c;m#4qERj&4jUz;x%rBZp?N4_yJ6`;J zC>uzn5mYZ_DAll&U~WIN!{9a@VAp$3SH7A@6%FhpJth>SbB1FTsuWx#K?xQQmsm7l zW$MC?`U@A}cj-*85b9y10fdE7U$z>wrFrxW)io}f|ftD8ijJg$IevN;`OsVxy=P;7%A>d+!VMz5fNOb0OxY)*5`KhYWK zfT$*mGS>ADh!~Ey!!!fLemi$)HL?{~J~tP{dbQ*3Btgn>;}3{r3%dg)0e7-H;B=8_ z6x~@`FXx02RgIreO+WJPW>s3>^6U;Ij~a-Ul*WEwX~fAOIh}*+%m@n!5&{u-yF+SC zlodGR3jasbpf_GO#=_|fl_2hK3GCCzTs5O9x*;W-fq3gOmGJX}8}Vclx=>)o;I5s@ za5Gh7Hxev`MbNo&=pShN%)XEzGT1s7h^^-<4Fl96%?`@MLwk!MAXiMgA`Q0iug|+6 zqBKbT`#S1feSg@2N>!$b!xmu3K)V0kZ*o|vIt1qCFuXtW>yM^Io=xVln?xgD z)xrcoy3zuFiXO`_RGoK=*a3$fx+n@HFc8H1nd%$-+6fb+p3$sE*wqINE$;i88^2J( z=t_5cj98aaCrn5#hd6;cV8j;67xhJE{zlra=@1-1RF$OA*J7B*L#Z0P)59!K7^QV4 z@CeEtZ*r&l&pq!d;=UVj5WRZ)8d`rIX32e2NdK3)?cy*LbY_*=OS5-Vd|JvZkT>>Dw)vu3q z+=s8#Z_MvhLcsr#<6Byvj zC*gBA1EWHEMVVQ~yE7EO7iPNauRFit0a?CuP3WWJJ?U~-oUZ*TWDi^9xrweqB2thV zg|Uh759aJI;p1{BFcj0@4id)lL$ZWF+JaY(Lm7eko6(8-p{-8D0hUjjax0 zjOcU-zd5rz*4@}>E!E#r{aeDwv6MtBQ%KMCIm0pc>7cA~pEtXH5$p;J_{eRUbYwCd z4OAD$fYM!e0cT`I(l_ZMr)Npx)Hy7twX%AyUH={bqQqYls zn&rE+gOKi)ZVunA#UCSt3zQ6ynH0O2AWp-L$TR9k4xW;$c*D=)6eK*_y;Rq^TvL6W@%W=dejj`^L1yN0sFsK}|0=^6usofmUtgIf6 ztOWW1OY;txb)7Da7_3&U5;3?{qt#)cdE>{mmvYXQloh zx}gf}@{fm81+90{|CsW*dwCVbF zV2iHNaAp6*{Mc9G6web!&#vT6H@^oMVDKG>K>%GH?Uf~~hq~p4KlEm+g;?72^9PdQ zJ9-@MJALGI*{);iL3&u?uCC6*e*@w~ah>c(7+M>RgBz5P;3gC7ZV@7#1bjv&uoo$c zUS;pUAGbK6> zPQ}>1LPQfB!ESdC2+1ncAHZGB6q%LR1DM|98Q=?hO7Pv>;Bs*Pd`(r(hgL1EH$Npn z>nf46%CcLjO`OuUNtLpI4uL#2L%PVk)IBZwoC{a&t`~2?iT-{|d6Vr2B>{1cI7WIJF$(JtZKHfHMnqOmw78H>71%?N86tS9*F9w$TjUv;Dad_f}=6aY(6!jSR*EZ^IdJ zR%hu+ZxTNCC)-xYcs9qevHEd;d(U2Ou!Dh6!oP8F+_5b9}!%WcNYxMl4bKUsh@%Bp}Xs$AI|m zSd-7R_bR0Q{JY+w1o}ewkE&P~CNAG>P{yC>eq!U>bPgT0<%aB+gtq8e1Pz{jd&h?} zcV~F&Mg)1LSSsSfCSP_{G8bq?7qNpk&bk9)sL(%unNn+h>P|nmbs-flj0MKEuNELM z8cA~`e$4aREYE+sD)K@Nlw0F~ElS@|uEmo3u}w?x@RNR{jd}g(i1j{x)ghb|OZ&J` zWxSLWDMgSEV2~OwFerAUqBpQe^d`o-$9VjQ#Ib(Zux|%Egm6M1>FNpsyoOcO!OeX1U*P6(M zKHPj=WwyIL_Y&p{BZK)=C5qj5v>v?Sp{>5dcLB;#%80!;6aJ+S|8kMGFO|haQ_0xG z(BF8I!YTOi@9^GW*sF?;tf0>~;S8KFYw2jjmkB6LW4vBPbs6Jlj~XdD{RU`5$`k8o znav1ke!Zowz^Ho??B^lhkl*EvF*YHJY7&|-@QR-l^HB39xX;W4Nf#!O+6Ow8b6g(P z;H43KE>`{3t&r6?Jz*3jBma^ znK*9FzPh;$^vSHU{8zqyauO#>NCNzU3w-%JWZF@X2D2fOY%j>0f19!$aX9Cr*!Isz zPTy=tmXszeI`5wDD_h$sR4~&ZG+wC+hqY5ce)3aPtZk9LIwuf(S?&8&jF+^l`6Ur$ z6C?Ue(Q3f^gxf)}mphq>hj|0ZW?xff#(=!a+T9|w9gsx z#(cjb2TS@MBVK;txX-6~ntTH(@+gh6G|TH zr9`!hUkk}kHg#A;5IvvigA|=NY|9Tx=ly2=J9+m82h(X41dRz$9CQYQJ-8jqud+nP zcd*cv{;I`lKUectzYoj)a30RbiifPhdeR^J+}_<5@p9okMO$p;&b(#*SclMXqQRE% zcWhZnPqs zQ)+7k4F6AaUl~+a&}|8UK=2UU0|fVA!7V^=3+@msxVr@p!QCMQ2<{f#-CZy4?#?vt zy|3o))YSYKswh&qr~CHlvwQEg*V?B$LVTSw6CFPrb${36@Jbkg3<7bd2Pb5I^1(#R_a0+&oYFFJ0r;YKQ%{W7!xM` zaN4R>^wluu>t0&-v}8f^(N$+hk@k#wLP#Ng<|XS2by-v`hwp{;m9~wSo`M1KuI{mj z`T;Kfy~6SIboK9@^Y)v71A$5sYcy-(Js`M6?Bk9{WduD*FSuFuReZC39=}g={-(n& zM*E#k0?IsuKy&#`>wIT*>M+mYn(1(<3$fm68*&A9x1mh0$bJr$jmx=)f>l<5DX-&+ z^KoA6kNn%8p>ghxi1mN=rzcM{^j8XIH{0K3h_*p;j9&$Eif7wLv@oRA!aw=pW1L!W z{t&AbGMv;88KJbi(>ZW`e$b}LVLq0kIxKAZfu=+BNESgL$)|&3fBxY*+$k<6s25S5dgUCvOH8_Uuj3Ttp9Np`CzJ1xC1#wfaP};)aB_8b3ib8n&}=oE1)<&%oiQ!Ih%6`7h2u z7uSM<0b(=VBT{e8k8@HHF?Xl3!w?EX?nqXujlJOn19}`615## zS~E@9^IoPmdUh@RGUI{ssjY1uy5O5A{3xw3Fcsbc2i+Q0Z1qj*410?>X#ggH&nKv6 z%i{3s;OH!xb|lEK z#}UU9%dO#{)_?ctPsTkCRElNmd(51=xVxOs9gW<$Z1>2<6P|yI>Q+X@B>&}H9 zo{D^BQ-b=s%xH2ER-Q(5E42gj;7iveX`);9LfwaO)-6_P2v3@;_?Cj+y@}dPCi`1G zyg9oMe)wnwvG#i}fPS(-ad?v! zbyM$Q@AM(=1_$`|?SFi#SvmvvJj-%c3XBk3{9RjbMILpFD5>Xu0Ya76TmM>(_1XBB1y{6ARFmn( z%$u}nu8@{dm0$%E-fea#wtebjEBEVEqnO_!*-48gAJO@rV_(ro_LF;d>k!^@Aj>=; z5Kmwin{>61Y=gHu+)r6}HD4JJ2bfzOXF#(l5MpsmWQw>2h>C9bDsj;)HusNde!Sev@BG~P^(Ix4hSD;%bCKMB z%pB~O#~GKdz(+?qKR<$XeVi=zt`*T{>h;CS8N7N%U3$X;WC%k${cp_-7M79=Tj<5E z`xt!68}EV_*C@3*Mn7(H5a7K@mWAeAP@}VGA;mFL;u(J_u@7yEF&Sv9-91MByN80} zjU)|rCzIY~{#4=xWg}l>5)LO?<&d-wi%-6)T#n%v@uFR0MS-PF`g}!5P^3H0SIIMY zc?a%{$q1*|T{X{OgfN}Z%L@n(w`ppq{6mS^uW1pfv-<_x4fRuk**7g-C<9nMTN5cs zb^2r>t|2+Z)VZpxJBq4(8L}fcXf%cLNcXCB*bA_e7zTs^wz1vNJl!Mw znLR3|Zvpq@m-2P*Rp5EZNceVnT!byzHf%b#9P!};b!|;OR#T0gNq%ZSSJw^uddN_4 z*B{Q)O&=z+vfh={^V!yfm4*e?JxPTeOn^OptV8Hps_}W-8=2Y8L`V$UD_x=f3CdN$ znT+Iuw6>m3R?(%m{++tv^X5f_qkalYy>R!pbENo zx*G7P!7k03VKiac2S2NroRu6t;(#D8+^r+_6#uOPr*nOdHgctb*1JxFrmK5`;C6k7 zq|>O&mU{gyqNu+!EXnnK;;jZ)3q;3<6O?O6Mx+9a+_ieU5ZQvaEcLjosv5!E)$CE~8>VrlP=`#h z)mqeWMC`>0O^#%AV_H6stLx(c;RqM1;7nNw@AxhHKYz!3dF1N8;mNec@*C6(4Zarb zX9ASR{+R|%72}j7_;|in@R@(2@XhAD?wivBuJbQwMuclg)gv}CG3L1Lb81k=M9E#6 zn#%@u8GUgax>X>OL_?_r(=lZVL_GH?nWwkUbR@8I7PpD0HmEez7fvYE7>rPV*k}vK zC1^12-T!rq{Niq9BvQT%%Ne`$EC1qNBB>m1FXG=nK|%Q)kb_R-g(SS5MPX+UA+_9o ztk*4+dzd8l$N7Wheszwcym@?v*6=|`rNpotqoYMcFmdD5Hp5<0fmaVMh_N>T>n?ix z)svO4%ksVG$%&h>7}sYSy2sYl0pz7+GbWXKh}^yG;McFC6k~__*J?^e)Yw%jG*cCCQVvIMFtMtMnAe@wl=_XZJlQiS_DHWt@ z@*g>wx!ID(EX5{D^;;y5Uo#deapk?aL}gG8q~NDZN7$#bk-K-NZG0m~BN~+*EI~k7 z{@x3^BL!`{TBlT*?EtBtreA+>jRn}@7*`c5E8Os3^y~202TZG*LpZzQdZ?m$GZd)^ zrp>S+Yp9p5aA%CPa+-7h^PJuX*^OQ&G=J0hc&mSc_AxIz{!2}_8}FYYsJAt&!&&TM3VEN|T@WVh3{ z;sa`Ja!&@iysgJm>auQ8971=*?%fU%&P$fBzTBG$#5dukvQeI^t@mjy6$#W<*N35! z5)~Y<&rp=C1LKO+jMdz;ZBiL2%k8N9w>srfw=S|)ks6RLB9jG7Ju=V>1-!+5{b7Ua zdaAj3?y_&7fbH1&$yuGvNbZup35Z?~khW)$!m%@n z79g5DVQsouV>bj8de#2~)XWS=Q@pBsvqs4V8J9rPu6r&krxhbdkiB^=@I_+P_+6P| zex@s`o=D41e-2iLDV)b=TUau#pHrzbsG;r#4@BZAkkE?Zd90Wg7KiQU;v2(MIhqyE zo?%bCMV?9}OPdU+>||}uf28zPZrPgeYr67p-O_pwA#ugo|GbZ1a-M#eGfsjX_9Qwkyqdw;Ot{@gKdYr&Unqrsf+0}tGygQm zao{Ryf?_gH$kEM6GLSow@`gR&%;7?*>X8A;GC8b$i+infn4Cr+q_gq!TE$wOfr%#E zH)j)tS-6r0Z)D$eU)-v|kDhOV1GUoi;JF_;$a5962i}47N}4|CBO3Y+Uaw&qi6KBk zE_)-4&Wc1o-`Pn#I^dYOT~h^_9b&8n;V&r*(` z&Y98Z-F+PFxlud_n2Y9^`4=wnpzzs%TaBXCq&V8Ucb0kY2xVSgqOYy)WPqm`Qwsum zhx!3Fa9@EmGyUvZvSWRVp#r>yh6fR!gTz>WcLgI|ZK;JD*>Clz5#FkJ+Q=#iV4LJ!SkJv2AWxjUb%=#%|C`X!6Jm zZ1K=<0RsbFBrj5y4b4>cuj-CE$tcOuP2{7=)w=bC$=;Mw$VCWjDxZu-*z_jGV`V}* zRBE9`(B+$Zz9Y{b#f>uyLyw0f%Y)9dSF=Qf;N*HD2ZMrf; zH6h*#7j?mmGp_Ed z2A@>{DuC9L&lbXxOc!Yqc74I1kW(*g63szCAXvyO_pc6i5DxPWf;rzu`upr|w08W8ohS^8Kgq}U2oc9G|d^?ihts<5t`INRv70=pu zd-DA;WoIFi>Ds9-q4dhD%REJgoSXjc_dSZAy-;`H9~A1G;Ipu`ipT-R`a|cu!>z1M zv?!%mk1ct=ltLuEa60>aeF*8Wq(ZhtqH~tXgXd`Hu(rx^^or#m)uvRT4nt+q-7?Hno zQ{sT<8jy=@poD(9#3{Z!ZN2V?D?*qXK2OnwUGZxsu~BZK`{HFn&~HF>;>~b+PufZ`73S z#d18%`G;VVF}AR}EiJ7LmBuNjDN87pQgy~-U`GLynxXxu9`LLZa~|VrGv`M*#Q(Ep zECaxMD9)P3C;*)QjyBfU4So`1zzvwv-<(P>jW>f20c?n;$z_)XE35sE^!)4EhK(74 z1klJFW4dDZf|BEdCACC1^vmGJ3}CYtelhN%FqGaDxmfAA*h`q<+YF0%@ZQ-TY1vUB zih|T0FW~tBr3k;eKw4tL+q3$bj(`3Xy(!!6-1T{ciDtQ9uUfO-ajckd@KbNxW$8wY zSB4fd!ct_NFO`ab0KlhS((QmVeD03C6|oJKdP`SS3l|F7xH(oPPSjjU$0$#w4as z|AtJ{n;zyQcO~v{?0>larxw5sGUHM92;;%)k?8&S5IQ`fWo!2uP{iawqv#^XRyDJZ zSNut?EQ)EWqgM$R$*KC|HW4U=^oxP`b*&1QA*XMK- zQG?`*RV%rb(T}sN<*B_~3KizV4|TVV6{}bl{bKu>)1O_$ZP@lr^Yssi(fJZbJ=;Z9 zS(t#igG>%M!)%jpa{N2@ZKB(MRbHz?TFhV7%0ZEMKiGy7aUF+S!r!<&s>z=4DViYGrGp?0Svd%rKlk^tOL}F zT1q>MK1N|g7|G#6BsPPQ3ZEa5@Z1I#c2CyJ_1+ZGP0YlGO5Vap0{6zM-vDo-?#6jURSUu^SnRKJgtbN1?QtaJTk z#hUy=+t9GY1}OdnRKN=&wBT(j-#BH|*LJx&Gcj9(_;>YSV{8$LfgpJBWvLBt5p(Gk zX@H4pywEXa*ElP3^-mVQHJW8Ix!l7Vv83lORs2bm&y#4^g^5`7y3?e`-a5z~;R3nQ zw9z)ncJbsM1+b@p#HB+#5ZRConQ9+J4kxAg31nfHG2&d+g;u#+-DhYtOSXbTE#Mlm~pB>rjq zusr(!2goVCY~PnuCc#r|(*M4;u-@@ioy(~~y2qJ>*W;z?e6_hM9Y*Wp?tQ)M>JZ>8 zRl+sYDLC;IoB*cH=gB(*DPlPt4|iDjmy9oNVpkhoi8vCRdFSU23Uoy|9o?Nc=( z`;W!F^SnEr*siR#cDGAq;fD!VwqA2)%Xy(;gcEc>?d zOXO^s*WV+p;ly(1rkn8bA3t+h?xlIk(B!DO+EK7x4e43`vtRA?5rc7QIljm89EfY* zDr5QHMjif*n8sDw4^DJ+d?$==&ow*Ci{9RO>j}={CfR9kjVXC5y zNVa))Vz1SPjgF3P_q<-}dAL14J)_mUuIw^sGq^Rmp#sM!7PQk<)?ChygUruX-FA?R zHwYN^;a=q8bn}I0W7*Mb061V$F^V&G&R}I8Q{o9R*06-Hn;-QkKU2JpPLGzhnVoB3 zN|lw{DA+7ERohrBowl2;$N%_7?uRLYV2vEKw_CAE$@540*Br~z-Z9Y2&lXqB?5=bW zk{e<+n*pDOVAEN2@u;+R7!zvA{+{cfp(6?7@UCk>q`7q94+#3GrT8zmLQM&Y`Pgxo z=)9@m`_Dtb(%1o$FWgw1Dz?y#`zj z@9}7(kjct!iCpDHr(%h0C)QT26@ez@%fex8rLd0eesX%JAzdWFd2vowC(y4RB>x8=P5qE&?9!fW#>vAp`c&}&dfmR$I5rpRGt*fEu-0Vs($@neNd&$Y5JM6hY>cq9;-=o8Wib zo*>O@$t?E0u^{(#^rIIHz*OQLbs4fhX67J$#F}KDtmOxQPdCJR!}Ll)tO~b{j&G#d zYJm2BWPPKATiK||c#2{@K?L(ax~tNX@5iy}{+`YE0FeF%4ioGh%r(1x&!6{^q`4d3 z)2v|rO&OQ1D9N(jONdRV-AbNDl4Y)@s)(p~a&}U1vb|m!K^ zZy~;oBb5pKI)C&bphh?$&g+h87rMw0Va0xguV=x!#k0-Oz|c_rp94*$@sPn#GW(9h zzmHTt+k4O!qnW+~Oz#^yhM%8qNWh|bp-=lfDQD`?68;smYP1%n=oslg2)A-oo!ea} zAe%%}qOg)HZOs~1 z<7mhN9O@g-KNx{`72ZzjO|^%7%}dV=X(Bx5k1NMg#7yZUTUN?%IMS9oJ*Cn@j*?TR z-)`W2mh?j8e6l4^ikG&scIO$_6z?~(^Xr}>_rOPf8Ia-E|9c3k8Pl3YGyQlOFBELbnjT!dUyVA zF1j(G2Zvv{``vayx4Oc>?ovHObR=hD&n0J@4gf2X!jAqr<@Lm76K<#oC$FmZO)O*- zk1@Ah1#otd>_4yhj+|cY7${Uw<`KJ5ntEjF4i9G4DHm*MwZ~Y5N+)_n#zDoi4HVbi z4URq%!P*n6UriSDFOXlNxQqFiS?BnX8%m(->GMI7n%B?A5KxKI-q`L^F%VONtR8G% zpkxmvA}ss{q5fuT8lWeZ(v~N;zLuEiXk0eaw=EB6NGvQyrAA+4w1~a9n66!tUPM+L z_vZJMWPv+nrm8{8CV=QoSHDLF$<|v7#H}>CCh~!=9ft;N8Yt-uFf_Aq zVykVxkV^1NLM+s=&ua6aR%S}?YA_1vgd2r%r!8>pBL+89JRy;Z315Juw7NW8U${i} zul`f}Ue1)M>)#0x6Fx7|M>^a^7v|6irmf4N(wNBo#hT->;fU!(eL2#nV%bZmc;${j z6f;P(XP?|a{IJ9&SS;CIk9UmWN8?MQYj7pzPDB7IwBI499jd4XeWg+-Qh7;U8pfSg zbFSBd+5}?hZt1Wmo6vWv{jp%jI^~9G5-nBG)&pqq$H{lF&T|O z{vX-30BrcWlsranM7cC7_wlPpg+w8~5jSKr?#?NF1Y23FB&cbl5oh;wJtgKmJ2{s9 z6MEGkrF|o85qm`-7>2iw!cq~FNHLb`2ekXT|)(jGwRZVO;ml@^Gge z)BZIgkKXD#5iX9Emczuv4M8Pi&a8=*O|Fv(ISmcJcVW#zxn%qhhnHj$- zwGNyv+`6)wwWkMFhDTWkGc8#~ze+Q+WP;8HvUE++XMd>p7OSO{#jg$pHEE%KykbRZPi5&a|8|0mMNt355M^z1ZYN`n|50YDhPaJI5fu5&}!4 zh3FB*My1G`bSr>%sf2oSB25kBOb~|pO=CI5vi5hKHlt1XjS^mo;r^HvsI(T}%oNR; zSy58;77_|;k#~V&UjDqZ3hx9-KZhiHJeM$z!>Ea0nvX{4C^V@7g%Jd8=oh*Dg~&+zpB@GuPX%jJxO|?gR%2 z(C7(RJq1dIP{C&*22YpgOSx=q_Y2D=Kqn|MvqKrn8mmJ5uDo{*P>+%J8uy;-bhdZ) zQxR`{boW!(ZR7Jcu46ZCL@6~*#AJl?s}-QI&DJGDr1r~Zd+!dZUwflz5+vU!9dChx zkpYN~B+bDbHmGhZH^DR*sa&J3%3|3Wb=w14Dl^BK=(g&WeV%s%M7<(c6spa+HUU=t zje?|1i?=Gg1Q<4lwjj_?i8MRi7naF~QoBJ6rK35NPbikt8u1$-p}(9}(#|03WewKO zZ=kNiIlCW&jD4>fZ1B?QYi^Rv|1O0etN1}~`6u7Pj}a^dSY$J|Q>v-Aw>*ly$s|Fv zcA1ys7|e}axu|V8mOSpV=&u_lm`OhQT{;jKjCzgDjL)2R(s3h~mgw&=MVclXj@WE9 zz+_ImhkfVCI?uynw%K+^-|op+%UV1nO@}{zt(d(UoGOQ4g|V{0P>UXRokI9 zq3vOg1*)A&8kuu-<<3V96rD7Y)1RoKBzhmL*UipqQ^l~jB-0H|cS2S3$E2n@0^2}RZKl|sI?FPP)Su8`mF%MWdC(mdg1y_Vtgq(#GR9tVMvbixl!Qih> z(fAiZA`G~qMcb}05ucWS6esd``hz=Y&T?@^?Xn{aDiR1ckm)7g z2FTZ%OQvaIVU4;h8jRnkb#;j17DG4~DU!Gq@ozEYeNF0eJD=1sX)A7PfkNS^xp{Zk z84wyDw=a6O%F?cJo5bWiA$OD4#Ss~8Xe4MPfGT9!K{jQdR}_F8+y|!qCNxG)U3I#T z`5~Nw-vbB;grmPKePf{B6{sRVc>Q*WrU+t|zgC1r1O1`Y zzvT;io*nPDOJ8GiC<4c8aKf4tmKeiu*K9AEA-O=TB6TQHvB{>_q-hmCsBL7fMqL{m zfiEZQdnHI>(e7<}sQ#JU|7{5wLMFku`Q=4EBnT4mG^`uqJ(UP+<9ufYb;o|t(@Bgm za@VBzGxi5&_%gb zO3QV7&sm%R-{xFRW$pPc0Dfe}+p;qH)<+olJh^v*oKsZ&Nl+y(?0U(%HW4aRgHjs8 ziVk+eJ#TgXdwL&z4yIU43KS{! z-S(BB!WVXERE&A_M20hli@hQB|GV%3+Ck|_%$pn58R|)$K{F{mm5} zfF-Zs5zn~uqH| zh6E~xLwc>Y4$|+5nuCeKDZNo6S{nu6Yn}6_YlpfZ;wV1JI7c(A*`EpSjncsF{(1Po zzwoHuw|{9p+hVsI32vB_@yk0w=+-8pBMKmDgNz?zT28Nf8PCY8MDb^SL+(c=D`Jq8 z@GE%U>=ZTk9=q`Fso^Ey8O?a1Wh-3Isp*i@0a^?$$U=E4s>UPK~$R36nke#oJ#m8Jc@dJm|* zuH6Dij>h$1u6m?mXO;}Aq{y2hL+8=Vs0r)EP#X8`*TDZmk-SqKE8yhtB;n5NV6J$xVaC6!kQ6!}mq&+9~*bL~L#^rrS4cHnR1%EKk z&$o3QkM{-_C8&av7H-AqN9aqt#A9hi?etDLhh!{F=xJi&_bXRb#WN~3Rv4hccRUFw z(WKWdaHF+Cx~f57@`QsCqe}>0{_%#B93k_?0Q^&;0IC50)jkA7?3YhgjXywRzIj?d!9({qWKOb>Z5*)2Zho zk;E%C==%D4C^pm4)~=|Ru75Y$+1sC9UpqVEGG-|pr9P=dcC5aqp+V5q)n&t%$w}v- zq6&gT!ME9)qyb4a?d9Sc$@uV;$b7xq7amnKv+X^FxWl4YGEUBf-rg@&8rP{PR6xVa zocf-x+u{}19GH=j;nDgP23$ybsKxgutuUy{{_<~ulhaIki@{OS)qmeIs3rZMTecei zBN3xToFa=kn3^y11&0pepv}WL23^e@TAXX}G_CZ8eC5l8o$C_Slz!c!tgMY~=ohVG^$! z(qfJ3_HQ4@GKFB$UDgl~k&p^$=I6~0=c|zkIDUcoV#7x{-yUh%u~z}_r8+pUiDgFt zD&zdH7NX*r=@|EJ%4%ycsb7!zFUajR4k0bNOU@8a+V}4TbN>8EJ-@l!pP@^W&C8We z`i)BXDU(t+S6w7a1u( z6g9)RX}N9C6HcV0prBA7m%+bxw_jSCYieG4Rs)z?1?>hWWsyK+h5hMbrI)J;RZCSG zoDK`Ndd(BgYR4U@;C*ZfDD6zmTB|)UpNzM) zOIE5;QBixvwaeVwr`cj*iXuU%43}!s(!bnReBle&hW}+YT0ZJ>q{!Uf-4z@+-S|K0| z;@l4Us4~7bxm^~Ff7*|(_~0|bd;aS?*d-;u$LilMCA;ZpW&v{Xa5U-4ca^VSJFgBG zb|Ed^eTEvv@lTKUmA32M_WUNmxN^eb0r>)o^KoPo#;2c^<>h^*zEeewfBBZRwKbQWte`TDV(HXR<=pKhj$mG`n=Vzr*X=Gfa7xlxa1fyJ-@IpP zJP~&EKj0X4W*Y44YqQ`m{FtPLsebr@&qp}*WnZ-gwtyx6UVR zNlhI0>m}zTUe}KU2~2s0J>klD#>J}3PW)~c)IAX-CbMPw6cJzyP#11|L8wH()hmsa z2^<(4XlCp`e}*L{CI56&nV)7Nx3*bk6CV!dar84&Weldusa@rMW+(WyJho9t=!-> zpWDT!ZF{$i9fds?AESZzv}>1D2O3KhW}|*g9rr`_czShVV1|X{lN!a1hl{{hT^%hA zlxR0ddX+RBahLqtqXmyp)DI4&fb~IRU9n^vu=D6RII7WlFogUbiNV2dB%X%X73b?S zGgpc}lz!S(kyO?$vl2TBh#Q;Kzm$>)0Z&4?LyGL_4I68KChFAz|) zFR{M|fF#F#&M#YI;KNE2~d|^;46ATCpESS;tUQ)KsQlYlykxTug z@Nx<8BI;c|J%u?^2?fSO$@vP|V)c6rlZe1>zHbkwz5F7|AGbU=&)3`Maoeu>D@x{r z5y~zBqoU}+N$_;3p&b~;>% literal 0 HcmV?d00001 From 37bad3c763d0975434982071103210bda887f673 Mon Sep 17 00:00:00 2001 From: Hung Date: Sun, 4 Aug 2019 14:59:52 +0800 Subject: [PATCH 22/22] edit README.md and installation script --- README.md | 14 ++++++++++++++ setup.py | 9 +++++++++ toppra/interpolator.py | 30 +++++++++++------------------- 3 files changed, 34 insertions(+), 19 deletions(-) diff --git a/README.md b/README.md index 52328c5d..22146240 100644 --- a/README.md +++ b/README.md @@ -14,6 +14,20 @@ In general, given the inputs: TOPP-RA returns the time-optimal path parameterization: `s_dot (s)`, from which the fastest trajectory `q(t)` that satisfies the given constraints can be found. +## Quick-start + +To install toppra, simple clone the repo and install with pip + +``` shell +git clone https://github.com/hungpham2511/toppra +cd toppra && pip install . +``` + +To install depencidencies for development, replace the second command with: +``` shell +cd toppra && pip install -e .[dev] +``` + ## Citing TOPP-RA If you use this library for your research, we encourage you to diff --git a/setup.py b/setup.py index 7f2d79ec..b94a1ce6 100644 --- a/setup.py +++ b/setup.py @@ -47,6 +47,15 @@ if __name__ == "__main__": setup(install_requires=REQUIRES, setup_requires=["numpy", "cython"], + extras_require={ + 'dev': [ + 'pytest', + 'pytest-pep8', + 'pytest-cov', + 'tabulate', + 'cvxpy' + ] + }, packages=PACKAGES, zip_safe=False, name=NAME, diff --git a/toppra/interpolator.py b/toppra/interpolator.py index dd85a0ab..0577cb47 100644 --- a/toppra/interpolator.py +++ b/toppra/interpolator.py @@ -1,5 +1,4 @@ -"""Implementations of interpolators, which representgeometric paths. - +"""This module implements interpolators for representing geometric paths and trajectories. """ import logging import warnings @@ -21,13 +20,11 @@ def normalize(gridpoints): # type: (np.ndarray) -> np.ndarray """Normalize the path discretization. - Parameters - ---------- - gridpoints: Path position array. + Args: + gridpoints: Path position array. - Returns - ------- - out: Normalized path position array. + Returns: + out: Normalized path position array. """ return np.array(gridpoints) / gridpoints[-1] @@ -36,17 +33,12 @@ def _find_left_index(gridpoints, s): # type: (np.ndarray, float) -> int """Find the least lowest entry that is larger or equal. - Parameters - ---------- - gridpoints: - Array of path positions. - s: - A path position. - - Returns - ------- - out: - The desired index. + Args: + gridpoints: Array of path positions. + s: A path position. + + Returns: + out: The desired index. """ for i in range(1, len(gridpoints)):