diff --git a/.gitignore b/.gitignore index 8aac01b..ab23af3 100644 --- a/.gitignore +++ b/.gitignore @@ -1,5 +1,5 @@ # For project -data/visualization +data/visualization/ # Byte-compiled / optimized / DLL files __pycache__/ diff --git a/README.md b/README.md index a020203..60b24c5 100644 --- a/README.md +++ b/README.md @@ -8,4 +8,8 @@ This repo is a collection of research projects for learning-enabled motion plann ```bash # TODO: write the requirements here +conda create -n lemp python=3.8 +conda activate lemp +conda install -c conda-forge jupyterlab numpy matplotlib +pip install pybullet Pillow scipy ``` diff --git a/data/robot/kuka_iiwa/model_4dof.urdf b/data/robot/kuka_iiwa/model_4dof.urdf new file mode 100644 index 0000000..bf0547a --- /dev/null +++ b/data/robot/kuka_iiwa/model_4dof.urdf @@ -0,0 +1,289 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/robot/kuka_iiwa/model_5dof.urdf b/data/robot/kuka_iiwa/model_5dof.urdf new file mode 100644 index 0000000..80a1ae3 --- /dev/null +++ b/data/robot/kuka_iiwa/model_5dof.urdf @@ -0,0 +1,289 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/robot/simple2arm/2dof.urdf b/data/robot/simple2arm/2dof.urdf new file mode 100644 index 0000000..f008fc8 --- /dev/null +++ b/data/robot/simple2arm/2dof.urdf @@ -0,0 +1,125 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/environment/dynamic/dual_kuka4_env.py b/environment/dynamic/dual_kuka4_env.py new file mode 100644 index 0000000..845ec10 --- /dev/null +++ b/environment/dynamic/dual_kuka4_env.py @@ -0,0 +1,19 @@ +import pybullet as p +from environment.dynamic_env import DynamicEnv +from robot.multi_robot.dual_kuka4_robot import DualKuka4Robot + +class DualKuka4Env(DynamicEnv): + + def __init__(self, objects, robot_config=None): + if robot_config is None: + robot = DualKuka4Robot() + else: + robot = DualKuka4Robot(**robot_config) + super(DualKuka4Env, self).__init__(objects, robot) + + def set_camera_angle(self): + p.resetDebugVisualizerCamera( + cameraDistance=2., + cameraYaw=25, + cameraPitch=-20, + cameraTargetPosition=[0.5, 0.5, 0.5]) diff --git a/environment/dynamic/dual_kuka5_env.py b/environment/dynamic/dual_kuka5_env.py new file mode 100644 index 0000000..d4cad84 --- /dev/null +++ b/environment/dynamic/dual_kuka5_env.py @@ -0,0 +1,19 @@ +import pybullet as p +from environment.dynamic_env import DynamicEnv +from robot.multi_robot.dual_kuka5_robot import DualKuka5Robot + +class DualKuka5Env(DynamicEnv): + + def __init__(self, objects, robot_config=None): + if robot_config is None: + robot = DualKuka5Robot() + else: + robot = DualKuka5Robot(**robot_config) + super(DualKuka5Env, self).__init__(objects, robot) + + def set_camera_angle(self): + p.resetDebugVisualizerCamera( + cameraDistance=2., + cameraYaw=25, + cameraPitch=-20, + cameraTargetPosition=[0.5, 0.5, 0.5]) diff --git a/environment/dynamic/dual_kuka_env.py b/environment/dynamic/dual_kuka_env.py new file mode 100644 index 0000000..34f3cfb --- /dev/null +++ b/environment/dynamic/dual_kuka_env.py @@ -0,0 +1,19 @@ +import pybullet as p +from environment.dynamic_env import DynamicEnv +from robot.multi_robot.dual_kuka_robot import DualKukaRobot + +class DualKuka5Env(DynamicEnv): + + def __init__(self, objects, robot_config=None): + if robot_config is None: + robot = DualKukaRobot() + else: + robot = DualKukaRobot(**robot_config) + super(DualKuka5Env, self).__init__(objects, robot) + + def set_camera_angle(self): + p.resetDebugVisualizerCamera( + cameraDistance=2., + cameraYaw=25, + cameraPitch=-20, + cameraTargetPosition=[0.5, 0.5, 0.5]) diff --git a/environment/dynamic/dual_simple2arm_env.py b/environment/dynamic/dual_simple2arm_env.py new file mode 100644 index 0000000..5597927 --- /dev/null +++ b/environment/dynamic/dual_simple2arm_env.py @@ -0,0 +1,19 @@ +import pybullet as p +from environment.dynamic_env import DynamicEnv +from robot.multi_robot.dual_simple2arm_robot import DualSimple2ArmRobot + +class DualSimple2ArmEnv(DynamicEnv): + + def __init__(self, objects, robot_config=None): + if robot_config is None: + robot = DualSimple2ArmRobot() + else: + robot = DualSimple2ArmRobot(**robot_config) + super(DualSimple2ArmEnv, self).__init__(objects, robot) + + def set_camera_angle(self): + p.resetDebugVisualizerCamera( + cameraDistance=2., + cameraYaw=25, + cameraPitch=-20, + cameraTargetPosition=[0.5, 0.5, 0.5]) diff --git a/environment/dynamic/triple_kuka_env.py b/environment/dynamic/triple_kuka_env.py new file mode 100644 index 0000000..14dccf6 --- /dev/null +++ b/environment/dynamic/triple_kuka_env.py @@ -0,0 +1,21 @@ +import pybullet as p +from environment.dynamic_env import DynamicEnv +from robot.multi_robot.triple_kuka_robot import TripleKukaRobot + +class TripleKukaEnv(DynamicEnv): + + def __init__(self, objects, robot_config=None): + if robot_config is None: + robot = TripleKukaRobot() + else: + robot = TripleKukaRobot(**robot_config) + super(TripleKukaEnv, self).__init__(objects, robot) + + def set_camera_angle(self): + p.resetDebugVisualizerCamera( + cameraDistance=2., + cameraYaw=25, + cameraPitch=-20, + cameraTargetPosition=[0.5, 0.5, 0.5]) + + diff --git a/environment/dynamic/triple_simple2arm_env.py b/environment/dynamic/triple_simple2arm_env.py new file mode 100644 index 0000000..c4d07e0 --- /dev/null +++ b/environment/dynamic/triple_simple2arm_env.py @@ -0,0 +1,21 @@ +import pybullet as p +from environment.dynamic_env import DynamicEnv +from robot.multi_robot.triple_simple2arm_robot import TripleSimple2ArmRobot + +class TripleKukaEnv(DynamicEnv): + + def __init__(self, objects, robot_config=None): + if robot_config is None: + robot = TripleSimple2ArmRobot() + else: + robot = TripleSimple2ArmRobot(**robot_config) + super(TripleKukaEnv, self).__init__(objects, robot) + + def set_camera_angle(self): + p.resetDebugVisualizerCamera( + cameraDistance=2., + cameraYaw=25, + cameraPitch=-20, + cameraTargetPosition=[0.5, 0.5, 0.5]) + + diff --git a/examples/bit_star_planner.ipynb b/examples/bit_star_planner.ipynb new file mode 100644 index 0000000..e382ca5 --- /dev/null +++ b/examples/bit_star_planner.ipynb @@ -0,0 +1,187 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "> [BIT*](https://arxiv.org/abs/1405.5848) - it plans a trajectory by incrementally growing a search tree in a batch-sampling way" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "%cd -q .." + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "from environment.static.dual_kuka_env import DualKukaEnv\n", + "from objects.static.voxel import VoxelObject\n", + "env = DualKukaEnv(objects=[VoxelObject(base_orientation=[0, 0, 0, 1], base_position=[0, 1, 1], half_extents=[0.2, 0.2, 0.2]),\n", + " VoxelObject(base_orientation=[0, 0, 0, 1], base_position=[0, -0.5, 0.7], half_extents=[0.3, 0.1, 0.4])])" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAigAAAF7CAYAAAD4/3BBAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAAPYQAAD2EBqD+naQAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4yLjIsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+WH4yJAAAgAElEQVR4nOy9eZwdZZ3v/36eqjpL72u600lnIQQIJGwBkYAQliSggIr+ZIbR64zOqBfEm0FHZZy5Fx0FxRGdH9zRcYafODIMjKO4IMgOSQhLEhKykn1POt3p9N59tqrn90ctp053J+lOOjndfZ43r+KcWk7V91S6+3zOdxVKKYVGo9FoNBrNKELm2wCNRqPRaDSa/miBotFoNBqNZtShBYpGo9FoNJpRhxYoGo1Go9FoRh1aoGg0Go1Goxl1aIGi0Wg0Go1m1KEFikaj0Wg0mlGHFigajUaj0WhGHVqgaDQajUajGXVogaLRaDQajWbUkVeB8s///M9Mnz6dWCzG3LlzWbp0aT7N0Wg0Go1GM0rIm0B58sknWbx4Md/4xjdYvXo1H/jAB7jxxhvZs2dPvkzSaDQajUYzShD5GhZ42WWXcfHFF/PjH/842DZr1iw+8pGPcP/99+fDJI1Go9FoNKMEMx8XTaVSrFq1iq9//es52xcuXMjy5csHHJ9MJkkmk8G64zgcOXKE6upqhBCn3F6NRqPRaDQnj1KKrq4uGhoakPLYQZy8CJTDhw9j2zZ1dXU52+vq6mhqahpw/P333883v/nN02WeRqPRaDSaU8jevXuZPHnyMY/Ji0Dx6e/9UEoN6hG55557uPvuu4P1jo4OpkyZwt69eykrKzvldmo0hUJHT4oHHl9Le4+NkBII/z4qlFIox0E5No5ywHFQyl1QDkoRrCvHxrEz2HYGlOO9PjgVCgWhCPPff+46Zp0x4TS+29HJ9u1buPOu23EcJ9+mDIlZs87n+9/7FyKRaL5N0YwBOjs7aWxspLS09LjH5kWg1NTUYBjGAG9Jc3PzAK8KQDQaJRod+MNfVlamBYpGM4KUliouPreR1ze0IqQRfGFQCk+AKE98ODhOJng+2CNKYdsZDDuNcmzvPJ4gUWqAQFm1uYXLLjzzdL/lUcebb72KlAIpjXybMiSuv+5GqqtrdLhdMyyG8vOSlyqeSCTC3LlzeeGFF3K2v/DCC8ybNy8fJmk0Gtw/GvNmT0AahitQpIGQJlJm12VoEUK6CyL7B0cIhOd58fcTrPsXwj0m2KDYsruFrp4khU5ra0u+TRg2WpxoTgV5C/HcfffdfOpTn+KSSy7h8ssv56c//Sl79uzhC1/4Qr5M0mg0wMSqOHUVUZo7HYSUnthQKEd44RvhiRAQSoFQICXKAYGDwsH3iwghgsX1nrjnGow9Te0caOnk7OLa0/NGRyHd3Z3s2r0932ZoNKOCvAmU2267jdbWVr71rW9x8OBBZs+ezTPPPMPUqVPzZZJGowHKiiMsmFvPL5c2YSvpejmUAilACTefxAEpFSgDB8AB4QkVYWdFilIKhH+O8FWEK2xUdl05ipfe2sbZ0wpXoHR1dbJz59Z8m6HRjArymiR7xx13cMcdd+TTBI1GMwhXzqll455e1u7ucUM0vphQAhy84LBCKIlQDsr3kpD1rij3Be5xQqJwvOfZ1BOBQAm8nBTYsL2Jju4E5SWxfLztvPP2itdJp1P5NmPIxONFXHTh+/JthmackleBotEAXuKl+3z/vjYO7u8AYN/eNl5+fhMAc983jZs+cj41tSU63n0aEMCfXjOJ/b/aSVuPJzQECCVQQuDYtrsuFcJxEMLxxIl/At9j4ifCqqwnJgjz9POiCMHBw10sfWcnN10163S/5byjlGLv3l1jpnoHwLIsGhoa822GZpyiBYrmtJDJ2DiO+0l0cH8Hm9/LVnC99NwmDh5wRUlLcxeHW7oHvP6tN3by6sub+d4PP0ZdfZkWKacYIQRlRSY3XzaBJ5c2k8wEaa7BvXd8D4o0EMoB7OD1SnnCRIXWQzGewbwoQikcR7Fx+yEWzTsLyxwbVSwjRXdPF68vfyXfZmg0owYtUDQjRjKZIZXKAK7QWPnWrmDfW8t3snPHYQB6upMcae0Z9vk3rjvA1xb/is9+4UquvPrM43Yh1JwcQgguPascheCXr7eQTDluOAbcElhPhCilEI6d9ZoE2/0eKb5KyTk7g3lRhIB33tvP1j2HOfeMgS0HxjN2xqajoy3fZmg0owYtUDTDoq8vRVdnthT09SVbOdTUCcB7G5t4b+NBAFIpm67OxIhff+P6A/ztV37N3V9byIc/diGGoUXKqcQVKa7H6pfLWkikHTdqIwTCMBEhcZLtmaICYeIv9POguOcOt0ERgWZJJDOs3XKQWdMnFJSnbMvWjSSTI/87cyqJReP6i4LmlKEFimYAfb0pmjzRAfD2GzvZsc3tzbBvbxvr1+4P9iUSaRz79M6bTCYy/PB7z7N5UxN/dedV1NSUnNbrFxpSCC6Z6XZ9/OWyFmorLPa2JAHplRDLQcSJ20lWOcpNjh30RyTrRREi1GVWwCtvb+eGK86mojR+6t/gKGHbtk1jTqBcddUCSkvL822GZpyiBUoB0X9w9e6drXR1uX8Q167Zx7vv7AOg7UhPjgixbTXgtfkmkcjw6/96hz27j/Cd73+UqurifJs0rpFCcOnMUqpKTJ5Z1YaUguKoQUe3jRBel1jHQTkZHNtbHMdrcX90BvOiCAXNbd2see8A8y+dcWrf2CghlUrx5ltL823GsDFNs6C8XJrTixYo45zt21o4dNBNQN22pZnXl2abQG3b0kxnR1++TBsRVr61i2/8zVPcufgazpvToP9YnkKEEMyYGOfT10X4+UtNNHek3UZuhoS028TNzqSwM6mgtf0QzopAofp5URSwbPUuPjB3OkYBhBAcx+bA/j35NkOjGVVogTLOaW/r5a/vfPK0h2FOJyvf2sWdf/kf/N23buK6hbOQUouUU4UQgvIik89cX8/bW7v4/duHqS0rYv+hJI6dJpNK4PQTJ65mPMa/Sai5bLaiB9ZuPcjmnS2cO2P8J8s2NR2gLzG2vyxoNCPN+P9qUuBUVhYFc1HGM709Kb7zf/7Ao//6+pj3Co0FSuIm82dX8OHLarAdkIaFUgrHzoQSYl3Vofx+KEclZ0CP9yhIZxzWbWsadeHFU8HGTWvHXAWPYRjMPLPw+tVoTh9aoGjGDT3dSX7y0Kt8+38/rUXKaUBKwVXnVfA/PziZKXUlSMPCcWwc5SXHhqp3siJlcLERjsyF5fQ7m/aTscdO47ITwXEc1q5dmW8zho1pmMw5f26+zdCMY7RAGefUTihl5tkT8m3GaUMpeOXFzXzlS7/kzdd3FMS373wipaC+MsKnrqknonrc3BPlV+4or929y7H/KYL5xzlelG17W9l1YGx5FoaLUopNm9bl2wyNZtShBco4p7QsRl19Wb7NOO2sXrmHv/vqU7y5XIuUkcTva+LYGZo3vc3Bta+zbct2/uP3b9DS0tLv6LAvZAj/BiL7xM9bcRQsf3f3SJg+atmyZQMHm/bl2wyNZtShk2QLgEKtbOlo7+Pvv/ob/tdXruf6RbOIF0XybdKYQimFcmzsdJKDa5bi2Gl2vPorupp2oRyb1q2raYlOZ+WkvyBplSKQubEawhJlKD+D4Uoev7oH3tvZQl8yTTxqjeTbGzW0tR+ht3f4nZXzjRCFkN2mySdaoBQAN3/0Al59aXO+zcgLHe19/MPf/57Vq/bwlb9dRJEWKcfFTiXpPXKQfStfYusLj9PX1kzn/m0ob4id8KIwjoywbcINpCPlCM/r4Yph4QZs+lXvDE0oh0SKN5xw295WDrV2M62hcuTfbJ5RSrF9+9j83bzk0iuoqRn/FVaa/KEFSgFQXlE43TgHQyl4+rdr6etN8cm/uJxzZ08sWK/SscgkejmwZgnrf/UQrdvXkmhrDlJCBFlhgvc8bcZpL56BEIbrOBEiWzHmCRVfpAzvdvsixa03th3Fayt3MO2W8ZmQ+eZbS/JtwglRXFSCZY1Pr5ZmdKAFSgEQjZpEoiapZCbfpuQN5ShefG4Ta9/dz/0/uJU5F0zSIsVDKcWB1a+y9okf0LR2KXYqgRAgZW5gJpQi4npQjDgIAyFldqN3gKtLvLTX4/VBGZRsAzdQtHUlsG1n3M1eajp0gAMH9ubbDI1mVDK+fts1g3LWOXWcM6s+32aMCpqbOvn6X/+KR36yrKAFm0860cvuZb/l1W9/kgOrXkClE0jh/mGQIrsYoef+vgMVl+IYMW9QoB/YEYE3JcsJCsHgHIJVG/fT0T225tQMhdbWFlpaDuXbDI1mVKI9KAWAEEJ3Vw3R0tzFT//vEjo7+/ji4muJRAvz1yCd6OGNh/6a7c/9OyiF4UdnQseEnR8Dt0svrEP/Pe6zIf/IhVrJ9t/jzepxlDpOmfLY5NChA/k24cTRf1I0pxjtQSkQpk6vzrcJowqlFE8+toIfPvACu3e1FlwpslKKdU8+yPbn/h2ByvGMiJC3RPjb6ZeLEnhJ+i+h/aFtOQQTkA33UQqEdJ8PVDUCIQTJtM1b68dfKOSll57JtwknhBCCBdffnG8zNOMcLVAKACEEV197Vr7NGHU4juK/n1jFl+/8L7ZvbSkYkaKU4sA7L7Hl9z/F8MWJyCbBBmJEHGXxzuMeIwYsucJEhASJDISIkL4w8baL0HNfrITEjVJq3IV4uro6aGraf/wDRyFCCKqravJthmacowWKpuDZvauVr/31f/O7X79LJjPUKbxjl0RHC2/+6IukOpoDwTGoIGGg/yPHg9J/T38hIg2kYSC958IwPGFigH9c/yUkUtzXyeD8yZSNM45EZGvrYbbv2JJvMzSaUYsWKAVCLB7Bsox8mzFq2bPrCPd/6xke/dfXSafHt0jZt/xpeg/tyvGUMIggyQnehISLH/KRUiINE2lYSNN7NCykaXnbTU+omEhPcLiLRErfi+KLmX4iRfoixT0HCJav3UNfIn2a79apo6u7gyF12NVoCpTCzA4sQC68uJHGqVXs2Na/HbnGx844/NtPlrFlczNfuvs6Jk8Zf43BHDvDvjd+j1Bq0OTXYF3krgu8MBBZ74khJdKwjpkoO2DTgM9jld0pvKJi30vibZZC4GBj2+Prw/y5536HbY9NMVxcXEIsVtj9lTSnHi1QCgQphtssqzCxMw6vvPAe+/e28cA/fZyGSRXjql9Ky/rlHFrzSm7bEo/B2pX0LzcOF4OV2EcwpAA5/D8jgdToH7JRakCZctDBVo4fh28qlaSlpSnfZpww5557AZMnT823GZpxzvj5jdccEyFg2nSd1DZUtrx3iK8v/hVvLNuO44yPb+5KKfraDmEn+3ITXQkV5HhI3N4n/mKKgeuNXWuwyHhhG3PQRUgzyEcJL1JKpJDZ/JQgedbNVZGGfw4/j8UcVwKlo6ONd1a/lW8zTorxJNw1o5Px8xuvOSbSkMz7wIx8mzGmeG9TE3/zpf/mv59YiW07+TZnRNjx3M+D5wMKbrynOUJEgiFDZce43jgphNu8LZwAO8iSm3tihPJNcsVKNvfEyBEm/ZNtxwvbt28hk9GNAjWaY6FDPBrNMUilMvzTP77E7l1H+PRnL2dCXVm+TToJFOme9kFDOeCVF4vBwzpBSbF/jABDilBZ8CAn9NJLVCjxRPg7lLdduevZprHeOb0YlHIUStk4gBAS27ZZv349zz77bJCrMnfuXK655hrkGPKwrFv/Dul0Kt9maDSjGi1QCohzZzdQVh6js2N89ZM41aSSGf7rP1aw9b1DfOcfP0rthNJ8m3RyHCWH9XjixN/nj8ORws0LkdIYvG2sLz5yNqlAuAhUTu8Z4YmTnHiTsMFx7erp6eHr99zDqy89T19fHwCO41BeXs5tt93GJz/5SaZMmTLqQw+OY9PV1ZlvM06K9192Vb5N0BQAY+crh+akmdRYQVFRJN9mjFlWr9rDlz7/nzz3zIYx2dStY9dGuvZvDdaD6hyyM3bCPU5cgSK8xQ33RIxs+Cdud1HfvQG8XJJs7kk4nJObgyJFtr+JENnjgnLl8GMo3COkwaFda3n2D7+nr6/PG98gMQyDnp4eHnnkEe644w66u7vzcGeHR29vD68teT7fZpwUM2acnW8TNAWAFigFxmj/djna2balme/8n6f549Prx5xISXYeJtXdnhUlZMuHA3HiHRtu1Ca9pFhL5uanREhTkmkNNVeTXjO2UN6IMUiztpAIEb4Q8fqmSMPCyOmhkk2gTfe1Y0hBxDLd8JLXBdcyJFIINm/ezMaNG/Nzc4dBc3MTyWQy32ZoNKMeHeIpIKJRi+sXncsvfvZGvk0Z0/T1prn/W8/Q0tzFrZ+YS0lpNN8mDZmggXz/Hij+ekiY+OLE8MI6/TvMKvzy9VAeij/dD7+U2BNxyg3p+BfzhbIr8lS2iie0XeENCkSBrVDdB7m4pIvzS3owhXtmN4qk2JmIsaa7lN/+5ikuu+yyEb9vI8k7q9+iu3tsh3g0mtOBFigFhJSC8grdXGkk6OtN85OHXuPq684eMwKlqLaR4pp6Eq3Z/ht+m7R+xTyBAOnvI/KrfHwdMqF3K1u9XJQgf8QTKKFOJt4mf7sIkmF9tSSlBCFBeXkpymtgpgRCKUyV5kPqdWpr2t3r97Ntcqyb80t6MZO7T/Y2nVKUUmPee2IYBqapPzo0px79U6bRFAglE6dTOqGR1JGmnA/3AQ3bvA2+ByNQAyEvi1+CPKl3A4ZQKGF4IiP0Yv/E4VCYJ0hcb4s3JFAYCOm6RJRy3MURKGwcB4Q0KOvexgTZieWdLji9ytpUYTk0FI3uBPBMJs1zz/8232acFGfOOIdZ55yfbzM0BYAWKAXGRZdMIR636OsbPzNNNEPHD9scs/dcSFwoFMoLzigFKhQa8nuhgERKEZpCHLqY90SE4kp+KEjg5q1kvS7KFSZKoBBuaTEK6aSZceApilQCJSDtR42y0aMAu68LO5XAiMRO6P6carq7u+jp7sq3GSeF9qBoThf6p6zAaJxSiRUxtEApUPweJhBUAQcf8P6641fxePscFSpDVrlCpTzTQl3vJloqLwkSWyGQIqFcFz+s4wWTws9d14lbgiwkrtvEdq+pHIrbNlLWspK4CWkHMs4gNnt27l37BqveeJN4w1lMrCmjuqJ4VCWGv7P6LQ41H8y3GRrNmGDYVTxLlizh5ptvpqGhASEEv/nNb3L2K6W49957aWhoIB6PM3/+fDZs2JBzTDKZ5K677qKmpobi4mJuueUW9u3bd3LvRDNE3LJRTSEiaLzmdrd/iciKjiAS4y/K/bD3F9tR2ErhONltfgJsEX2UZtqCkmHDMDFMC8OMYFjeoxnBsLzFXw8mHnsVPkZ40rGfMOtW55wf3UZfoo/WRK7Act9RLo7j8P8+toS//ac/8L3/72VSo2gytVKKvXt35tsMjWbMMGyB0tPTwwUXXMDDDz886P4HHniABx98kIcffpgVK1ZQX1/PggUL6OrKujUXL17MU089xRNPPMGyZcvo7u7mpptuGrOTPccSZeUxrrr2rHybMS5wHIftW5vzbcaQEUIQq5qYnUws+n3Ah8SH8rwStnJDKmkH0kqRdtxtjgM2rmfkvNZn3FwSr++JkdPPxPLESLasOFyKnC0jDrfAF0FFz7xzqyjd/xqGcK/bnnTtct9PbqWRKSEiwTBdkbTzQAcrN+wbNeXgSimWLns532acNKZl5dsETYEwbIFy44038u1vf5tbb711wD6lFD/60Y/4xje+wa233srs2bP5+c9/Tm9vL48//jgAHR0dPPLII/zgBz/g+uuv56KLLuKxxx5j3bp1vPjiiyf/jjTHxDAkJSWjMz4/1rBtxYo3d+XbjGFRPOlMYmXVQbmx70UJk/WcuOGUjOMKlJQNaUeRsiHlbXeUosJuxVBp1+NhyNCwv3DDNk+EeJ6RnEXK3F4qnjipLjW5dk4ZMWljGa4AAdcuS0I0NCMopxxaGkjDwkHwu9c2kc7oLz4jyU0f+ni+TdAUCCPaqG3nzp00NTWxcOHCYFs0GuXqq69m+fLlAKxatYp0Op1zTENDA7Nnzw6O6U8ymaSzszNn0Zw4JaXRQTuTa8Y/JZPPJlJeHXSH7f9z4Id5bLf1CBnfe2JD0oa+DPTZioStSGQgYUNVz1bqezZ67pjcQYBZr4j0wje5i9/e3q/q8akqNfnsokmYzetp37EWA/ePleWJEktCWdTtbGtJdzH9xfPYCGmwfX8bm3a2nLb7WwgUxUdXXo9m/DKiAqWpye2vUFdXl7O9rq4u2NfU1EQkEqGysvKox/Tn/vvvp7y8PFgaGxtH0uyCY9GHZhOJ6PzoQkRIkwlzF2Xn7IQar/n44R2HkGDBFStJB3oz0JOGvoyiNwMZ22bGkVfc8wuR9Yh4CzgIxADPCSLbO8X9z7WnsdriL66bQGNNFOVkwLEhZK8hXGHUl4HSCMRNdyk2odgURKJxzEgUwzDd93LMkiWNRjNaOSWt7vura6XUcRX3sY6555576OjoCJa9e/eOmK2FiGHobz+FipCSyvM+gGFFkGQHAAYzeEJVPQF+5Y63ZBxXHHSloSul6EpBQ+dqLLs3FKLxPCfCCLwZeKIEX5QE5cYuxVHBVbOK+eKH6misiSKEYPerv3Tt9uwzhes1iRuQyEDMEFREBXFTEDMEcRMi0ThWpAhpRkAIXl+ze9TkoWg0mqEzol+j6+vrAddLMnHixGB7c3Nz4FWpr68nlUrR1taW40Vpbm5m3rx5g543Go0SjY6Nbp1jAYFASi1SRgLHUUMS4KOJ6guuIVZRS0/Lfq+UN7flfc5neT/BokLrSdsVK0IoGto3MLX1NXbFb81OJfbOF9QkB+fIvUA8AhdPizHv7CJqSo2ce9nbvCeYHWTKbDjH8IRKa0LRUCQoMt28GSkFlhXFjMSwMymkNGhp6z35m6YBoKiomJqaCfk2Q1MgjKgHZfr06dTX1/PCCy8E21KpFK+99logPubOnYtlWTnHHDx4kPXr1x9VoGhGlgl1pVw274x8mzEuWPbaVtrH2AegESuh7oqPhaYV57a7P5rUUqHFUdnk2fYktCVsLtj/75ipdpRyApeH3/8kew6FFIqYBZMrBfNnRblrUQW3XFJKbZk5qNAzvOqciPRzTgQRQ1BiQWXUDUXFDCiPQJEJkUg0uJrruRk74nG0U1MzgbPPnp1vMzQFwrA9KN3d3Wzbti1Y37lzJ2vWrKGqqoopU6awePFi7rvvPmbOnMnMmTO57777KCoq4vbbbwegvLycz372s3z5y1+murqaqqoqvvKVrzBnzhyuv/76kXtnmqNiWgZFRZF8mzEu6OlJYdvO8Q8cRQgpqTr/GvY9+y+oZBLl5Xc4uN6UoeJA0BulJQHTW9cz/eDTbG38E7DAsgyKo+53IKVgWo1BfYVBaUwwa1IEy4SYdezvSH7pcDYRVmAGU5VFYLclIWpAGoFhWjjJNEopr4pID23XaMYiwxYoK1eu5JprrgnW7777bgA+/elP8+ijj/LVr36Vvr4+7rjjDtra2rjssst4/vnnKS0tDV7zwx/+ENM0+cQnPkFfXx/XXXcdjz76KIZhjMBb0gyFMj00sKCpnHM1leddScvql9yQn1BIr4usGCwPZTBCHVx70nCoJ8285ke54KbboChGadxk5sSsEDYkmMPMf/KFh+UJE1+cmKGEWYUbbiq2BKZQxDMdpPq8oYNCUFY8On7W9+zZSVPT/nybodGMGYYtUObPn3/MhDMhBPfeey/33nvvUY+JxWI89NBDPPTQQ8O9vGaE+NAtc3jyP1agdIVDQWJEi6g49wpa17yMUirwogiVO6vneD8dAi/cg8A68/1M+h9/R9WFk0csJ8cUboWOEWrGZsjwuitKErYrWIpNh9lHnmWN8TGkaQKCay6ZNipyhA4fPkRHR1u+zdBoxgza91mgSCmOmmugKQzqrvg40op46SIiW3rM0fNQwoQ/85VS7H9vDZG6M0ZUDEy6+jaKTEGx5eaXxE23gqfIFBSbbnJs1HCHEfamFaZpYpSUY9tpdxihkDohfASZf/Ui7enWnDa0QClQysrj1NSW5NuMMU8mbbNn15F8m3FCxCZMpfqCa4MqGb8bqy9U4NhCJRgg6ImaTCrBO499l3Rfz4jZWHbmXIoqaiiLuOXE5RFBWcRNkI2bbtKsKaHEEhTXNFB85y85dO7tQVdaKfXsqZGktrYeqXN6NKcJ/ZNWoNRPLGfGzNp8mzHmSSYzrFqxO99mnBDSijLlw4sxLMsTGlkvit8Kvz/92+OH14VSbH3uFyz5x8/TsnnViPQeiU86i+Ip5xKVUGS5S8x0q3gsKTCEwJCS0otupObOxzhY8z6WrD2AYVogBA21pcycUnn8C2k0mlGHFigaTQFTfu48ys+6NBAj4Q6zEgaqlNB6eCKyxG/05rDjlV/ywv++jeaNb4+ISJn4ye8RqTsDU7jJspZ0c1OkBLNmGiUf/zZVX/g5h0vO5ruPvERnb8YdTIigtDhKxNQhCY1mLKL7nRcw8z5wJm8s25FvMzR5REiT2vfdTNvG5UhAKbeixxDZih5wk2W9RrPu6/zn/jGCoAoIBT0te3nxm3/Kubd8jvM/sRgjcmIDKoUQxKZdiPm//ovUyz9B7XjT3VE1BXPurURmL8QpquL3Szby9JKNtLT3EYmXBi30r7pwkm6DMkIYhkFpSenxD9RoRggtUAqYM2fqjpCFjhCC+vm3s++PP6X74E7XG6KynhRHeY1gVfg1bl8T/3PfFy++SFHe/t7D+1n5s2/S197CnI9/iZK6KSeUQCuEwJp0Huaf/RMoJzCioyfFcyu2sXLD26zf1oTCcFv4GyYIQXlJlFlTK0dFBc94oKKiive//+p8m6EpILRA0WgKHKt8ApMW/SVbHv2GJzQEApUjUnyNEjyGWuL3f+4f6HpkHDb8+mH2vv0cC+59gspp555w4zQhJY4D2/YcZtPOQzyzZCMHWjq9ZFgTKd25P1IaCASTJ5RQWXpinhvNYAgt9jSnFS1QCpia2hIqq4poOzK2WrWPNnbtOEw6bWNZYzPXQQhB+REGArsAACAASURBVDnzsIpKSfZ0DWh7L8mGbnJfmG3qFh406OemqJA3pXPfVp75mw9y3q13csGffNn1cgwDpRRbd7fwu1fXs2LDXvqSGYSQGGbEG1DoTUuWBv4H6dyzJ2CZoyfNbtv2zfk2QaMZU4ye317NaWfq9GoaJlXk24wxzzsr95BKZvJtxklRdtYlVF+8MFgPKnNENpQTrtwZ9LFfDxV/3S9fTrQd4p2f/wNrHn8AJ5Mesm1KKdZtPch9//YiS1fvJpkBw4xgGBbSyHpOhDQ8GxXFcYu5Z4+uEOZbby3JtwkazZhCCxSNRoM0LBpvuhMzXgzkJsMOVm98VNEyWPmxF+4xBAg7zZpf3Mea//z+kESKUor125r44WNL6ejJuKJEmq5AMSNY0SKiRWXESioxrWjwmjMnl1NabA37PmiOTnFxsQ7xaE4rOsRT4Fx59Uw2rDuQbzM0o4CSqbOJ1UwmuWfzYNGcAZU8/cnJT8FdEeGd/jF2mnd/8R0EcMGf/g3SPLqQ2Heogwd/sYzOXhsrWoQZiSOkxIoWuZ4TaYBXsZM2I2RSCexMikm1xbq8eIS59pobiceL8m2GpoDQAqWAEUIwfUZNvs3QjBKMeCkTLruZjj2b3XySwYYGhhTKoAmz/Y/1CFf9CAHKybD+yR/Q+P4bqT7zwqN+M//j8m0kVZxYSQl2Jk2qrwuEINXXnZv4ohSxkgqkYWAIg4vPrjupe6EZiJSG9qBoTis6xFPgjN45Jf1TNd3FMsuIRWpylohVwdCmx5w6nHEwdFEIQd28WzFjRe5nPv1CPcFxR8k/EQNDPMFzkbtIASrRzfJ//ByZvu6j2tSZskin+uhuayLRfQQ7k8ou6SR2OkkmnSCdTtB55ABdrQew0wmqy0fHBGONRnPiaA9KgTP30qk0TKrgwP72U3gVt8KiP5ZRgmkMdBkLaRKP1OZOo/OQMoIUua57pRxS6U56EvtJpds5/gzekaXtSA/LlmzlxpvmnNbrngpKps2hZu4N7Fn6K9eDcgxPSlDBE9ocVPT4K9nDByKgc/cG9r35DNOvvW1QexLdbdjpJJFYCaYVdfucSDNoxIZycJSDY2ew0ylsO4Vjp1HO2E5a1mg0WqAUPPGiCKY1HEeaRIpBfmyEIB6pQYiBcX/LLMU0iwd5iTFAbJwIQkiikQoiVimpdCe9iQMk0x2Ac9LnHgq2rejpTp2Wa51qpGkRraoHcj0og+J7UtTgnpYhObVsm4PvvMi0+R/3SoT7X0MQL60iEi9DGgbpZC+ZdAKB8NroK5SCaLyEWFE5mXSCTF/bEC+uGSqWFeGcs2fn2wxNgaEFSoEjgPLyEgzZl7PdNOJEIwOHrBkyhmUO0u5agCC/MWohDKKRSiJWOal0B6lMJ33JQzjO+BAPp4tJ136KHU//BEPY9GYGbX8yYEN/L4r/5FhJtf5rWze9hXKcQQVKrLgCRQ/J3g7sdNJLN3FQdoZMOolybBDQ29mClAaReAklJeWDeuw0J04kEuGss8/NtxmaAkMLlALHMCX/8L2PsWldBy/84SB7dvXS1ZlmLHeNdD0qlUSsCoqi9fQmm7RQGQZWcTnRkgqM3lZ6M9lBgMFQQBggSny8fNXcx0Geh+lrPcCRre9QM+uyAedLJ3txMmkMK4IZjYNSKKVwHBthGNjpJOEao1Sih4RwON1hvuOx/8Aetu/Ykm8zNJoxhRYoBY4QgkmNxTRMLuK6GyeyZ2cPmzd1sfSlZt5b30EicXrCJKcCIQSGEaUkPoWiaB29yUNaqAyBovrp1Mx6P6m1z9CZUkGzNT+5NZwAGxDKOxkgSrxHR0FGQbrfj1S6t4u+1oOD2iKkxIzE3HJi3B4nSjne9SKgFI6dCbXalzhOZkSmKI8kXV2dtLW15tsMjWZMoQWKBiDwlkw9o4SpZ5Rw/Y317Nvdy5pVbaxZ2ca7q9pIp5wB337HAq5QiVFaNJWiaB1pu4fevgOkMp2M1Dft3TsP4zhqFFdFDR0hBBkFGQeihi9MRNaTQm7+cv/wjv8z4t9ZpdxsIKUUaWegQBGDKh4Xt0uskc1tUg44CiEkUhoow8KxbYRQ3nUVtu1woKWT2sqBeU+aE8Ofb6TRnE60QNEMipSCKdOLmTK9mBs/3EBrS5LXX21hw7sdbFzXQU/32KySMIwYhhEjYlWQSrePmFB54/UdfMl2gm/6Y52UA21JRcwAQwp3cCC57ewHiwD6DdpUaD3rSRFIoehJZ9OXj5ejEo1GkIaVPdL3lCgFQgUCxrFVsD+dsXl3y0EuOGviyd4GjccV866hoqIq32ZoCgwtUDTHxbIk9Q1xPnb7FG7+mE1He5rXX21hxRut7N7RQ0f70OeqjBakMIhFqolaFSQ9oZKxe3HU2HsvpwJHQW8GSi2wZCjEw8D29jkr/UqSB8s98Scke4cfkwWXTmHj3gQZ23FzT2wbR6W9icgKodxJxo5tZ8+mFNv3HCaZyhCN6D9xI0E8XoRhjA/xrRk76N9ezbCIRA1q6ww+clsjH/zoJI4cTrJmZRuvPHeIfXt76RxjYkUEQqUS20nSm2gikWwueKESLXM7DJsSIgYDPShCYCM5YtTi9HP9G9hU2y34aiUsUBwEllQ49tCKwM9qLOe8M2rYsLsL5djYMuMKpIzCUV6oxzARdhocx5Mogu37jtDW2Ud9zSAVZxqNZkygBYrmhIlEXM/KoptjLPjQRPbv7WXLxk5efKaJndu76e2x823ikBFCYhpxSoumURSrpzdxkESypWCFyvSFn2LPiz8nIgURQ9Auq+g2yllnXcgRoxoBZDDZYc1EiaC2BwRYKs30zDaEcvBDM1PSO5ma2Q6ZJLVqP30ZRV8G+mywj+FGkQL+7NpGHnn+ALsO9SAyaWwhvGRZBY4NQiClie34P2+Knr4Uzy3fwqduunhc5AVpNIWIFiiak8ZNQoUp04ppnFrEdTfWs3tHD5vWd/LGUjdvJZVyRlvl56AIITyhMp2i2ER6EwdJZzpJZ47ejn08YhmSmrjB3vhZvBGbz0GjgU5ZTs7UP4SbPCndTFp3kyADbLXmuqXInpjYoi5BKYeI00ddei9VqQNc0ruECYmDtCWP7ksRQlBZYvK5GyfxxqYOnl15mCQC5dgox8bx+p0Ivw5aqeCay9/dxW03XEBMh3lOCiEEDQ2T822GpgDRv7maEcWvBpo2o4RpM0pYeNNEDuztZeWbR1i3pp2177SRSo7+aiBfqJQVn4HjZEim2+hNHPCEykDju7sSNB3soHHK+EgkTJpl/Lbmf7InOpMM5sCyXeH2yRHScEMsUiIQ7qPfhh6Rk0jr9i8pYp9Rwh7rTDbHL+bc5GrO73yV6DH6qgkhKC8yWXBRFUVRg1fWHuFAcwY7kwrOq1Bud1n3FSAErR19vLNpP5efP2XM9vQZDRiGyRXzrs23GZoCRAsUzSnFMASN04ppnFbMh26dRFtrkqUvt7BudRtbNnXR3TX6q4GkNIlHa4lalSTTRzyvSq5QaT3cw5b3Do0bgXLEnMCuovNdEeLYbnkvIhhL7IsRKQ2vksYEId3jPW+GCLq5ZTNopWN6XWMFSVXFmuj17Iicw3mReiYcxyZDCq6aXcHMSXH+5ekku/d1u54UO+M+hrwnAoFtOzz92ibeP2fKoBVHp5NNm9aOut4sGs1oRwsUzWkjEpHUTYzz8T+bws0fn0R7W5q3lh7mjSUt7N3dO+qrgVyhMoFopJpk6gipdAeJ1GGUGv0ia7gIITBM09cjCOV+wvsfskJI11siJcIwvKoadyikK1D8R4L+Ge4gQUUkWhR4P4Q06BJTOGxOZOYQbZtYGeXzH5zGd362n+72bhzHHtie1vPg7G/pYH9LB411FSd9T06GNe+uyOv1NZqxiBYomrwQjRrU1Rvc8v9M5sYPN9B8KMH6Ne28+GwT+/f00tU5ej/0pTCIR2uJRWqCPJVE6nC+zRpROrqTwXMRJMG69ThuaEeCX0EjsmGd/gIl7EUJnBiGgTStoG29EAIphzc7p6zIgHQ3mVQiEEeurcJPRUEIQWdPim17Wpk8oVyHeTSaMYYWKJq8Y0UkkxqLaJgcZ8GH3Hb7WzZ18crzTWzb3E2iL//VQJXVESY1Fg22B2ggXpzm/AvHTyLhqyt3hNrHeyJDCRCeQPFEyUBxIoP9/rbgHO4T/AnEoNxwjxAIOfBPkVKKVHc7rdvX0rrtXfateDHY93bJAvY0xxDSdMufZVhEudkoyhNFr6zYwfxLzjhVt2rcU1FeSSwWy7cZmgJECxTNqMH/9jttRglTzyhmwYfcaqB1a9pZ9eYR1q1uJ50emGBrmMf+Zlw7IcoZM0uOur+k1OL6D9Yfsxy1vMKibuKx/0iPp2/ojpO9ya5HIhuuCQSKX73jeUoCgSJ9geJ7U3xPSihpVoFCgVRETIvKstx7m+rtYvvLT7L+Vw/TtmuTa4f3PwHsmXY2lJxz9PbrWTcKO/YdYe+hDqbU5zfMM1aZM+diamvr822GpgDRAkUzKulfDXTjhxs4dDDBG0sO09yUCI4rLjG5ZmHdMcVFUYlBVXX0lNs8XnAcheP4E4EFKP/fI3CpeNU6WU+Jv/T3ruCJlaxAyf13UsqhpiLK9IZyb13Rsnkl65/8IbuW/hqUwgxFf/wW+4ZhYBgmfsVONhE3e34/YbYvlSGRHL0hw7HAeBLfmrGDFiiaMYFpumGgj//ZlHybMu45eLiTDTuavTVPpEDwKPxpPL7nhKwXBS//xF+kl0ybDfcMLD2eMbkC6W1Mdbez9LufoXvfFgxC837Cn4/CQBkRd4BgqEposA9Rf9vm3Yc5a2rNSd8bjUZz+hheZppGoxn3dHQnSaePkfcT8pSEvSf981CkdMNAwi9F9gb7ScNEGhZSmhTHI1w/dxJSCpTjsOqnX6f3wFakAEO4nWQN6T73l674JNqKzgx6roSTdt3rmV5vlmwTufd2tpy+G6jRaEYE7UHRaDQ5vLpyuxfiETDAK5Htc+KuhnJQZCj044kD4YkUKSTIUGUPbg7KRTMraJxQDECqp52WdUuRKPqnlvh5uq5gMZBWDCVk0L021zMz0JMiDf2n7kS54opr8m2CpkDRv7UajSYglbY50tGXE9gJE5QQB8myIshJkcII+qNI6T+GhAoiCPegYEK5xcK59Rhe/tDhjW/RfWC7e53ggq6b15Bgeh6VmCkxI3HXO+Kh+nf39dNlvPLluuqyEbtHw6Xl8CHWrX0nb9c/OQRTp+gKKE1+GFaI5/777+fSSy+ltLSUCRMm8JGPfITNmzfnHKOU4t5776WhoYF4PM78+fPZsGFDzjHJZJK77rqLmpoaiouLueWWW9i3b9/JvxuNRnNStHX2sn5bk7syWP6HzFbm5CTFBt6SrCjJihNPuBhu+EUIiWVK/nxBI5Nq4jnXD0eMpHBFScSAqARLQsQQlNJDiejDjMQwrRiGFcW0YphWFNOMYpgRDDOCGYlhReJEojHmXdB4Wu7fYCSTCdraj+Tt+hrNWGVYAuW1117jzjvv5M033+SFF14gk8mwcOFCenp6gmMeeOABHnzwQR5++GFWrFhBfX09CxYsoKurKzhm8eLFPPXUUzzxxBMsW7aM7u5ubrrpJmw7//0uNJpCRSnFKyt2kBqQfxIK5+CHU8JlxUbwGBYnQR6IH/IRBqCQAm6YW8uUCbl9ZXxBEuSehBZTQtQQxE2ozhyiJn0Qw4pheCLFtKKh9ShWNE4kVoIZjTNrei2NE45eZq7RaEYnwwrx/PGPf8xZ/9nPfsaECRNYtWoVV111FUopfvSjH/GNb3yDW2+9FYCf//zn1NXV8fjjj/P5z3+ejo4OHnnkEX7xi19w/fXXA/DYY4/R2NjIiy++yKJFi0borWk0muHQ05fmpbe2ZQfuDcCvlmFASbGUhhvi8efzhDrMul4UgVJgSsENl9SwaG5tENoJzi5cL4mtsrVD2dwTgSnBEmAYYJoWphUNWrN5jVVyO9y6E3m44X2NmIYukz0RIpEIpmnl2wxNgXJSVTwdHR0AVFW5A9J27txJU1MTCxcuDI6JRqNcffXVLF++HIBVq1aRTqdzjmloaGD27NnBMf1JJpN0dnbmLBqNZmR5b2cznT1ui/twQbGPGLBHQJBv0k+c+CEfwxcnbpv8GRPjLLp4oDjxz2x6FTv+HybliRVHKb/vGlEDLNPEisaxYiVEYiVE42VEi8uJFlcQK6kgGi8hGo/zocsaOG9ame7jcYKcO+t8zphxVr7N0BQoJyxQlFLcfffdXHnllcyePRuApiY3dl1XV5dzbF1dXbCvqamJSCRCZWXlUY/pz/333095eXmwNDbmL56s0YxHHEexccchUhk7ND+Hfv1H3Fb3/nM3MTZc6pvNMfHXARwvdDu5JsafXdPA0cbulJ9xAaV1UzHd/m7uaxVkHEjakLAVKS/6ZFkRrGgxkXgp0aIyIkVl7mOsGCsSp7Iszo1zq1k0t3pQMaQZGtL7N9Zo8sEJV/F88YtfZO3atSxbtmzAvoHdItVxv8Ec65h77rmHu+++O1jv7OzUIkWjGUFa2rp5ZeUO93dQweAhHhXs698HJZhsHJQgCxzb7d4qDZPGmjh/ecNkqsuso/6eRysmEC2toLd5N45wQz2OyoZ8Ug4kbYUDzGx9nsOTb8CwIkGTt1hE0FhlUF8uuezMGFUlUntONJoxzAkJlLvuuovf/e53LFmyhMmTswPS6uvdeQ1NTU1MnDgx2N7c3Bx4Verr60mlUrS1teV4UZqbm5k3b96g14tGo0SjulW5RnMqUErx/Btbae9K5PQ4GfDhrvBa1/ut5UMVPH6JsZCgFI6y3W/fhkXUFPyP6xqoLY8c2xBpMOnaT9K1cx22coL8EkdlH9M2JGyYVFfJJTPiNNbEOKPO/TMWMdCiRKMZRwzLd6eU4otf/CK//vWvefnll5k+fXrO/unTp1NfX88LL7wQbEulUrz22muB+Jg7dy6WZeUcc/DgQdavX39UgaLRaE4dh1q7eXXF9qAVPQzSny0HFRyTO3vHe62UGKaFkCamhJveV0N91fG/YAghqL/6duLVE4Nqnty2+K5ISWTA7mvlT64o54qzo0ysMJhYYVBdamhxMsKce+4F+TZBU8AMy4Ny55138vjjj/Pb3/6W0tLSIGekvLyceDyOEILFixdz3333MXPmTGbOnMl9991HUVERt99+e3DsZz/7Wb785S9TXV1NVVUVX/nKV5gzZ05Q1aPRaE4PSim2723lSGfCa6bmM/CDXimFUA5KeQ3SAnEisvv92TheUuxN76tj/vnVxxzmGMYsLqfyvCvpfe2/MKRCOmBnS3UCDm1+h7bdm6icOmv4b/o0s27dO9j22BxWeNFF79OiT5M3hiVQfvzjHwMwf/78nO0/+9nP+PM//3MAvvrVr9LX18cdd9xBW1sbl112Gc8//zylpaXB8T/84Q8xTZNPfOIT9PX1cd111/Hoo49iGAYajeb0kUrbPL1kUygp9lgfRiqoxoFsjY9SDkrZ4ICD65ZVQnLmxCLef07FkMUJgDQtGm+6k+YVf8Dp6caQkLFD+sTL3+05tJvn/+7jzL71i8y6+a+Q5uhtir15y0ZvdIBGoxkOw/qtdv84HRshBPfeey/33nvvUY+JxWI89NBDPPTQQ8O5vEajGWFWv7efzbtbGDwpdiBKZUWKUgrHybheFekgpYPExAGiEfjIvHpK4sMXDsWTz6Godgrp3k2YQpHxHDLKKyKSuOZ2H9jGmz/+KsnuNs754GeIV9Xpb/sjzfH/5Gs0pwxdP6bRFChKKZas2un2F2GQpFhUvwVQDspxcBybTCZJKtFLKtFDKtFNJtWHnUnj2Bk+eGkdMxqKT0gwGEVlTP7gF5CGDDrJ+g3bcpq3AcJOsepn3+T5v/84PS37hvQlSqPRjA20QNFoCpSDh7tYt+2Qt+Z9/AeCwm2MFl58keI4GTLJPlJ9XaT6Okn0ttPXdYS+7jbSyV4qiiXzzqs+YW+GEIKauTdiRIvdXnAiNwLlixQZmtfTunkFL937J/Q07z3h+6HJpbysgtrauuMfqNGcIrRA0WgKEMdRPLP0Pbr7kjnuCb9D7GCOCFeoKM+DksHJpLHTSTLJPtLJHhLd7fS0NxN1Onh2yXqefPYdXnl7K22dvbR19pJIDT1RNFrdQPVFC3D8vnDkTjjObYPvelnatqzk1W/9KX3tLSdzazQedXUNTJt2Zr7N0BQwozezTKPRnDI6uxMsfWcnKJGtvAH3U1/5CZ0hleL3aMN1pyjlhnlUaMCnwiGd7GHtxh2s3bgDAMOQxCLun5mzptYyub6S918wlcb6SirLcocFhhGGSfXcG9i99Nc4fgzKu3xgrtf63p/bA9C+bTVde7cQr6g98Zuj0WhGBVqgaDQFyLtbD9KTSIc+7fEUSG6ljitM/OcKhetBUY5XuXMcbNuhpy8FuAm5q9/bzzNLN1JbWcKNV87i4nMbmTKxAjlI//vSGRd6vVnsrCclVHIswmZ7CGWz88XHmDDniiHfC41GMzrRIR6NpsBIpDI8vWQTth2KnwCuFAl7Tbx15T33wjtKObgN573XCjnUIiDAFS1Nhzv52W/e4svff4qnXlxLe2fvgARXI1ZCUUUVRSZEJcQMiBsQN7NLzHCXqOEl0wLKGT09R1Q2gWfsoQuiNHlGCxSNpsA4dLiLpsPdoZyT43eOzfGq4D/1G7W5z0+EVNrm0d++zVd/8DteXbEN2872CymZeAbWtLmkHKiIQmUUKqMid4lBVdRdYsYJm3HK6Ozq4I03X8u3GSfEwgW36LJtTV7RIR6NpoBQSrF2axPdfanQ1OJwIoc7a0cpP8Fj8G//wvOaCIRf23Mi1gSa5+DhTv7vfy7ljTU7+eLtV1FWEsOzjPKIIBYxsEXkaCMMUQqiwsZOJEeVRrEzGTo62vNtxglRVVWjBYomr2iBotEUELajeHWlm8Aa/iR39UlONgdZj4nwtEqog2xQVuP5YJQ4Ae+F8Lriu96ZZCrDG2t3kbEdFn9qPkXxCLtL5tJcZXLYqGOncYZXCS2R0siZnAyKeKaDM3tXM7VYJ8hqNOMBLVA0mgKiL5mmx/eeAANVhXJzSrwEWIFACb+Nq8iVLcIvSVahCcdDx893EZ6nxq8SWrFhLz967FVuvf5Cfnd4Buny6Th2BuVVFxmGhWFFkYbpCRUJQtCeSbOi5CzKKidx6bDvjEajGW1ogaLRFBAbth2iua0np3onJ4VEKYR0P/D95my+SBFKeDolGxIKCx2VI1+OjwgLGgEi1EZ/5YZ9HDzcje0o12NiWG75sxCuQDEjWYHieVPMSAwBzD1/xsncIg1gWRHKSsvzbYamwNECRaMpEJRSLF29y1vrL05yQzoBfnsUX5z4k4pl7jmUkNm1EypaCeW8eNVD+w+1I6SBYUa8cI6BlDIQJu6jiTRMhHT3VZREmd5QcSIGaELU1tZx0UXvy7cZmgJHCxSNpoA43N5LICwGVN/42yUI6fU5CRRKVpwIkXO8O8RPZDVOTqRnqGpFZPNghF+am20KJ70wjpAGwjA8QWIgTQvDtDyvismnFp1BTXlsuLdFMyg6QVaTX7RA0WgKhMPtvbR39QGDiZMsQgDSQCgHfyZPTuvW3KNzzzLglLlhn2PJFZHzzBUqyhMoSkiEJ1Ck8MSJF+oxrSimFeHqOdXMnlZ2jCtoNJqxhBYoGk2B0NTaRUtb75D6lkhp4DiZkCZRKHW01wy9gifUE25QlNcqVgQlztlSZCEMhBfiMawIhhXFisRccXJ+DR+9fAKWqVs7aTTjBS1QNJoCQXg9To55TCiUIqWJY2fw4zbHa+Z2tM1qMPVyFKXilyz7ThsRyksRQrjeE8PCMKOYVhTDtLh6TvWoFSdr3l1BItGXbzOGzSVzL8c09ceDJr/on0CNppARIidII7yyXSEEhmkhpEQ5No5jB7N6jnKio27O3ROe8XOU14lQRkq/nBbh551YEUzT4qo5VXx0Xt2oFCcAe/fuIpNJ59uMYTNt2pkYhpFvMzQFjhYoGk2h4YsS4XtUsirCFydCyKDc2EEgg1wSFY66ZE+JGDBUcHBBI4KHrO7IPSab89I/5cX1ohjSRErJVXOq+dgVE0etONFoNCeHFigaTQHhig6ZDfcIvzg42/Y+CPMIiZQEgkT1C9b4fVL8Bm74IsXLHXEH5RFsGzDPJ2tV7loo/BMWK36jtkwmydkTyrn1Si1ONJrxjBYoGk2hIARSmjmek2xOStazgZBZD4oSSMAR2ak7A8RIKEykyIoS4VXg+A3YBNmqnKFN+PXzXrwes45Dsq8Lp+sIcrLBocMdlBW7JcVSCkqKonp2zAgghCASieTbDI1GCxSNplCIWCaRiEXGa2/ih3lcRNCvzRUnIgj1KCEQ0glm8fgEAsQLC7miBLLeE4VSEkVWpOA4QWfa4QgVcAVKJp3EyaRZsmILK9btxJCuB6U4HuGGK2dx5cVnUF1RjGXq/IkTpaysgg9ceX2+zdBotEDRaAqFGZMrmNZQxfb9HdlS46Bdfb88FCmzXha3bSzK8USKINvxVYls2MgTG0ophHICkSKUn5/iuB1olcoKE+GFcY4a/smilONWFXmVPX2JbPJpd2+Sf//d2/znM6v48DVzuGn+eVSVF4/YvSskhBBYlvagaPKPFigaTYEghWBCVQk7m7q9ymERCJXcHBThhXn8RFW/Y6zMSX5VygFHBB4X9yBXoCik6y1Rjts/RTn4GsVvwkZYmAR9T7z92eFAQa6tMAyEnRVL/VFAKmPzyxfW8Pb63dzzVwtoqC3XYR+NZoyiM8w0mgJBCMG88ydhGKY3x0YGLeOD9vHeo5AyuwjvOMN0K2gM97hgDo5f9SP81xpegq3MniuU1yKkl6SLzOa7CBFUDSFCj9IIzotyG8hJ6V+/3+LZJKTBnqYOvvtvL9F0uCtvQ0zy6QAAIABJREFU91sphTOIkNJoNENDCxSNpoCYNbWShgllrkAJTwP2hYonKKQnKnzxIkNCRsrskD5fEIgcseCLk5Aw8RJzB0wwxkuDCZJ2Q2XOoXLnrFgKiSCj3xLY4dq251AHzy57b0DuzOkimUzw8ivP5uXaJ4NlWtrrpBkVaIGi0RQQRTGTBZc0YloRpGEhpJkVH4HAMHM8IVmREPK29BcnnuBxhYIMeVRkqJw59JiDCMqec8SJDIsV3w6RFU6i/xIWM+77WLJ6Fwfz5EVxHIfu7s68XPtkmD9/EcXFJfk2Q6PRAkWjKSSEEFw5p45LZ03AMCMYpoU0razA6OcNETleFukJGt+D4odVPPHQzyMT/hYuQkm4uQOUB4oVQjkwvliRA7wxMiRgxEAh4+3v6E7y3PItefOijEVisThS6o8GTf7RSbIaTYERjRgsurSBXc0p2rqSQbWNTzAHJ1vW4xXuqEAg+EmtwrFx7DTgigjl901RuW3dcprK+gU8wbX6N2rr16PFe5TSCJ3AfbXyy5eVE9qX7UYrhGDngfYTvlcajSZ/aIGi0RQg0+qK+NwHp/Nvz++nvTvlVcV4H+79jg3qaZQKwjfeBjex1RMM0jBxHNs7lyc/QgJCeaXHKnQF0f9KOZVE2Zb8ANI0XJevctwZQV4fFuU4wbwgv7eKTqHQaMY+WqBoNAWIEIIzJhbxV4sm84eVR9h6IIGjbJRzvH4kIuiD4jZeAylNFGCYEcgkcYTwxIi3+OLBcbx29f1FSngwT0iceELI96gYVtR9reN4XW7xzpvBsd3Kn+AaQV+V7HkKBSEFsag1hAPBMiM5KrG2ZiJnnnnOqTNOoxkGWqBoNAXM9Po4f7VoIq+u7+TNLb2092ZQzuBzc5TjYGdSbqhFGG7res9V4Ti2JwRE1qNhZ9zFsVG+QCE3nJTr6ugvTrJ9WgwrghWJuaW7diYQKMLJ4NjZnil+m5XAdBEODeUX960JYjELIQXRqIVlnRrbLMuiqCi3Ud2ZM86joWFqzjEfuPIGIpFosC0eL6a8rPKU2KTRDBctUDSaAidqSRZeWM77zy7lra19rNzeR2efQ9rOnUislINhWuHPfpTj4MgMtp0OxIVjp7AzSTLpFI7jCh78zrKhVwshPCeHAsKda8OTjN3jDMPEtGIoFE4mjZAGyrEh43lU/N4phDwyntApimc/gE8nQgiqqycQjVqYlkEsZmEYEikHq2Q6OS695CoqK6qD9ZKSci695KqcROVYrIhoNDai19VoTiVaoGg0GoQQlBcZLDi/mKvPLWZnc5r2XofVu5L0JhVdCYfeZL8sV7Lt52U6hWNnMKRJOtlHOtmLY6eD3BYVNIf1K27CV5e5FT6hYYb+9mhRuRviUQrbK3/OpJNZG7z8EwHu7KBQVc+1l047VbftmMRicR76p38HBilWGmEikeio8RRpNCOFFigajSZACEHUgnMmRVBKcekM1/vQ3OFwpCdbKWM7sGJHmlTGq6RxMtiZNKlkglUHesikEgNP7rfIxw3fuNcjZx6Q6OdZEAikYWFG4hhmxA0ReRVETqKbTCpBJpNyK4m80FG4zDgWiVBWnJ8px0II4vGi035djWa8oAWKRqMZFCEEhve5PrHSYGJl9hu6Uoo5jQMTMbt6U9y1xiap/Eoe33ESEgjKm8XTv3FbUFUcbuoGNVXlzDl3klcU5GCnkxxp72DNwcNk0kkv8ZaggRuhPJb66mJmTKoYsXui0WhOH8NKb//xj3/M+eefT1lZGWVlZVx++eU8+2y2lbNSinvvvZeGhgbi8Tjz589nw4YNOedIJpPcdddd1NTUUFxczC233MK+fftG5t1oNJrTQm6DtOzS1NJJKpXO9icJhv2FE25DjVCCx9xOs8LrvYIQXHleJZ+ZX8Znrinjs9dW8LlFdSyYU0yyrysbRgquR7alvhBMrisd6XQPjUZzmhiWQJk8eTLf/e53WblyJStXruTaa6/lwx/+cCBCHnjgAR588EEefvhhVqxYQX19PQsWLKCrK9tqevHixTz11FM88cQTLFu2jO7ubm666SZs2x7Zd6bRaE4riWSa3726gb5EKlvmG4R1BiM0n0cMpiPcfRfMrM3Z2nS4k//4w0qvpNg7s1IhT43XiRbBBWfWInVTFI1mTCLUSfaArqqq4vvf/z6f+cxnaGhoYPHixXzta18DXG9JXV0d3/ve9/j85z9PR0cHtbW1/OIXv+C2224D4MCBAzQ2NvLMM8+waNGiIV2zs7OT8vJyOjo6KCsrOxnzNRrNCJBIpfnX/36Tl97ehu8JEZ5IyGm+BiCEN0tHZlvihwYKhhu01VUW8fefuYzKUrf6pOlwJ9975CW27z+SbasfzO4x3Nb93oyg0uIof/vp9zG1Xv+N0GhGC8P5/D7hDka2bfPEE0/Q09PD5Zdfzs6dO2lqamLhwoXBMdFolKuvvprly5cDsGrVKtLpdM4xDQ0NzJ49OzhmMJLJJJ2dnTmLRqMZHSRSaV55exsvvrnFa/QGILIOlH4IcnNMcn0n/397dx8cVZXgffzXSSdNEkILAdI0EzHsZNZhElcnKBrdgVnedGGoXavEEURmZJ/CRZAoLMq4VctMOYlateBOOesuLAWOLE925kF8WJfRBEeiGJBsAA1hFvABgUja+BI6CSTdSfo8fyS5pPMCaWiS2/L9VN3Svvf07XNPIP3j3HPODR8oO2LYEN0w1KVQyKhk71E9969v6/9Vf3XxHF3f2e1BhKOHJ8s7MnwtEACxI+JBspWVlbrrrrvU3NysoUOHavv27ZowYYIVMNLT08PKp6en69SpU5Ikn8+nxMREDR8+vEcZn8/X52cWFhbq5z//eaRVBXCNNQdbtP63ZXrnw+PtS5r053aKlSMuhpS+3nXHBI/ONTTp3/7PXu37+FMFW0MXn1js6NIrYz1k8OLJ7sweI2f89bWKLPBNEnFA+dM//VMdOnRI586d07Zt27Rw4UKVlpZax7v/gmp/wNilf2ldrszq1av11FNPWa/r6+uVkZERadUBRIkxRs2BFm3Ytle79h2VOhdK6xo4eh1XYh3tcaz774CkxHid/fxLPfPWPp2t9csRF9f+lF1H3MXPC5sB5LBWkXU6HRp1w5BBmV4MIDoiDiiJiYn69re/LUmaOHGiysvL9U//9E/WuBOfz6cxY8ZY5Wtra61eFY/Ho2AwqLq6urBelNraWuXl5fX5mS6XSy7X4KwGCSCcMUbHTn2hX299X5/WfC3TcVvGespx11BgjT8JP0fYwNiud2YcUuczdILBoP5r98dqDrZaY1UccXHWQm6d4aNzoG37q/YHCA5JjNeEm9IEIHZddf+nMUaBQECZmZnyeDwqKSmxjgWDQZWWllrhIzc3VwkJCWFlampqdPjw4UsGFAD20NLapp3vH9ELG3fp5GdftS9pYoWFOFlRodt4kC6LnFwMMr0d7zJopTkQULDNKC6+fdDrxQGxcRcXdgtbXiVkTW82hlmBQKyLqAflZz/7me677z5lZGSooaFBRUVF2r17t9566y05HA7l5+eroKBAWVlZysrKUkFBgZKTkzVv3jxJktvt1qJFi7RixQqlpaVpxIgRWrlypXJycjRt2rRrcoEAoqOu/oK27/pY//fdSoXak0lYr0n3zGE9GSdsX1/PoTEdPTEXhdpaFRfX5VdUlynJkqM9uMjREV7iLgYTY/TtsTco8Ro9iA/AwIgooHz++edasGCBampq5Ha7dcstt+itt97S9OnTJUmrVq1SU1OTlixZorq6Ok2aNEnFxcVKTU21zrFu3To5nU7NnTtXTU1Nmjp1qjZv3qz4eH6ZAHb16dmv9fy/lehsrb+9k8MKC3EX1zLp0ntyMUhIvfaUSLJCSdepPg4jY9pDjTOhfYl6Y8zF83ZMJ5YcGpIyTMa097DEdexrCZxX83m/xo4eSkABYtxVr4MyGFgHBRgYbW0hvfGHSv3Xe1X64uvGi70lkvUE4a7hoXNgSdcpv10Hqlq3aeK6PL24Y82Ui6vISi3NDTrx4W8Vag2GrRDb+dmm8/M7+l2Moz0eGRNSa7BZP10wV08u/V8D2lYALi+S72+exQOgV21tIb2+6yNt3Vmh1rZQWAjpvqBa2GzfLr0k4YNjuw4YCd9lZKzH8xgjnf/6M9VVVyrU1qr+/huq68DZT/54SMFgUImJiVdw5QDsgIACoAcrnPz+gFrbTLfeEuniyrBdpuJ0P66O/Z3CworpmKvT8exASaaja8Qh6dzZP8qE2ge6dt7m6S6sZ6bbNKF9+/bpwoULBBQghhFQAPRw+BOf/vfvD6mtTe23Y8KCR/dQoh7hRB37+mIkOUxHSHFcDCmd41I6u1gutY4Ja5wA32wsswigh7c+OKo20xFOOntPOgbEXpy103VKcafOcSd9n9uYkGRC1lOOraced04RDrWqNdgU9p7enpx8KefPn9eBAweu6NoB2AMBBUCYL+rO69jpL7uEgY6Qol6CiaOzT6XLKrJde1E6A0vH4Nj2cNIRSkyo/UaPtXZJ+zomLYHzqquutOrTWzi5XFAJBAI6ceJEv8evALAfAgqAME3NLfI3Bi4uihYWCLouad85WFY9wklcfILkcCjO6VRcfIKcCS45E4e0Twl2JiguvuPushVWOrfQxddX6e2331YwGLzq8wAYHIxBARDm7FcXOtY36RzK2i5s0Kujl70dIcWZmKQEV5Jami8oLiFRDknxzkTJ4ehY2yReklGorVVtrUG1tbaE93R0Cyd99YJc7jaPz+dTa2srj8kAYhQBBUCYqpPnlDAkVcGmRjlkOm7DtB8LnzkTJ8XFhU3OiYt3akjKDYp3JkhGik9IlMMR195j0p54rHEsJtSmUKhNzefPqa0lIBkpFGpVa/BCWDDqy+UeMlpTU6P3339f995775U2BYBBREABEObUwTd19vAZtbUGlTzcq+HeCQqFWiVJcXHxHdODHRqSOrJL8LASjBISh0iOOMXFJ8gRF6dQa1AtzY3W8e6h4lz1YZ2rOSYjKdD4pRpqTyjU2tyvul5qjElbW5t2796tGTNmtD8FGUBMIaAACNPc+KU+PbBDUvvgVmu8SBeOOKdGj5/Yfuumk+mYJGytItseZS6cq9E537E+Py/U1mqteSJd7KWJxjTi8vJynT9/PuxxGwBiAwEFQA9WODCh9tsvPQR09o+l/T5X2HL1l/q8Pl5fqRMnTujAgQOaPHlyVM4HYODQ7wkgTNfpu9GYptv1HN3Pd6mpw1cyvdhaS6XL57zxxhtMNwZiED0oACznz5/X6dOne3zJX43ewsTlekgcDoc1bqS3sp116/rfzkGz8fHxcrlcGjp0qH7wgx/oO9/5ztVeAoBBQEABYPH7/froo4+u+jyXek5Of7jdbs2bN09OpzPsFlH3/3Yyxiiu4wnJmZmZuuOOO+R0OjVq1CiWxAdiFAEFQK+6frFfrjcl2mNIhg4dqqVLlyopKemqzgMgdjEGBYBlz549va6+2p/xIP19Tk5/BINB1dfXX/V5AMQuAgoAy8mTJ9XW1tavsBHJw/siVVtbqw8++CCq5wQQW7jFA0BSe69FdXV1j/1XGz66jiGJROfD/hhDAlyf6EEBIEm6cOGCysrKJF3b3pH+Kikp4WF/wHWMgAJAktTc3KxQKNTrscuNQbnUOiVXOl35xIkT+u///u8rei+A2EdAASBJKi4ult/vH+xqWFpbW1VbW8sia8B1ioACQC0tLdq1a1dUw0A0bg/97ne/i1JtAMQaAgoAtbW16dNPP5UUvefgRENVVZU++eSTwa4GgEFAQAGgsrIy+Xy+wa5GD/X19Tp48OBgVwPAICCgANc5Y4zKysrU0tIy2FXpVXFxsdra2ga7GgAGGAEFuM41Nzfrvffeu2SZrk8J7m271Puu1t69e3X69OmrPg+A2EJAAa5zFRUVvY7z6E8A6Vr2WmlqarpsgALwzUNAAa5jxhjt3LkzLGD0N5T0dq5rEVSMMdq3bx+LtgHXGQIKcB1raGiI+iDUrkElWjOCdu/ercrKyqicC0BsIKAA17Hjx4/r6NGj1+Tc0exNaW5u1jvvvMOibcB1hIACXMd++9vfXtMv/Wiee+fOnWpsbIza+QDYGwEFuE61tLToiy++GOxq9Fttba0+/vjjwa4GgAFCQAGuU9XV1dbTi2NBU1MTq8oC1xHnYFcAwOAoKSlRMBi0BrXGxQ38v1d6uwVkp6X2AQweelCA61ReXp7GjBkTFhI6H/B3qS1aOj+3e0jp/trhcCgpKUmzZ8/WtGnTovb5AOztqgJKYWGhHA6H8vPzrX3GGK1Zs0Zer1dJSUmaMmWKqqqqwt4XCAS0bNkyjRw5UikpKZozZ46qq6uvpioAIpSdna0FCxZo6NChiouL63f46E+I6W+w6RpSuq+jMmTIEN10001asGCBtm7dqnXr1mns2LFXf+EAYsIVB5Ty8nKtX79et9xyS9j+F198UWvXrtXLL7+s8vJyeTweTZ8+XQ0NDVaZ/Px8bd++XUVFRdqzZ48aGxs1e/ZsnrcBDLBFixZp69atmjJlSo9AERcX1+cWjR6Wvj5vxIgRWrx4sTZt2qRt27ZpzZo1uvXWW+V0ckcauJ5c0d/4xsZGzZ8/Xxs2bNBzzz1n7TfG6KWXXtKzzz6r+++/X5L06quvKj09XVu3btXixYvl9/u1ceNGvfbaa1Z37ZYtW5SRkaFdu3Zp5syZUbgsAP2RkJCgnJwcNTY2RjQGpbcg0tvibH3dvklOTlZra6skaezYsYqPj1dGRoZ++MMf6jvf+Y5uv/32QRkTA8A+riigPP7445o1a5amTZsWFlBOnjwpn8+nGTNmWPtcLpcmT56ssrIyLV68WBUVFWppaQkr4/V6lZ2drbKysl4DSiAQUCAQsF7X19dfSbUB9MLhcOiJJ56w/l7V1dVpx44dCoVCkvoeK9La2qrjx49fspzD4QgLLi6XS8uWLdP3v/99XbhwQaFQSHfeeaecTqccDocSEhKu7cUCiBkRB5SioiIdOHBA5eXlPY75fD5JUnp6etj+9PR0nTp1yiqTmJio4cOH9yjT+f7uCgsL9fOf/zzSqgLoB4fDoT//8z+3XhtjNG/evMu+r6WlRR999FHYrdneZuUcPXpUe/bskSTNmjVLf/3Xf81MHQCXFVFAOXPmjJYvX67i4mINGTKkz3Ldf/kYYy77C+lSZVavXq2nnnrKel1fX6+MjIwIag6gv/o7lsTlcumOO+64bLm8vDz99Kc/jUbVAFxHIrrJW1FRodraWuXm5srpdMrpdKq0tFS/+tWv5HQ6rZ6T7j0htbW11jGPx6NgMKi6uro+y3Tncrk0bNiwsA0AAHxzRRRQpk6dqsrKSh06dMjaJk6cqPnz5+vQoUMaP368PB6PSkpKrPcEg0GVlpYqLy9PkpSbm6uEhISwMjU1NTp8+LBVBgAAXN8iusWTmpqq7OzssH0pKSlKS0uz9ufn56ugoEBZWVnKyspSQUGBkpOTrXvabrdbixYt0ooVK5SWlqYRI0Zo5cqVysnJYREmAAAg6Rosdb9q1So1NTVpyZIlqqur06RJk1RcXKzU1FSrzLp16+R0OjV37lw1NTVp6tSp2rx5s+Lj46NdHQAAEIMc5lo+a/0aqa+vl9vtlt/vZzwKAAAxIpLvb1ZCAgAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAthNRQFmzZo0cDkfY5vF4rOPGGK1Zs0Zer1dJSUmaMmWKqqqqws4RCAS0bNkyjRw5UikpKZozZ46qq6ujczUAAOAbIeIelO9973uqqamxtsrKSuvYiy++qLVr1+rll19WeXm5PB6Ppk+froaGBqtMfn6+tm/frqKiIu3Zs0eNjY2aPXu22traonNFAAAg5jkjfoPTGdZr0skYo5deeknPPvus7r//fknSq6++qvT0dG3dulWLFy+W3+/Xxo0b9dprr2natGmSpC1btigjI0O7du3SzJkze/3MQCCgQCBgva6vr4+02gAAIIZE3INy/Phxeb1eZWZm6sc//rFOnDghSTp58qR8Pp9mzJhhlXW5XJo8ebLKysokSRUVFWppaQkr4/V6lZ2dbZXpTWFhodxut7VlZGREWm0AABBDIgookyZN0m9+8xu9/fbb2rBhg3w+n/Ly8vTVV1/J5/NJktLT08Pek56ebh3z+XxKTEzU8OHD+yzTm9WrV8vv91vbmTNnIqk2AACIMRHd4rnvvvus/8/JydFdd92lP/mTP9Grr76qO++8U5LkcDjC3mOM6bGvu8uVcblccrlckVQVAADEsKuaZpySkqKcnBwdP37cGpfSvSektrbW6lXxeDwKBoOqq6vrswwAAMBVBZRAIKA//vGPGjNmjDIzM+XxeFRSUmIdDwaDKi0tVV5eniQpNzdXCQkJYWVqamp0+PBhqwwAAEBEt3hWrlypH/3oR7rxxhtVW1ur5557TvX19Vq4cKEcDofy8/NVUFCgrKwsZWVlqaCgQMnJyZo3b54kye12a9GiRVqxYoXS0tI0YsQIrVy5Ujk5OdasHgAAgIgCSnV1tR566CF9+eWXGjVqlO68807t27dP48aNkyStWrVKTU1NWrJkierq6jRp0iQVFxcrNTXVOse6devkdDo1d+5cNTU1aerUqdq8ebPi4+Oje2UAACBmOYwxZrArEan6+nq53W75/X4NGzZssKsDAAD6IZLvb57FAwAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbIeAAgAAbCfigPLZZ5/p4YcfVlpampKTk3XrrbeqoqLCOm6M0Zo1a+T1epWUlKQpU6aoqqoq7ByBQEDLli3TyJEjlZKSojlz5qi6uvrqrwYAAHwjRBRQ6urqdPfddyshIUG///3vdeTIEf3jP/6jbrjhBqvMiy++qLVr1+rll19WeXm5PB6Ppk+froaGBqtMfn6+tm/frqKiIu3Zs0eNjY2aPXu22traondlAAAgZjmMMaa/hZ955hl98MEHev/993s9boyR1+tVfn6+nn76aUntvSXp6el64YUXtHjxYvn9fo0aNUqvvfaaHnzwQUnS2bNnlZGRoZ07d2rmzJk9zhsIBBQIBKzX9fX1ysjIkN/v17BhwyK6YAAAMDjq6+vldrv79f0dUQ/Kjh07NHHiRD3wwAMaPXq0brvtNm3YsME6fvLkSfl8Ps2YMcPa53K5NHnyZJWVlUmSKioq1NLSElbG6/UqOzvbKtNdYWGh3G63tWVkZERSbQAAEGMiCignTpzQK6+8oqysLL399tt67LHH9MQTT+g3v/mNJMnn80mS0tPTw96Xnp5uHfP5fEpMTNTw4cP7LNPd6tWr5ff7re3MmTORVBsAAMQYZySFQ6GQJk6cqIKCAknSbbfdpqqqKr3yyit65JFHrHIOhyPsfcaYHvu6u1QZl8sll8sVSVUBAEAMi6gHZcyYMZowYULYvu9+97s6ffq0JMnj8UhSj56Q2tpaq1fF4/EoGAyqrq6uzzIAAOD6FlFAufvuu3X06NGwfceOHdO4ceMkSZmZmfJ4PCopKbGOB4NBlZaWKi8vT5KUm5urhISEsDI1NTU6fPiwVQYAAFzfIrrF8+STTyovL08FBQWaO3eu9u/fr/Xr12v9+vWS2m/t5Ofnq6CgQFlZWcrKylJBQYGSk5M1b948SZLb7daiRYu0YsUKpaWlacSIEVq5cqVycnI0bdq06F8hAACIOREFlNtvv13bt2/X6tWr9Ytf/EKZmZl66aWXNH/+fKvMqlWr1NTUpCVLlqiurk6TJk1ScXGxUlNTrTLr1q2T0+nU3Llz1dTUpKlTp2rz5s2Kj4+P3pUBAICYFdE6KHYRyTxqAABgD9dsHRQAAICBQEABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2Q0ABAAC2E1FAuemmm+RwOHpsjz/+uCTJGKM1a9bI6/UqKSlJU6ZMUVVVVdg5AoGAli1bppEjRyolJUVz5sxRdXV19K4IAADEvIgCSnl5uWpqaqytpKREkvTAAw9Ikl588UWtXbtWL7/8ssrLy+XxeDR9+nQ1NDRY58jPz9f27dtVVFSkPXv2qLGxUbNnz1ZbW1sULwsAAMQyhzHGXOmb8/Pz9eabb+r48eOSJK/Xq/z8fD399NOS2ntL0tPT9cILL2jx4sXy+/0aNWqUXnvtNT344IOSpLNnzyojI0M7d+7UzJkz+/W59fX1crvd8vv9GjZs2JVWHwAADKBIvr+veAzX6+1NAAAKXElEQVRKMBjUli1b9Oijj8rhcOjkyZPy+XyaMWOGVcblcmny5MkqKyuTJFVUVKilpSWsjNfrVXZ2tlWmN4FAQPX19WEbAAD45rrigPLGG2/o3Llz+slPfiJJ8vl8kqT09PSwcunp6dYxn8+nxMREDR8+vM8yvSksLJTb7ba2jIyMK602AACIAVccUDZu3Kj77rtPXq83bL/D4Qh7bYzpsa+7y5VZvXq1/H6/tZ05c+ZKqw0AAGLAFQWUU6dOadeuXfqbv/kba5/H45GkHj0htbW1Vq+Kx+NRMBhUXV1dn2V643K5NGzYsLANAAB8c11RQNm0aZNGjx6tWbNmWfsyMzPl8XismT1S+ziV0tJS5eXlSZJyc3OVkJAQVqampkaHDx+2ygAAADgjfUMoFNKmTZu0cOFCOZ0X3+5wOJSfn6+CggJlZWUpKytLBQUFSk5O1rx58yRJbrdbixYt0ooVK5SWlqYRI0Zo5cqVysnJ0bRp06J3VQAAIKZFHFB27dql06dP69FHH+1xbNWqVWpqatKSJUtUV1enSZMmqbi4WKmpqVaZdevWyel0au7cuWpqatLUqVO1efNmxcfHX92VAACAb4yrWgdlsLAOCgAAsWdA1kEBAAC4ViK+xWMHnZ0+LNgGAEDs6Pze7s/Nm5gMKJ3P9mHBNgAAYk9DQ4Pcbvcly8TkGJRQKKSjR49qwoQJOnPmDONQrrH6+nplZGTQ1gOE9h5YtPfAor0Hlt3a2xijhoYGeb1excVdepRJTPagxMXFaezYsZLEwm0DiLYeWLT3wKK9BxbtPbDs1N6X6znpxCBZAABgOwQUAABgO/Fr1qxZM9iVuFLx8fGaMmVK2Iq2uDZo64FFew8s2ntg0d4DK1bbOyYHyQIAgG82bvEAAADbIaAAAADbIaAAAADbIaAAAADbIaAAAADbicmA8s///M/KzMzUkCFDlJubq/fff3+wqxRzCgsLdfvttys1NVWjR4/WX/3VX+no0aNhZYwxWrNmjbxer5KSkjRlyhRVVVWFlQkEAlq2bJlGjhyplJQUzZkzR9XV1QN5KTGpsLBQDodD+fn51j7aO7o+++wzPfzww0pLS1NycrJuvfVWVVRUWMdp7+hpbW3V3//93yszM1NJSUkaP368fvGLXygUClllaO8r99577+lHP/qRvF6vHA6H3njjjbDj0Wrburo6LViwQG63W263WwsWLNC5c+eu+fX1ycSYoqIik5CQYDZs2GCOHDlili9fblJSUsypU6cGu2oxZebMmWbTpk3m8OHD5tChQ2bWrFnmxhtvNI2NjVaZ559/3qSmpppt27aZyspK8+CDD5oxY8aY+vp6q8xjjz1mxo4da0pKSsyBAwfMD3/4Q/Nnf/ZnprW1dTAuKybs37/f3HTTTeaWW24xy5cvt/bT3tHz9ddfm3Hjxpmf/OQn5sMPPzQnT540u3btMp988olVhvaOnueee86kpaWZN99805w8edL87ne/M0OHDjUvvfSSVYb2vnI7d+40zz77rNm2bZuRZLZv3x52PFpte++995rs7GxTVlZmysrKTHZ2tpk9e/aAXWd3MRdQ7rjjDvPYY4+F7bv55pvNM888M0g1+maora01kkxpaakxxphQKGQ8Ho95/vnnrTLNzc3G7Xabf/mXfzHGGHPu3DmTkJBgioqKrDKfffaZiYuLM2+99dbAXkCMaGhoMFlZWaakpMRMnjzZCii0d3Q9/fTT5p577unzOO0dXbNmzTKPPvpo2L7777/fPPzww8YY2juaugeUaLXtkSNHjCSzb98+q8zevXuNJPM///M/1/qyehVTt3iCwaAqKio0Y8aMsP0zZsxQWVnZINXqm8Hv90uSRowYIUk6efKkfD5fWFu7XC5NnjzZauuKigq1tLSElfF6vcrOzubn0YfHH39cs2bN0rRp08L2097RtWPHDk2cOFEPPPCARo8erdtuu00bNmywjtPe0XXPPffonXfe0bFjxyRJH330kfbs2aO//Mu/lER7X0vRatu9e/fK7XZr0qRJVpk777xTbrd70No/pta9/fLLL9XW1qb09PSw/enp6fL5fINUq9hnjNFTTz2le+65R9nZ2ZJktWdvbX3q1CmrTGJiooYPH96jDD+PnoqKinTgwAGVl5f3OEZ7R9eJEyf0yiuv6KmnntLPfvYz7d+/X0888YRcLpceeeQR2jvKnn76afn9ft18882Kj49XW1ubfvnLX+qhhx6SxJ/vaylabevz+TR69Oge5x89evSgtX9MBZRODocj7LUxpsc+9N/SpUv18ccfa8+ePT2OXUlb8/Po6cyZM1q+fLmKi4s1ZMiQPsvR3tERCoU0ceJEFRQUSJJuu+02VVVV6ZVXXtEjjzxilaO9o+M//uM/tGXLFm3dulXf+973dOjQIeXn58vr9WrhwoVWOdr72olG2/ZWfjDbP6Zu8YwcOVLx8fE90lxtbW2P9Ij+WbZsmXbs2KF3331X3/rWt6z9Ho9Hki7Z1h6PR8FgUHV1dX2WQbuKigrV1tYqNzdXTqdTTqdTpaWl+tWvfiWn02m1F+0dHWPGjNGECRPC9n33u9/V6dOnJfHnO9r+7u/+Ts8884x+/OMfKycnRwsWLNCTTz6pwsJCSbT3tRSttvV4PPr88897nP+LL74YtPaPqYCSmJio3NxclZSUhO0vKSlRXl7eINUqNhljtHTpUr3++uv6wx/+oMzMzLDjmZmZ8ng8YW0dDAZVWlpqtXVubq4SEhLCytTU1Ojw4cP8PLqZOnWqKisrdejQIWubOHGi5s+fr0OHDmn8+PG0dxTdfffdPabNHzt2TOPGjZPEn+9ou3DhguLiwr9O4uPjrWnGtPe1E622veuuu+T3+7V//36rzIcffii/3z947T8YI3OvRuc0440bN5ojR46Y/Px8k5KSYj799NPBrlpM+du//VvjdrvN7t27TU1NjbVduHDBKvP8888bt9ttXn/9dVNZWWkeeuihXqeufetb3zK7du0yBw4cMH/xF3/BtMB+6jqLxxjaO5r2799vnE6n+eUvf2mOHz9u/v3f/90kJyebLVu2WGVo7+hZuHChGTt2rDXN+PXXXzcjR440q1atssrQ3leuoaHBHDx40Bw8eNBIMmvXrjUHDx60lteIVtvee++95pZbbjF79+41e/fuNTk5OUwzjtSvf/1rM27cOJOYmGi+//3vW1Nj0X+Set02bdpklQmFQuYf/uEfjMfjMS6Xy/zgBz8wlZWVYedpamoyS5cuNSNGjDBJSUlm9uzZ5vTp0wN8NbGpe0ChvaPrP//zP012drZxuVzm5ptvNuvXrw87TntHT319vVm+fLm58cYbzZAhQ8z48ePNs88+awKBgFWG9r5y7777bq+/rxcuXGiMiV7bfvXVV2b+/PkmNTXVpKammvnz55u6urqBusweHMYYMzh9NwAAAL2LqTEoAADg+kBAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtkNAAQAAtvP/AdcmpGQyvmQSAAAAAElFTkSuQmCC", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# visualize environment\n", + "%matplotlib inline\n", + "import matplotlib.pyplot as plt\n", + "env.load()\n", + "plt.imshow(env.render())\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "from planner.bit_star_planner import BITStarPlanner" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "# sample a non-trival problem setting and solve\n", + "while True:\n", + " start, goal = env.robot.sample_random_init_goal()\n", + " if not env.edge_fp(start, goal):\n", + " result_initial = BITStarPlanner(num_batch=100, stop_when_success=True).plan(env, start, goal, timeout=('time', 10))\n", + " result_refined = BITStarPlanner(num_batch=100, stop_when_success=False).plan(env, start, goal, timeout=('time', 10))\n", + " if result_initial.solution and result_refined.solution:\n", + " break" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [], + "source": [ + "# Visualization\n", + "from time import sleep\n", + "def visualize_traj(env, trajectory): \n", + " gifs = []\n", + " for timestep in np.linspace(0, len(trajectory.waypoints)-1, 100):\n", + " env.robot.set_config(trajectory.get_spec(timestep))\n", + " p.performCollisionDetection()\n", + " sleep(0.1)\n", + " gifs.append(p.getCameraImage(width=360, height=360, lightDirection=[1, 1, 1], shadow=1,\n", + " renderer=p.ER_BULLET_HARDWARE_OPENGL)[2]) \n", + " return gifs" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "data": { + "text/html": [ + "" + ], + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "text/html": [ + "" + ], + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "%matplotlib inline\n", + "import matplotlib.pyplot as plt\n", + "import pybullet as p\n", + "import pybullet_data\n", + "import numpy as np\n", + "from utils.utils import save_gif\n", + "from IPython.display import HTML\n", + "import base64\n", + "from objects.trajectory import WaypointLinearTrajectory\n", + "\n", + "env.load(GUI=True)\n", + "for title, result in [('rrt_star_initial', result_initial), ('rrt_star_refined', result_refined)]:\n", + " # generate collision-free trajectory\n", + " traj = WaypointLinearTrajectory(result.solution) \n", + " gifs = visualize_traj(env, traj)\n", + " save_gif(gifs, f'data/visualization/{title}.gif')\n", + " b64 = base64.b64encode(open(f'data/visualization/{title}.gif', 'rb').read()).decode('ascii')\n", + " display(HTML(f'')) " + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [], + "source": [ + "p.disconnect()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3.8.15 ('lemp')", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.15" + }, + "vscode": { + "interpreter": { + "hash": "c72f54e4f59ef741f6ce9a8d00eb4e33af6f143b90eb5c5a2b70c805b0346120" + } + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/examples/rrt_star_planner.ipynb b/examples/rrt_star_planner.ipynb index 66b212d..58faab6 100644 --- a/examples/rrt_star_planner.ipynb +++ b/examples/rrt_star_planner.ipynb @@ -18,7 +18,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ @@ -30,19 +30,17 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 5, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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", "text/plain": [ - "
" + "
" ] }, - "metadata": { - "needs_background": "light" - }, + "metadata": {}, "output_type": "display_data" } ], @@ -57,7 +55,7 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 7, "metadata": {}, "outputs": [], "source": [ @@ -68,7 +66,7 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 8, "metadata": {}, "outputs": [], "source": [ @@ -88,7 +86,7 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 12, "metadata": {}, "outputs": [], "source": [ @@ -107,13 +105,13 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 13, "metadata": {}, "outputs": [ { "data": { "text/html": [ - "" + "" ], "text/plain": [ "" @@ -125,7 +123,7 @@ { "data": { "text/html": [ - "" + "" ], "text/plain": [ "" @@ -158,7 +156,7 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 14, "metadata": {}, "outputs": [], "source": [ @@ -168,9 +166,9 @@ ], "metadata": { "kernelspec": { - "display_name": "pybullet", + "display_name": "Python 3.8.3 ('pybullet')", "language": "python", - "name": "pybullet" + "name": "python3" }, "language_info": { "codemirror_mode": { @@ -183,6 +181,11 @@ "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.8.3" + }, + "vscode": { + "interpreter": { + "hash": "91da548c7234d9e42a976552f88f78aa923f188c3ddab2037cd41e2aa5ee13cb" + } } }, "nbformat": 4, diff --git a/planner/bit_star_planner.py b/planner/bit_star_planner.py index 3114ce7..2c7383c 100644 --- a/planner/bit_star_planner.py +++ b/planner/bit_star_planner.py @@ -1,91 +1,40 @@ import numpy as np -from utils.utils import DotDict +from utils.utils import create_dot_dict +from scipy import special from planner.abstract_planner import AbstractPlanner - - -class BITStarPlanner(AbstractPlanner): - - def __init__(self, num_batch) - - @abstractmethod - def _plan(self, env, start, goal, timeout, **kwargs): - ''' - return an instance of DotDict with: - 1. solution: a list of waypoints. if there is no solution found, the value is None - ''' - raise NotImplementedError - - @abstractmethod - def _num_node(self): - ''' - return the number of sampled nodes - ''' - raise NotImplementedError - - def _catch_timeout(self, env, start, goal, timeout, **kwargs): - ''' - return an instance of DotDict - ''' - return create_dot_dict(solution=None) - - -import numpy as np import math import heapq -INF = float("inf") - - -class BITStar: - def __init__(self, environment, maxIter=5, plot_flag=False, batch_size=200, T=1000, sampling=None): - self.env = environment +INF = float("inf") - start, goal, bounds = tuple(environment.init_state), tuple(environment.goal_state), environment.bound - self.start = start - self.goal = goal +class BITStarPlanner(AbstractPlanner): + def __init__(self, num_batch, stop_when_success=True, eta=1.1): + self.num_batch = num_batch + self.stop_when_success = stop_when_success - self.bounds = bounds - self.bounds = np.array(self.bounds).reshape((2, -1)).T - self.ranges = self.bounds[:, 1] - self.bounds[:, 0] - self.dimension = environment.config_dim + self.batch_size = num_batch + self.eta = eta # a parameter to determine the sampling radius after a solution is found and needs to keep being refined - # This is the tree + def setup_planning(self): + self.ranges = self.env.robot.limits_high - self.env.robot.limits_low + self.dimension = self.env.robot.config_dim + self.vertices = [] self.edges = dict() # key = point,value = parent - self.g_scores = dict() - - self.samples = [] + + # This is the tree + self.samples = [] # samples are not included in the tree nodes self.vertex_queue = [] self.edge_queue = [] - self.old_vertices = set() + self.old_vertices = set() + self.g_scores = dict() - self.maxIter = maxIter self.r = INF - self.batch_size = batch_size - self.T, self.T_max = 0, T - self.eta = 1.1 # tunable parameter - self.obj_radius = 1 - self.resolution = 3 - - # the parameters for informed sampling - self.c_min = self.distance(self.start, self.goal) - self.center_point = None - self.C = None - - # whether plot the middle planning process - self.plot_planning_process = plot_flag - - if sampling is None: - self.sampling = self.informed_sample - else: - self.sampling = sampling - self.n_collision_points = 0 - self.n_free_points = 2 + self.n_free_points = 2 - def setup_planning(self): # add goal to the samples self.samples.append(self.goal) self.g_scores[self.goal] = INF @@ -100,20 +49,20 @@ def setup_planning(self): return radius_constant + def radius_init(self): - from scipy import special # Hypersphere radius calculation n = self.dimension unit_ball_volume = np.pi ** (n / 2.0) / special.gamma(n / 2.0 + 1) - volume = np.abs(np.prod(self.ranges)) * self.n_free_points / (self.n_collision_points + self.n_free_points) + volume = np.abs(np.prod(self.ranges)) * self.n_free_points / (self.n_collision_points + self.n_free_points) # the volume of free configuration space gamma = (1.0 + 1.0 / n) * volume / unit_ball_volume radius_constant = 2 * self.eta * (gamma ** (1.0 / n)) return radius_constant def informed_sample_init(self): + self.c_min = self.distance(self.start, self.goal) self.center_point = np.array([(self.start[i] + self.goal[i]) / 2.0 for i in range(self.dimension)]) a_1 = (np.array(self.goal) - np.array(self.start)) / self.c_min - id1_t = np.array([1.0] * self.dimension) M = np.dot(a_1.reshape((-1, 1)), id1_t.reshape((1, -1))) U, S, Vh = np.linalg.svd(M, 1, 1) self.C = np.dot(np.dot(U, np.diag([1] * (self.dimension - 1) + [np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])), Vh) @@ -145,16 +94,11 @@ def informed_sample(self, c_best, sample_num, vertices): return sample_array def get_random_point(self): - point = self.bounds[:, 0] + np.random.random(self.dimension) * self.ranges + point = self.env.robot.uniform_sample() return tuple(point) def is_point_free(self, point): - if self.dimension == 2: - result = self.env._state_fp(np.array(point)) - elif self.dimension == 3: - result = self.env._state_fp(np.array(point)) - else: - result = self.env._state_fp(np.array(point)) + result = self.env.state_fp(np.array(point)) if result: self.n_free_points += 1 else: @@ -162,8 +106,7 @@ def is_point_free(self, point): return result def is_edge_free(self, edge): - result = self.env._edge_fp(np.array(edge[0]), np.array(edge[1])) - # self.T += self.env.k + result = self.env.edge_fp(np.array(edge[0]), np.array(edge[1])) return result def get_g_score(self, point): @@ -194,8 +137,7 @@ def distance(self, point1, point2): def get_edge_value(self, edge): # sort value for edge - return self.get_g_score(edge[0]) + self.heuristic_cost(edge[0], edge[1]) + self.heuristic_cost(edge[1], - self.goal) + return self.get_g_score(edge[0]) + self.heuristic_cost(edge[0], edge[1]) + self.heuristic_cost(edge[1], self.goal) def get_point_value(self, point): # sort value for point @@ -270,7 +212,7 @@ def get_best_path(self): point = self.edges[point] path.append(point) path.reverse() - return path + return list(np.array(path)) if len(path) else None def path_length_calculate(self, path): path_length = 0 @@ -278,22 +220,18 @@ def path_length_calculate(self, path): path_length += self.distance(path[i], path[i + 1]) return path_length - def plan(self, pathLengthLimit, refine_time_budget=None, time_budget=None): - collision_checks = self.env.collision_check_count - if time_budget is None: - time_budget = INF - if refine_time_budget is None: - refine_time_budget = 10 - + def _plan(self, env, start, goal, timeout, **kwargs): + + self.env = env + self.start = tuple(start) + self.goal = tuple(goal) self.setup_planning() - init_time = time() - while self.T < self.T_max and (time() - init_time < time_budget): + while True: if not self.vertex_queue and not self.edge_queue: c_best = self.g_scores[self.goal] self.prune(c_best) - self.samples.extend(self.sampling(c_best, self.batch_size, self.vertices)) - self.T += self.batch_size + self.samples.extend(self.informed_sample(c_best, self.batch_size, self.vertices)) self.old_vertices = set(self.vertices) self.vertex_queue = [(self.get_point_value(point), point) for point in self.vertices] @@ -328,15 +266,16 @@ def plan(self, pathLengthLimit, refine_time_budget=None, time_budget=None): heapq.heappush(self.vertex_queue, (self.get_point_value(bestEdge[1]), bestEdge[1])) self.edge_queue = [item for item in self.edge_queue if item[1][1] != bestEdge[1] or \ - self.get_g_score(item[1][0]) + self.heuristic_cost(item[1][0], item[1][ - 1]) < self.get_g_score(item[1][0])] - heapq.heapify( - self.edge_queue) # Rebuild the priority queue because it will be destroyed after the element is removed + (self.get_g_score(item[1][0]) + self.heuristic_cost(item[1][0], item[1][1])) < self.get_g_score(item[1][0])] + heapq.heapify(self.edge_queue) # Rebuild the priority queue because it will be destroyed after the element is removed else: self.vertex_queue = [] self.edge_queue = [] - if self.g_scores[self.goal] < pathLengthLimit and (time() - init_time > refine_time_budget): + + if (self.stop_when_success) and self.g_scores[self.goal] < float('inf'): break - return self.samples, self.edges, self.env.collision_check_count - collision_checks, \ - self.g_scores[self.goal], self.T, time() - init_time \ No newline at end of file + + self.check_timeout(timeout) + + return create_dot_dict(solution=self.get_best_path()) diff --git a/robot/kuka4_robot.py b/robot/kuka4_robot.py new file mode 100644 index 0000000..4f13591 --- /dev/null +++ b/robot/kuka4_robot.py @@ -0,0 +1,27 @@ +from abc import ABC, abstractmethod +import numpy as np +from robot.individual_robot import IndividualRobot +import pybullet as p + + +class Kuka4Robot(IndividualRobot): + + def __init__(self, base_position=(0, 0, 0), base_orientation=(0, 0, 0, 1), + urdf_file="../data/robot/kuka_iiwa/model_4dof.urdf", collision_eps=0.5, **kwargs): + super(Kuka4Robot, self).__init__(base_position=base_position, + base_orientation=base_orientation, + urdf_file=urdf_file, + collision_eps=collision_eps, **kwargs) + + def _get_joints_and_limits(self, urdf_file): + pid = p.connect(p.DIRECT) + item_id = p.loadURDF(urdf_file, [0, 0, 0], [0, 0, 0, 1], useFixedBase=True, physicsClientId=pid) + num_joints = p.getNumJoints(item_id, physicsClientId=pid) + limits_low = [p.getJointInfo(item_id, jointId, physicsClientId=pid)[8] for jointId in range(num_joints)] + limits_high = [p.getJointInfo(item_id, jointId, physicsClientId=pid)[9] for jointId in range(num_joints)] + p.disconnect(pid) + return list(range(num_joints)), limits_low, limits_high + + def load2pybullet(self, **kwargs): + item_id = p.loadURDF(self.urdf_file, self.base_position, self.base_orientation, useFixedBase=True, **kwargs) + return item_id \ No newline at end of file diff --git a/robot/kuka5_robot.py b/robot/kuka5_robot.py new file mode 100644 index 0000000..030a924 --- /dev/null +++ b/robot/kuka5_robot.py @@ -0,0 +1,27 @@ +from abc import ABC, abstractmethod +import numpy as np +from robot.individual_robot import IndividualRobot +import pybullet as p + + +class Kuka5Robot(IndividualRobot): + + def __init__(self, base_position=(0, 0, 0), base_orientation=(0, 0, 0, 1), + urdf_file="../data/robot/kuka_iiwa/model_5dof.urdf", collision_eps=0.5, **kwargs): + super(Kuka5Robot, self).__init__(base_position=base_position, + base_orientation=base_orientation, + urdf_file=urdf_file, + collision_eps=collision_eps, **kwargs) + + def _get_joints_and_limits(self, urdf_file): + pid = p.connect(p.DIRECT) + item_id = p.loadURDF(urdf_file, [0, 0, 0], [0, 0, 0, 1], useFixedBase=True, physicsClientId=pid) + num_joints = p.getNumJoints(item_id, physicsClientId=pid) + limits_low = [p.getJointInfo(item_id, jointId, physicsClientId=pid)[8] for jointId in range(num_joints)] + limits_high = [p.getJointInfo(item_id, jointId, physicsClientId=pid)[9] for jointId in range(num_joints)] + p.disconnect(pid) + return list(range(num_joints)), limits_low, limits_high + + def load2pybullet(self, **kwargs): + item_id = p.loadURDF(self.urdf_file, self.base_position, self.base_orientation, useFixedBase=True, **kwargs) + return item_id \ No newline at end of file diff --git a/robot/multi_robot/dual_kuka4_robot.py b/robot/multi_robot/dual_kuka4_robot.py new file mode 100644 index 0000000..b1f9dcd --- /dev/null +++ b/robot/multi_robot/dual_kuka4_robot.py @@ -0,0 +1,18 @@ +from abc import ABC, abstractmethod +import numpy as np +from robot.kuka4_robot import Kuka4Robot +from robot.grouping import RobotGroup +import pybullet as p + +class DualKuka4Robot(RobotGroup): + + def __init__(self, base_positions=((0, 0, 0), (0.5, 0, 0)), + base_orientations=((0, 0, np.sin(np.pi), np.cos(np.pi)), (0, 0, 0, 1)), + urdf_file="../data/robot/kuka_iiwa/model_4dof.urdf", + collision_eps=0.5, **kwargs): + + robots = [] + for base_position, base_orientation in zip(base_positions, base_orientations): + robots.append(Kuka4Robot(base_position=base_position, base_orientation=base_orientation, urdf_file=urdf_file, collision_eps=collision_eps)) + + super(DualKuka4Robot, self).__init__(robots=robots, **kwargs) \ No newline at end of file diff --git a/robot/multi_robot/dual_kuka5_robot.py b/robot/multi_robot/dual_kuka5_robot.py new file mode 100644 index 0000000..4d90bfb --- /dev/null +++ b/robot/multi_robot/dual_kuka5_robot.py @@ -0,0 +1,18 @@ +from abc import ABC, abstractmethod +import numpy as np +from robot.kuka5_robot import Kuka5Robot +from robot.grouping import RobotGroup +import pybullet as p + +class DualKuka5Robot(RobotGroup): + + def __init__(self, base_positions=((0, 0, 0), (0.5, 0, 0)), + base_orientations=((0, 0, np.sin(np.pi), np.cos(np.pi)), (0, 0, 0, 1)), + urdf_file="../data/robot/kuka_iiwa/model_4dof.urdf", + collision_eps=0.5, **kwargs): + + robots = [] + for base_position, base_orientation in zip(base_positions, base_orientations): + robots.append(Kuka5Robot(base_position=base_position, base_orientation=base_orientation, urdf_file=urdf_file, collision_eps=collision_eps)) + + super(DualKuka5Robot, self).__init__(robots=robots, **kwargs) \ No newline at end of file diff --git a/robot/multi_robot/dual_simple2arm_robot.py b/robot/multi_robot/dual_simple2arm_robot.py new file mode 100644 index 0000000..53b4161 --- /dev/null +++ b/robot/multi_robot/dual_simple2arm_robot.py @@ -0,0 +1,18 @@ +from abc import ABC, abstractmethod +import numpy as np +from robot.kuka5_robot import Kuka5Robot +from robot.grouping import RobotGroup +import pybullet as p + +class DualSimple2ArmRobot(RobotGroup): + + def __init__(self, base_positions=((0, 0, 0), (0.5, 0, 0)), + base_orientations=((0, 0, np.sin(np.pi), np.cos(np.pi)), (0, 0, 0, 1)), + urdf_file="../data/robot/simple2arm/2dof.urdf", + collision_eps=0.5, **kwargs): + + robots = [] + for base_position, base_orientation in zip(base_positions, base_orientations): + robots.append(Kuka5Robot(base_position=base_position, base_orientation=base_orientation, urdf_file=urdf_file, collision_eps=collision_eps)) + + super(DualSimple2ArmRobot, self).__init__(robots=robots, **kwargs) \ No newline at end of file diff --git a/robot/multi_robot/triple_kuka_robot.py b/robot/multi_robot/triple_kuka_robot.py new file mode 100644 index 0000000..72db5aa --- /dev/null +++ b/robot/multi_robot/triple_kuka_robot.py @@ -0,0 +1,18 @@ +from abc import ABC, abstractmethod +import numpy as np +from robot.kuka_robot import KukaRobot +from robot.grouping import RobotGroup +import pybullet as p + +class TripleKukaRobot(RobotGroup): + + def __init__(self, base_positions=((0, 0, 0), (0.5, 0, 0), (0, 0.5, 0)), + base_orientations=((0, 0, np.sin(np.pi), np.cos(np.pi)), (0, 0, 0, 1), (0, 0, 0, 1)), + urdf_file="../data/robot/kuka_iiwa/model_0.urdf", + collision_eps=0.5, **kwargs): + + robots = [] + for base_position, base_orientation in zip(base_positions, base_orientations): + robots.append(KukaRobot(base_position=base_position, base_orientation=base_orientation, urdf_file=urdf_file, collision_eps=collision_eps)) + + super(TripleKukaRobot, self).__init__(robots=robots, **kwargs) \ No newline at end of file diff --git a/robot/multi_robot/triple_simple2arm_robot.py b/robot/multi_robot/triple_simple2arm_robot.py new file mode 100644 index 0000000..5503267 --- /dev/null +++ b/robot/multi_robot/triple_simple2arm_robot.py @@ -0,0 +1,18 @@ +from abc import ABC, abstractmethod +import numpy as np +from robot.simple2arm_robot import Simple2ArmRobot +from robot.grouping import RobotGroup +import pybullet as p + +class TripleSimple2ArmRobot(RobotGroup): + + def __init__(self, base_positions=((0, 0, 0), (1, 1, 0), (1, 1, 0)), + base_orientations=((0, 0, 0.7071, 0.7071), (0, 0, 0, 1), (0, 0, 0, 1)), + urdf_file="../data/robot/simple2arm/2dof.urdf", + collision_eps=0.5, **kwargs): + + robots = [] + for base_position, base_orientation in zip(base_positions, base_orientations): + robots.append(Simple2ArmRobot(base_position=base_position, base_orientation=base_orientation, urdf_file=urdf_file, collision_eps=collision_eps)) + + super(TripleSimple2ArmRobot, self).__init__(robots=robots, **kwargs) \ No newline at end of file diff --git a/robot/simple2arm_robot.py b/robot/simple2arm_robot.py new file mode 100644 index 0000000..0955de3 --- /dev/null +++ b/robot/simple2arm_robot.py @@ -0,0 +1,32 @@ +from abc import ABC, abstractmethod +import numpy as np +from robot.individual_robot import IndividualRobot +import pybullet as p + + +class Simple2ArmRobot(IndividualRobot): + + def __init__(self, base_position=(0, 0, 0), base_orientation=(0, 0, 0.7071, 0.7071), + urdf_file="../data/robot/simple2arm/2dof.urdf", collision_eps=0.5, **kwargs): + super(Simple2ArmRobot, self).__init__(base_position=base_position, + base_orientation=base_orientation, + urdf_file=urdf_file, + collision_eps=collision_eps, **kwargs) + + def _get_joints_and_limits(self, urdf_file): + pid = p.connect(p.DIRECT) + item_id = p.loadURDF(urdf_file, [0, 0, 0], [0, 0, 0, 1], useFixedBase=True, physicsClientId=pid) + num_joints = p.getNumJoints(item_id, physicsClientId=pid) + limits_low = [p.getJointInfo(item_id, jointId, physicsClientId=pid)[8] for jointId in range(num_joints)] + limits_high = [p.getJointInfo(item_id, jointId, physicsClientId=pid)[9] for jointId in range(num_joints)] + p.disconnect(pid) + return list(range(num_joints)), limits_low, limits_high + + def load2pybullet(self, **kwargs): + item_id = p.loadURDF(self.urdf_file, self.base_position, self.base_orientation, useFixedBase=True, **kwargs) + return item_id + + +if __name__ == '__main__': + env = Simple2ArmRobot() + env._get_joints_and_limits(env.urdf_file) \ No newline at end of file