diff --git a/doc/images/mjx/apg_diagram.png b/doc/images/mjx/apg_diagram.png
new file mode 100644
index 0000000000..961798da7c
Binary files /dev/null and b/doc/images/mjx/apg_diagram.png differ
diff --git a/mjx/training_apg.ipynb b/mjx/training_apg.ipynb
new file mode 100644
index 0000000000..d7cfac89d2
--- /dev/null
+++ b/mjx/training_apg.ipynb
@@ -0,0 +1,1426 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Policy learning and Policy Gradients\n",
+ "\n",
+ "This is a recap of policy learning contextualizes how we can use MJX's differentiability for policy learning. If the below concepts are unfamiliar, there are many great resources [online](https://spinningup.openai.com/en/latest/spinningup/rl_intro.html)! \n",
+ "\n",
+ "The goal of policy learning is to find a control policy $\\pi$ which outputs actions $a_t \\sim \\pi(\\cdot| x_t, \\theta)$ maximizing the total rewards $\\sum r_t$ over some time period, where $r_t$ is shorthand for a reward function evaluated at the state and action of time t:\n",
+ "\n",
+ "$$r_t = r(x_t, a_t)$$\n",
+ "\n",
+ "$\\theta$ are the parameters of the policy; weights in the common case that the policy is a neural network. **Policy gradient methods** involve estimating the gradient of the rewards with respect to the weights, and using this value in a first-order optimization algorithm such as Gradient Descent or [Adam](https://arxiv.org/abs/1412.6980). How we estimate the policy gradient depends on what state transition model we assume. \n",
+ "\n",
+ "#### Zeroth-Order Policy Gradients (ZoPG)\n",
+ "\n",
+ "Referring to `mjx.step` as the simulation function f, we borrow some [terminology](https://arxiv.org/abs/2202.00817) to differentiate between zeroth-order gradients, which only depend on values of f, and first-order gradients, which depend on its jacobian.\n",
+ "\n",
+ "Reinforcement learning (RL) algorithms such as the standard [PPO](https://github.com/google/brax/blob/main/brax/training/agents/ppo/train.py) assume the stochastic state transition model $x_{t+1} \\sim P(\\cdot | x_t, a_t)$. This leads to a ZoPG of the form:\n",
+ "\n",
+ "$$\n",
+ "\\nabla_\\theta J(\\pi_\\theta) = \\mathbb{E}_{\\tau \\sim \\pi_\\theta}\\left[ \\sum \\nabla_\\theta \\log\\pi_\\theta (a_t | s_t) R(\\tau) \\right]\n",
+ "$$\n",
+ "\n",
+ "Where $R(\\tau)$ is some function depending on the rollout $\\tau = \\{x_t, a_t\\}_{t=0}^{T}$. Despite this method's popularity and extensive research into its refinement, a fundamental property is that the gradient has high variance. This allows the optimizer to thoroughly explore the space of policies, leading to the robust and often surprisingly good policies that have been achieved. However, the variance comes at the cost of requiring many samples $(x_t, a_t)$ to converge.\n",
+ "\n",
+ "#### First-Order Policy Gradients (FoPG)\n",
+ "On the other hand, if you assume a deterministic state transition model $x_{t+1} = f(x_t, a_t)$, you end up with the first-order policy gradient. Other common names include Analytical Policy Gradients (APG) and Backpropogation through Time (BPTT). Unlike ZoPG methods, which model the state evolution as a probabilistic black box, the FoPG explicitly contains the jacobians of the simulation function f. For example, let's look at the gradient of the reward $r_t$, in the case that it only depends on state.\n",
+ "$$\n",
+ "\\frac{\\partial r_t}{\\partial \\theta} = \\frac{\\partial r_t}{\\partial x_t}\\frac{\\partial x_t}{\\partial \\theta} \n",
+ "$$\n",
+ "\n",
+ "$$\n",
+ "\\frac{\\partial x_t}{\\partial \\theta} = \\textcolor{Navy}{\\frac{\\partial f(x_{t-1}, a_{t-1})}{\\partial x_{t-1}}}\\frac{\\partial x_{t-1}}{\\partial \\theta} + \\textcolor{Navy}{\\frac{\\partial f(x_{t-1}, a_{t-1})}{\\partial a_{t-1}}} \\frac{\\partial a_{t-1}}{\\partial \\theta}\n",
+ "$$\n",
+ "\n",
+ "The navy-colored terms in the above expression are enabled by MJX's differentiability and are the key difference between FoPG's and ZoPG's. An important consideration is what these jacobians look like near contact points. To see why certain gradients within the jacobian can be pathological, imagine a hard sphere falling toward a block of marble. How does its velocity change with respect to distance ($\\frac{\\partial \\dot{z}_t}{\\partial z_t}$), the instant before it touches the ground? This is the case of an **uninformative gradient**, due to [hard contact](https://arxiv.org/html/2404.02887v1). Fortunately, the default contact settings in Mujoco are sufficiently [soft](https://mujoco.readthedocs.io/en/stable/computation/index.html#soft-contact-model) for learning via FoPG's. With soft contacts, the ground applies an increasing force on the ball as it penetrates it, unlike rigid contacts, which instantly provide enough force for deflection.\n",
+ "\n",
+ "A helpful way to think about FoPG's is via the chain rule and computation graphs, as illustrated below for how $r_2$ influences the policy gradient, again for the case that the reward does not depend on action:\n",
+ "\n",
+ " \n",
+ "\n",
+ "Note that there three distinct gradient chains in this example. The red pathway considers how the immediately prior action affected the state. The blue path explains the name *Backpropogation through Time*, capturing how actions affect downstream rewards. The least intuitive may be the green chain, which shows how the reward depends on how actions depend on previous actions.Experience shows that blocking *any* of these three pathways via jax.lax.stop_grad can badly hinder policy learning. As the length of $x_t$ backbone increases, [gradient explosion](https://arxiv.org/abs/2111.05803) becomes a crucial consideration. In practice, this can be resolved via decaying downstream gradients or periodically truncating the gradient.\n",
+ "\n",
+ "**The Sharp Bits of FoPG's**\n",
+ "\n",
+ "While FoPG's have been shown to be very sample efficient, especially as the [dimension of the state space increases](https://arxiv.org/abs/2204.07137), one fundamental shortcoming is that due to the lower gradient variance, FoPG's also have less exploration power than ZoPG's and benefit from the practioner being more explicit in the problem formulation.\n",
+ "\n",
+ "Additionally, discontinuous reward formulations are ubiquitious in RL, for instance, a large penalty when the robot falls. It can be significantly more [challenging](https://arxiv.org/abs/2403.14864) to design robust policies with FoPG's, since they cannot backprop through such penalties.\n",
+ "\n",
+ "Last, despite the sample efficiency, FoPG methods can still struggle with wall-clock time. Because the gradients have low variance, they do not benefit significantly from massive parallelization of data collection - unlike [RL](https://arxiv.org/abs/2109.11978). Additionally, the policy gradient is typically calculated via autodifferentiation. This can be 3-5x slower than unrolling the simulation forward, and memory intensive, with memory requirements scaling with $O(m \\cdot (m+n) \\cdot T)$, where m and n are the state and control dimensions, $m \\cdot (m+n)$ is the jacobian dimension, and T is the number of steps propogated through.\n",
+ "\n",
+ "Note that with certain models, using autodifferentiation through mjx.step currently causes [nan gradients](https://github.com/google-deepmind/mujoco/issues/1517). For now, we address this issue by using double-precision floats, at the cost of doubling the memory requirements and training time."
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "---\n",
+ "\n",
+ "**Coming Up**\n",
+ "\n",
+ "In this tutorial, we demonstrate two ways to use FoPG's, using Brax's simple APG [algorithm](https://github.com/google/brax/tree/main/brax/training/agents/apg). This algorithm essentially uses FoPG's to perform live gradient descent on the policy, unrolling it for a short window, using the data to do a policy update, then continuing where it left off."
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Setup: Imports and installations"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 1,
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "import os\n",
+ "os.environ[\"XLA_PYTHON_CLIENT_MEM_FRACTION\"] = \"0.8\" # 0.9 causes too much lag. \n",
+ "from datetime import datetime\n",
+ "import functools\n",
+ "\n",
+ "# Math\n",
+ "import jax.numpy as jp\n",
+ "import numpy as np\n",
+ "import jax\n",
+ "from jax import config # Analytical gradients work much better with double precision.\n",
+ "config.update(\"jax_debug_nans\", True)\n",
+ "config.update(\"jax_enable_x64\", True)\n",
+ "config.update('jax_default_matmul_precision', jax.lax.Precision.HIGH)\n",
+ "from brax import math\n",
+ "\n",
+ "# Sim\n",
+ "import mujoco\n",
+ "import mujoco.mjx as mjx\n",
+ "\n",
+ "# Brax\n",
+ "from brax import envs\n",
+ "from brax.base import Motion, Transform\n",
+ "from brax.io import mjcf\n",
+ "from brax.envs.base import PipelineEnv, State\n",
+ "from brax.mjx.pipeline import _reformat_contact\n",
+ "from brax.training.acme import running_statistics\n",
+ "from brax.io import model\n",
+ "\n",
+ "# Algorithms\n",
+ "from brax.training.agents.apg import train as apg\n",
+ "from brax.training.agents.apg import networks as apg_networks\n",
+ "from brax.training.agents.ppo import train as ppo\n",
+ "\n",
+ "# Supporting\n",
+ "from etils import epath\n",
+ "import mediapy as media\n",
+ "import matplotlib.pyplot as plt\n",
+ "from ml_collections import config_dict\n",
+ "from typing import Any, Dict\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "#### Quadruped Env"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "!git clone https://github.com/google-deepmind/mujoco_menagerie.git"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 3,
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "text/html": [
+ "
"
+ ],
+ "text/plain": [
+ ""
+ ]
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "xml_path = epath.Path('mujoco_menagerie/anybotics_anymal_c/scene_mjx.xml').as_posix()\n",
+ "\n",
+ "mj_model = mujoco.MjModel.from_xml_path(xml_path)\n",
+ "\n",
+ "if 'renderer' not in dir():\n",
+ " renderer = mujoco.Renderer(mj_model)\n",
+ "\n",
+ "init_q = mj_model.keyframe('standing').qpos\n",
+ "\n",
+ "mj_data = mujoco.MjData(mj_model)\n",
+ "mj_data.qpos = init_q\n",
+ "mujoco.mj_forward(mj_model, mj_data)\n",
+ "\n",
+ "renderer.update_scene(mj_data)\n",
+ "media.show_image(renderer.render())"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 4,
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "# Rendering Rollouts\n",
+ "def render_rollout(reset_fn, step_fn, \n",
+ " inference_fn, env, \n",
+ " n_steps = 200, camera=None,\n",
+ " seed=0):\n",
+ " rng = jax.random.key(seed)\n",
+ " render_every = 3\n",
+ " state = reset_fn(rng)\n",
+ " rollout = [state.pipeline_state]\n",
+ "\n",
+ " for i in range(n_steps):\n",
+ " act_rng, rng = jax.random.split(rng)\n",
+ " ctrl, _ = inference_fn(state.obs, act_rng)\n",
+ " state = step_fn(state, ctrl)\n",
+ " if i % render_every == 0:\n",
+ " rollout.append(state.pipeline_state)\n",
+ "\n",
+ " media.show_video(env.render(rollout, camera=camera), \n",
+ " fps=1.0 / (env.dt*render_every),\n",
+ " codec='gif')"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Study 1: Imitating Kinematics\n",
+ "\n",
+ "FoPG's have been demonstrated to work well in [imitation learning](https://openreview.net/forum?id=06mk-epSwZ), especially when the agent state is reset to track the reference state when it gets too far. In this section, we learn to trot in place. Due to the limited gain on the PD controllers, trotting quickly is far from trivial!\n",
+ "\n",
+ "The RL environment has three rewards:\n",
+ "- min_reference_tracking penalizes error from the reference motion, in minimal coordinates. This makes the policy's output more precise.\n",
+ "- reference_tracking penalizes error in maximal coordinates and increases training stability.\n",
+ "- feet_height nudges the balance of which body positions and velocities to track, by placing additional incentive on the *position* of the feet."
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "#### Designing Reference Kinematics"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 7,
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "def cos_wave(t, step_period, scale):\n",
+ " _cos_wave = -jp.cos(((2*jp.pi)/step_period)*t)\n",
+ " return _cos_wave * (scale/2) + (scale/2)\n",
+ "\n",
+ "def dcos_wave(t, step_period, scale):\n",
+ " \"\"\" \n",
+ " Derivative of the cos wave, for reference velocity\n",
+ " \"\"\"\n",
+ " return ((scale*jp.pi) / step_period) * jp.sin(((2*jp.pi)/step_period)*t)\n",
+ "\n",
+ "def make_kinematic_ref(sinusoid, step_k, scale=0.3, dt=1/50):\n",
+ " \"\"\" \n",
+ " Makes trotting kinematics for the 12 leg joints.\n",
+ " step_k is the number of timesteps it takes to raise and lower a given foot.\n",
+ " A gait cycle is 2 * step_k * dt seconds long.\n",
+ " \"\"\"\n",
+ " \n",
+ " _steps = jp.arange(step_k)\n",
+ " step_period = step_k * dt\n",
+ " t = _steps * dt\n",
+ " \n",
+ " wave = sinusoid(t, step_period, scale)\n",
+ " # Commands for one step of an active front leg\n",
+ " fleg_cmd_block = jp.concatenate(\n",
+ " [jp.zeros((step_k, 1)),\n",
+ " wave.reshape(step_k, 1),\n",
+ " -2*wave.reshape(step_k, 1)],\n",
+ " axis=1\n",
+ " )\n",
+ " # Our standing config reverses front and hind legs\n",
+ " h_leg_cmd_bloc = -1 * fleg_cmd_block\n",
+ "\n",
+ " block1 = jp.concatenate([\n",
+ " jp.zeros((step_k, 3)),\n",
+ " fleg_cmd_block,\n",
+ " h_leg_cmd_bloc,\n",
+ " jp.zeros((step_k, 3))],\n",
+ " axis=1\n",
+ " )\n",
+ "\n",
+ " block2 = jp.concatenate([\n",
+ " fleg_cmd_block,\n",
+ " jp.zeros((step_k, 3)),\n",
+ " jp.zeros((step_k, 3)),\n",
+ " h_leg_cmd_bloc],\n",
+ " axis=1\n",
+ " )\n",
+ " # In one step cycle, both pairs of active legs have inactive and active phases\n",
+ " step_cycle = jp.concatenate([block1, block2], axis=0)\n",
+ " return step_cycle\n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 8,
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "text/html": [
+ "
"
+ ],
+ "text/plain": [
+ ""
+ ]
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "poses = make_kinematic_ref(cos_wave, step_k=25)\n",
+ "\n",
+ "frames = []\n",
+ "init_q = mj_model.keyframe('standing').qpos\n",
+ "mj_data.qpos = init_q\n",
+ "default_ap = init_q[7:]\n",
+ "\n",
+ "for i in range(len(poses)):\n",
+ " mj_data.qpos[7:] = poses[i] + default_ap\n",
+ " mujoco.mj_forward(mj_model, mj_data)\n",
+ " renderer.update_scene(mj_data)\n",
+ " frames.append(renderer.render())\n",
+ "\n",
+ "media.show_video(frames, fps=50, codec='gif')"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "#### The RL Environment"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 21,
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "def get_config():\n",
+ " def get_default_rewards_config():\n",
+ " default_config = config_dict.ConfigDict(\n",
+ " dict(\n",
+ " scales=config_dict.ConfigDict(\n",
+ " dict(\n",
+ " min_reference_tracking = -2.5 * 3e-3, # to equalize the magnitude\n",
+ " reference_tracking = -1.0,\n",
+ " feet_height = -1.0\n",
+ " )\n",
+ " )\n",
+ " )\n",
+ " )\n",
+ " return default_config\n",
+ "\n",
+ " default_config = config_dict.ConfigDict(\n",
+ " dict(rewards=get_default_rewards_config(),))\n",
+ "\n",
+ " return default_config\n",
+ "\n",
+ "# Math functions from (https://github.com/jiawei-ren/diffmimic)\n",
+ "def quaternion_to_matrix(quaternions):\n",
+ " r, i, j, k = quaternions[..., 0], quaternions[..., 1], quaternions[..., 2], quaternions[..., 3]\n",
+ " two_s = 2.0 / (quaternions * quaternions).sum(-1)\n",
+ "\n",
+ " o = jp.stack(\n",
+ " (\n",
+ " 1 - two_s * (j * j + k * k),\n",
+ " two_s * (i * j - k * r),\n",
+ " two_s * (i * k + j * r),\n",
+ " two_s * (i * j + k * r),\n",
+ " 1 - two_s * (i * i + k * k),\n",
+ " two_s * (j * k - i * r),\n",
+ " two_s * (i * k - j * r),\n",
+ " two_s * (j * k + i * r),\n",
+ " 1 - two_s * (i * i + j * j),\n",
+ " ),\n",
+ " -1,\n",
+ " )\n",
+ " return o.reshape(quaternions.shape[:-1] + (3, 3))\n",
+ "\n",
+ "def matrix_to_rotation_6d(matrix):\n",
+ " batch_dim = matrix.shape[:-2]\n",
+ " return matrix[..., :2, :].reshape(batch_dim + (6,))\n",
+ "\n",
+ "def quaternion_to_rotation_6d(quaternion):\n",
+ " return matrix_to_rotation_6d(quaternion_to_matrix(quaternion))\n",
+ "\n",
+ "class TrotAnymal(PipelineEnv):\n",
+ "\n",
+ " def __init__(\n",
+ " self,\n",
+ " termination_height: float=0.25,\n",
+ " **kwargs,\n",
+ " ):\n",
+ " step_k = kwargs.pop('step_k', 25)\n",
+ "\n",
+ " physics_steps_per_control_step = 10\n",
+ " kwargs['n_frames'] = kwargs.get(\n",
+ " 'n_frames', physics_steps_per_control_step)\n",
+ "\n",
+ " mj_model = mujoco.MjModel.from_xml_path(xml_path)\n",
+ " kp = 230\n",
+ " mj_model.actuator_gainprm[:, 0] = kp\n",
+ " mj_model.actuator_biasprm[:, 1] = -kp\n",
+ "\n",
+ " sys = mjcf.load_model(mj_model)\n",
+ "\n",
+ " super().__init__(sys=sys, **kwargs) \n",
+ " \n",
+ " self.termination_height = termination_height\n",
+ " \n",
+ " self._init_q = mj_model.keyframe('standing').qpos\n",
+ " \n",
+ " self.err_threshold = 0.4 # diffmimic; value from paper.\n",
+ " \n",
+ " self._default_ap_pose = mj_model.keyframe('standing').qpos[7:]\n",
+ " self.reward_config = get_config()\n",
+ "\n",
+ " self.action_loc = self._default_ap_pose\n",
+ " self.action_scale = jp.array([0.2, 0.8, 0.8] * 4)\n",
+ " \n",
+ " self.feet_inds = jp.array([21,28,35,42]) # LF, RF, LH, RH\n",
+ "\n",
+ " #### Imitation reference\n",
+ " kinematic_ref_qpos = make_kinematic_ref(\n",
+ " cos_wave, step_k, scale=0.3, dt=self.dt)\n",
+ " kinematic_ref_qvel = make_kinematic_ref(\n",
+ " dcos_wave, step_k, scale=0.3, dt=self.dt)\n",
+ " \n",
+ " self.l_cycle = jp.array(kinematic_ref_qpos.shape[0])\n",
+ " \n",
+ " # Expand to entire state space.\n",
+ "\n",
+ " kinematic_ref_qpos += self._default_ap_pose\n",
+ " ref_qs = np.tile(self._init_q.reshape(1, 19), (self.l_cycle, 1))\n",
+ " ref_qs[:, 7:] = kinematic_ref_qpos\n",
+ " self.kinematic_ref_qpos = jp.array(ref_qs)\n",
+ " \n",
+ " ref_qvels = np.zeros((self.l_cycle, 18))\n",
+ " ref_qvels[:, 6:] = kinematic_ref_qvel\n",
+ " self.kinematic_ref_qvel = jp.array(ref_qvels)\n",
+ "\n",
+ " # Can decrease jit time and training wall-clock time significantly.\n",
+ " self.pipeline_step = jax.checkpoint(self.pipeline_step, \n",
+ " policy=jax.checkpoint_policies.dots_with_no_batch_dims_saveable)\n",
+ " \n",
+ " def reset(self, rng: jax.Array) -> State:\n",
+ " # Deterministic init\n",
+ "\n",
+ " qpos = jp.array(self._init_q)\n",
+ " qvel = jp.zeros(18)\n",
+ " \n",
+ " data = self.pipeline_init(qpos, qvel)\n",
+ "\n",
+ " # Position onto ground\n",
+ " pen = jp.min(data.contact.dist)\n",
+ " qpos = qpos.at[2].set(qpos[2] - pen)\n",
+ " data = self.pipeline_init(qpos, qvel)\n",
+ "\n",
+ " state_info = {\n",
+ " 'rng': rng,\n",
+ " 'steps': 0.0,\n",
+ " 'reward_tuple': {\n",
+ " 'reference_tracking': 0.0,\n",
+ " 'min_reference_tracking': 0.0,\n",
+ " 'feet_height': 0.0\n",
+ " },\n",
+ " 'last_action': jp.zeros(12), # from MJX tutorial.\n",
+ " 'kinematic_ref': jp.zeros(19),\n",
+ " }\n",
+ "\n",
+ " x, xd = data.x, data.xd\n",
+ " obs = self._get_obs(data.qpos, x, xd, state_info)\n",
+ " reward, done = jp.zeros(2)\n",
+ " metrics = {}\n",
+ " for k in state_info['reward_tuple']:\n",
+ " metrics[k] = state_info['reward_tuple'][k]\n",
+ " state = State(data, obs, reward, done, metrics, state_info)\n",
+ " return jax.lax.stop_gradient(state)\n",
+ " \n",
+ " def step(self, state: State, action: jax.Array) -> State:\n",
+ " action = jp.clip(action, -1, 1) # Raw action\n",
+ "\n",
+ " action = self.action_loc + (action * self.action_scale)\n",
+ "\n",
+ " data = self.pipeline_step(state.pipeline_state, action)\n",
+ " \n",
+ " ref_qpos = self.kinematic_ref_qpos[jp.array(state.info['steps']%self.l_cycle, int)]\n",
+ " ref_qvel = self.kinematic_ref_qvel[jp.array(state.info['steps']%self.l_cycle, int)]\n",
+ " \n",
+ " # Calculate maximal coordinates\n",
+ " ref_data = data.replace(qpos=ref_qpos, qvel=ref_qvel)\n",
+ " ref_data = mjx.forward(self.sys, ref_data)\n",
+ " ref_x, ref_xd = ref_data.x, ref_data.xd\n",
+ "\n",
+ " state.info['kinematic_ref'] = ref_qpos\n",
+ "\n",
+ " # observation data\n",
+ " x, xd = data.x, data.xd\n",
+ " obs = self._get_obs(data.qpos, x, xd, state.info)\n",
+ "\n",
+ " # Terminate if flipped over or fallen down.\n",
+ " done = 0.0\n",
+ " done = jp.where(x.pos[0, 2] < self.termination_height, 1.0, done)\n",
+ " up = jp.array([0.0, 0.0, 1.0])\n",
+ " done = jp.where(jp.dot(math.rotate(up, x.rot[0]), up) < 0, 1.0, done)\n",
+ "\n",
+ " # reward\n",
+ " reward_tuple = {\n",
+ " 'reference_tracking': (\n",
+ " self._reward_reference_tracking(x, xd, ref_x, ref_xd)\n",
+ " * self.reward_config.rewards.scales.reference_tracking\n",
+ " ),\n",
+ " 'min_reference_tracking': (\n",
+ " self._reward_min_reference_tracking(ref_qpos, ref_qvel, state)\n",
+ " * self.reward_config.rewards.scales.min_reference_tracking\n",
+ " ),\n",
+ " 'feet_height': (\n",
+ " self._reward_feet_height(data.geom_xpos[self.feet_inds][:, 2]\n",
+ " ,ref_data.geom_xpos[self.feet_inds][:, 2])\n",
+ " * self.reward_config.rewards.scales.feet_height\n",
+ " )\n",
+ " }\n",
+ " \n",
+ " reward = sum(reward_tuple.values())\n",
+ "\n",
+ " # state management\n",
+ " state.info['reward_tuple'] = reward_tuple\n",
+ " state.info['last_action'] = action # used for observation. \n",
+ "\n",
+ " for k in state.info['reward_tuple'].keys():\n",
+ " state.metrics[k] = state.info['reward_tuple'][k]\n",
+ "\n",
+ " state = state.replace(\n",
+ " pipeline_state=data, obs=obs, reward=reward,\n",
+ " done=done)\n",
+ " \n",
+ " #### Reset state to reference if it gets too far\n",
+ " error = (((x.pos - ref_x.pos) ** 2).sum(-1)**0.5).mean()\n",
+ " to_reference = jp.where(error > self.err_threshold, 1.0, 0.0)\n",
+ "\n",
+ " to_reference = jp.array(to_reference, dtype=int) # keeps output types same as input. \n",
+ " ref_data = self.mjx_to_brax(ref_data)\n",
+ "\n",
+ " data = jax.tree_util.tree_map(lambda x, y: \n",
+ " jp.array((1-to_reference)*x + to_reference*y, x.dtype), data, ref_data)\n",
+ " \n",
+ " x, xd = data.x, data.xd # Data may have changed.\n",
+ " obs = self._get_obs(data.qpos, x, xd, state.info)\n",
+ " \n",
+ " return state.replace(pipeline_state=data, obs=obs)\n",
+ " \n",
+ " def _get_obs(self, qpos: jax.Array, x: Transform, xd: Motion,\n",
+ " state_info: Dict[str, Any]) -> jax.Array:\n",
+ "\n",
+ " inv_base_orientation = math.quat_inv(x.rot[0])\n",
+ " local_rpyrate = math.rotate(xd.ang[0], inv_base_orientation)\n",
+ "\n",
+ " obs_list = []\n",
+ " # yaw rate\n",
+ " obs_list.append(jp.array([local_rpyrate[2]]) * 0.25)\n",
+ " # projected gravity\n",
+ " obs_list.append(\n",
+ " math.rotate(jp.array([0.0, 0.0, -1.0]), inv_base_orientation))\n",
+ " # motor angles\n",
+ " angles = qpos[7:19]\n",
+ " obs_list.append(angles - self._default_ap_pose)\n",
+ " # last action\n",
+ " obs_list.append(state_info['last_action'])\n",
+ " # kinematic reference\n",
+ " kin_ref = self.kinematic_ref_qpos[jp.array(state_info['steps']%self.l_cycle, int)]\n",
+ " obs_list.append(kin_ref[7:]) # First 7 indicies are fixed\n",
+ "\n",
+ " obs = jp.clip(jp.concatenate(obs_list), -100.0, 100.0)\n",
+ "\n",
+ " return obs\n",
+ " \n",
+ " def mjx_to_brax(self, data):\n",
+ " \"\"\" \n",
+ " Apply the brax wrapper on the core MJX data structure.\n",
+ " \"\"\"\n",
+ " q, qd = data.qpos, data.qvel\n",
+ " x = Transform(pos=data.xpos[1:], rot=data.xquat[1:])\n",
+ " cvel = Motion(vel=data.cvel[1:, 3:], ang=data.cvel[1:, :3])\n",
+ " offset = data.xpos[1:, :] - data.subtree_com[self.sys.body_rootid[1:]]\n",
+ " offset = Transform.create(pos=offset)\n",
+ " xd = offset.vmap().do(cvel)\n",
+ " data = _reformat_contact(self.sys, data)\n",
+ " return data.replace(q=q, qd=qd, x=x, xd=xd)\n",
+ "\n",
+ "\n",
+ " # ------------ reward functions----------------\n",
+ " def _reward_reference_tracking(self, x, xd, ref_x, ref_xd):\n",
+ " \"\"\"\n",
+ " Rewards based on inertial-frame body positions.\n",
+ " Notably, we use a high-dimension representation of orientation.\n",
+ " \"\"\"\n",
+ "\n",
+ " f = lambda x, y: ((x - y) ** 2).sum(-1).mean()\n",
+ "\n",
+ " _mse_pos = f(x.pos, ref_x.pos)\n",
+ " _mse_rot = f(quaternion_to_rotation_6d(x.rot),\n",
+ " quaternion_to_rotation_6d(ref_x.rot))\n",
+ " _mse_vel = f(xd.vel, ref_xd.vel)\n",
+ " _mse_ang = f(xd.ang, ref_xd.ang)\n",
+ "\n",
+ " # Tuned to be about the same size.\n",
+ " return _mse_pos \\\n",
+ " + 0.1 * _mse_rot \\\n",
+ " + 0.01 * _mse_vel \\\n",
+ " + 0.001 * _mse_ang\n",
+ "\n",
+ " def _reward_min_reference_tracking(self, ref_qpos, ref_qvel, state):\n",
+ " \"\"\" \n",
+ " Using minimal coordinates. Improves accuracy of joint angle tracking.\n",
+ " \"\"\"\n",
+ " pos = jp.concatenate([\n",
+ " state.pipeline_state.qpos[:3],\n",
+ " state.pipeline_state.qpos[7:]])\n",
+ " pos_targ = jp.concatenate([\n",
+ " ref_qpos[:3],\n",
+ " ref_qpos[7:]])\n",
+ " pos_err = jp.linalg.norm(pos_targ - pos)\n",
+ " vel_err = jp.linalg.norm(state.pipeline_state.qvel- ref_qvel)\n",
+ "\n",
+ " return pos_err + vel_err\n",
+ "\n",
+ " def _reward_feet_height(self, feet_pos, feet_pos_ref):\n",
+ " return jp.sum(jp.abs(feet_pos - feet_pos_ref)) # try to drive it to 0 using the l1 norm.\n",
+ "\n",
+ "envs.register_environment('trotting_anymal', TrotAnymal)"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "#### Imitation Learning via FoPG's\n",
+ "Takes 15 minutes on a NVIDIA 3060 TI GPU"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 22,
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "make_networks_factory = functools.partial(\n",
+ " apg_networks.make_apg_networks,\n",
+ " hidden_layer_sizes=(256, 128)\n",
+ ")\n",
+ "\n",
+ "epochs = 499\n",
+ "\n",
+ "train_fn = functools.partial(apg.train,\n",
+ " episode_length=240,\n",
+ " policy_updates=epochs,\n",
+ " horizon_length=32,\n",
+ " num_envs=64,\n",
+ " learning_rate=1e-4,\n",
+ " num_eval_envs=64,\n",
+ " num_evals=10 + 1,\n",
+ " use_float64=True,\n",
+ " normalize_observations=True,\n",
+ " network_factory=make_networks_factory)"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 23,
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "text/plain": [
+ ""
+ ]
+ },
+ "execution_count": 23,
+ "metadata": {},
+ "output_type": "execute_result"
+ },
+ {
+ "data": {
+ "image/png": "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",
+ "text/plain": [
+ ""
+ ]
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "x_data = []\n",
+ "y_data = []\n",
+ "ydataerr = []\n",
+ "times = [datetime.now()]\n",
+ "\n",
+ "def progress(it, metrics):\n",
+ " times.append(datetime.now())\n",
+ " x_data.append(it)\n",
+ " y_data.append(metrics['eval/episode_reward'])\n",
+ " ydataerr.append(metrics['eval/episode_reward_std'])\n",
+ "\n",
+ "# Each foot contacts the ground twice/sec.\n",
+ "env = envs.get_environment(\"trotting_anymal\", step_k = 13)\n",
+ "eval_env = envs.get_environment(\"trotting_anymal\", step_k = 13)\n",
+ "\n",
+ "make_inference_fn, params, _= train_fn(environment=env,\n",
+ " progress_fn=progress,\n",
+ " eval_env=eval_env)\n",
+ "\n",
+ "plt.errorbar(x_data, y_data, yerr=ydataerr)"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 24,
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "text/html": [
+ "
"
+ ],
+ "text/plain": [
+ ""
+ ]
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "demo_env = envs.training.EpisodeWrapper(env, \n",
+ " episode_length=1000, \n",
+ " action_repeat=1)\n",
+ "\n",
+ "render_rollout(\n",
+ " jax.jit(demo_env.reset),\n",
+ " jax.jit(demo_env.step),\n",
+ " jax.jit(make_inference_fn(params)),\n",
+ " demo_env,\n",
+ " n_steps=200,\n",
+ " seed=1\n",
+ ")\n",
+ "\n",
+ "model_path = '/tmp/trotting_2hz_policy'\n",
+ "model.save_params(model_path, params)"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "**A note on sample efficiency**\n",
+ "\n",
+ "Above, we train using epochs * horizon_length * num_envs = 1.024e6 total simulator steps. Let's see what we get from PPO, using ten times more samples:"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 8,
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "text/plain": [
+ "Text(0, 0.5, 'reward per episode')"
+ ]
+ },
+ "execution_count": 8,
+ "metadata": {},
+ "output_type": "execute_result"
+ },
+ {
+ "data": {
+ "image/png": "iVBORw0KGgoAAAANSUhEUgAAAkcAAAGwCAYAAACjPMHLAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjguMCwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy81sbWrAAAACXBIWXMAAA9hAAAPYQGoP6dpAABTpklEQVR4nO3deVhU1f8H8PewDfsgjLIIAuaCCCqKCpiKmkuaVqa5pVlqm6SFppGGQqllaZl9zcq11DTX3H5uuZcaIriAu2wKiKgwILLNnN8f5DQjqAwODMv79TzzNHPuwmduOPPm3HPulQghBIiIiIgIAGBk6AKIiIiIqhOGIyIiIiINDEdEREREGhiOiIiIiDQwHBERERFpYDgiIiIi0sBwRERERKTBxNAF1EQqlQqpqamwsbGBRCIxdDlERERUDkII5OTkwMXFBUZGj+4fYjiqgNTUVLi5uRm6DCIiIqqAlJQUuLq6PnI5w1EF2NjYACg5uLa2tgauhoiIiMpDoVDAzc1N/T3+KAxHFfDgVJqtrS3DERERUQ3zpCExdXZA9qJFi+Dp6Qlzc3O0a9cOR44cMXRJREREVA3UyXC0bt06fPDBB5g2bRpiYmLQuXNnPP/880hOTjZ0aURERGRgEiGEMHQRVa1jx45o27YtfvjhB3VbixYt8NJLL2HOnDlP3F6hUEAmkyE7O5un1YiIiGqI8n5/17meo8LCQkRHR6NXr15a7b169cLff/9d5jYFBQVQKBRaDyIiIqqd6lw4yszMhFKphKOjo1a7o6Mj0tPTy9xmzpw5kMlk6gen8RMREdVedS4cPfDwSHUhxCNHr4eFhSE7O1v9SElJqYoSiYiIyADq3FR+uVwOY2PjUr1EGRkZpXqTHpBKpZBKpVVRHhERERlYnes5MjMzQ7t27bB3716t9r179yIoKMhAVREREVF1Ued6jgAgNDQUI0eOhL+/PwIDA/HTTz8hOTkZ77zzjqFLIyIiIgOrk+FoyJAhuH37NiIjI5GWlgYfHx/s3LkT7u7uhi6NiIiIDKxOXufoafE6R0RERDUPr3NEREREVAEMR0REREQaGI6IiIiINDAcERERUbWQV1gMj493wOPjHcgrLDZYHXVythoREREZXn6REunZ+UhX5CM9Ox8pd/IMXRIAhiMiIiLSMyEEsvKKSkLPv8EnPTsfNxX5SPv3v+mKfGTlFT1yH/cLlbA0M0xMYTgiIiKq4fIKi+EdvhsAEB/Zu1JDRbFShYycAqQr8nEzWzvsqJ9n56OgWFWu/VmYGsNZZg5HW3PIbcyw7XQaAEDAcFcaYjgiIiIiAMC9gmJ16Hk47DzoAcrMLYCqnLnF3soMjrbm6vDj9OC57L82W3MT9Y3f8wqL1eHIUL1GAMMRERFRrSeEwJ17hVq9PA9OdaVrhJ+c/PINgjYxksDR1hyOtlI4yyxKgo9MCieZBZz+DUENbKUwNzXWqU5LMxMkftGvIm9RrxiOiIiIajilRlfOyr8TtYJQWnY+MhQFKFSW7zSXlZkxnGTmcPq3Z8dZVhJ2Sp5bwFEmhdxKCiMjSWW9HYNjOCIiIqphipQqnL2RjRPX7uBEwm2cTLyrXvblrouP3E5uXfo014Mg9KDNxty0Kt5CtcZwREREVM3lFylxOiULJxLu4J+EO4hOuov7Rcoy133exwkN7SzUoedBr4+jrTnMTHh5w/JgOCIiIqpm8gqLcSopCycSbuNEwh3EpmSh8KHZX/UsTdHB0x4dPB3Q2k2GQT8cAwDMe7W1QQcz1wY8ekREVGdV5RT4x1HkFyE68S6OJ9zGPwl3cPZ6NoofmhJW30aKDp72CPC0R8fGDmhS31o97seQV5OujRiOiIiIqtjde4X4J7HkFNmJhNuIT1WUmh7vIjNHx8YO6Ohpjw6e9vCUW6mnvFPlYjgiIiKqZBk5+fjn3/FCJ67dwcWbOaXW8XCwRAdPe3T0dEAHT3u42VsaoFICGI6IiIj0LjXrPk78e4rsxLU7uJZ5r9Q6TRpYq3uFOno6wElmXuGfV12uD1RbMBwRERE9BSEEku/k4cS/QehEwm1cv3tfax2JBPByskVHT3t09LRHe097yK2lBqqYnoThiIiISAdCCFy9lasOQ/8k3EG6Il9rHWMjCXxcbNGxsQM6eNijvYc9ZJa8flBNwXBERET0GCqVwIX0HPzz77T6fxLu4Pa9Qq11TI0laO1qV3KKrLED2rnXg7WUX7E1Ff/PERERaShWqhCXqlDPJPsn4Q4UD91zTGpihLaN6v0bhuzh51YPFma63UeMqi+GIyIiIgA/Hb6GmOQsRCfdRW6BdhiyMjNGOw979ZghX1cZpCYMQ7UVwxEREdVJKpXA2n+S1a+/3XdZ/dzG3AQdPEp6hTp4OsDHxRYmxrz1Rl3BcERERHXO+TQFPtl8FjHJWeq2nt4NEPSMHB087eHlZAvjWnzXeXo8hiMiIqoz8gqLseDPy1hyJAFKlYCV1Bj3Ckpu4LpgqB/vSUYAAPYREhFRnXDgYgZ6fXMYPx66BqVKoE9LJ2wLedbQZVE1xIhMRES1WoYiHxHb47HjTBoAoKGdBSIGtMRz3o68YSuVieGIiIh0Vl3uZv84KpXA6n+SMff/LiCnoBhGEmDMs5744LlmsOI1iOgx+NtBRES1TnxqyYDr2JQsAEBrVxlmvewLn4YywxZGNQLDERER1Rp5hcVYsO8ylhwtGXBtLTXBR72b47UAd84+o3JjOCIiolrhwIUMTN9yDjeySm76+ryPE2b0b/lUd7unuonhiIiIarSbinxEbovHjrOlB1wTVQTDERER1UhKlcCaE0mYu+sicgqKYWwkwZhnPTGxR1MOuKanwt8eIiKqccoacD17oC9auug24NrSzASJX/SrhAqpJmM4IiKiGiOvsBjf7ruMpRxwTZWI4YiIiGqE/Rdu4tMtceoB1319nRD+Agdck/4xHBERUbV2U5GPiG1x2Hk2HUDJgOvIF1uiRwsOuKbKwXBERETVklIlsPrfAde5GgOuP3iuabW8IjfVHrXmxrOJiYkYM2YMPD09YWFhgWeeeQYzZsxAYWGh1noSiaTUY/HixQaqmoiIyhKXmo2BP/yN8D/ikFtQjNZudtga0gmf9G3BYESVrtb8hl24cAEqlQo//vgjmjRpgnPnzmHcuHG4d+8evv76a611ly9fjj59+qhfy2S8nDwRUXVQ1oDrKX2aY0RHDrimqlNrwlGfPn20Ak/jxo1x8eJF/PDDD6XCkZ2dHZycnMq974KCAhQUFKhfKxSKpy+YiIi0/Hn+JsL/0B5wPaN/SzjacsA1Va1ac1qtLNnZ2bC3ty/VHhISArlcjvbt22Px4sVQqVSP3c+cOXMgk8nUDzc3t8oqmYiozknPzse7q6IxZuVJ3Mi6j4Z2Flg22h+LRrRjMCKDqDU9Rw+7evUqFi5ciHnz5mm1f/bZZ+jRowcsLCzw559/YtKkScjMzMT06dMfua+wsDCEhoaqXysUCgYkIqKnpFQJrDqehK92/zfgeuyznpjIAddkYNX+t2/mzJmIiIh47DpRUVHw9/dXv05NTUWfPn0wePBgjB07VmtdzRDUpk0bAEBkZORjw5FUKoVUKq1A9UREVJa41Gx8suksTl/PBgC0cbPD7Jd94e1ia+DKiGpAOAoJCcHQoUMfu46Hh4f6eWpqKrp164bAwED89NNPT9x/QEAAFAoFbt68CUdHXjODiKgy3Ssoxrf7LmHZX4lQqgRs/h1wPZwDrqkaqfbhSC6XQy6Xl2vdGzduoFu3bmjXrh2WL18OI6MnD6mKiYmBubk57OzsnrJSIiJ6nIcHXPfzdUZ4f2+OK6Jqp9qHo/JKTU1FcHAwGjVqhK+//hq3bt1SL3swM23btm1IT09HYGAgLCwscODAAUybNg1vvfUWT5sREVWS9OySK1z/37n/rnD92Ust0d2LvfVUPdWacLRnzx5cuXIFV65cgaurq9YyIQQAwNTUFIsWLUJoaChUKhUaN26MyMhIjB8/3hAlExHVakqVwK/HEvH1nksccE01ikQ8SA5UbgqFAjKZDNnZ2bC15eBBIqp78gqL4R2+GwAQH9m7VNg5dyMbn2w+izMccE3VSHm/vxndiYiq0JNCRU13r6AY3+y9hGV/JUAlUDLg+nkvDO/QiAOuqcaoXf8qiYjIYPbF30T4H+eQmp0PAOjXyhkzXvBGAw64phqG4YiIiJ5KenY+vtx1AbvjbgIoGXD9+Us+6ObVwMCVEVUMwxERET2VFxYeRV6hsmTAdWdPTOzBAddUs/G3l4iIdHYlI1f9PK9QiTZudpgz0BctnDngmmo+hiMiIio3IQR+OZaE2TvPq9vC+3tjdKAHjDjgmmoJhiMiIiqXjJx8fLT+DA5duqXVPrS9G4MR1SpPvr8GEZGB5RUWw+PjHfD4eAfyCosNXU6dtDf+Jvp8ewSHLt2CmYkRwvp6GbokokrDniMiInqkvMJifLb9PH77JxkA4OVkg++G+cG1ngXm7Lxg4OqIKgfDERERlenM9Sx8sDYW1zLvAQDGdfbE5N7NITUxZg8e1WoMR0REpEWpEvjh4BV8u+8yilUCTrbmmPdqa3RqIjd0aURVguGIiIjUUu7kIfT3WEQl3gUA9PV1wuyXfWFnaWbgyoiqDsMRERFBCIEtsTcQviUOOQXFsDIzRsSLPnilbUNIJJyJRnULwxERUR2Xfb8I07ecw7bTqQCAto3s8O0QPzRysDRwZUSGwXBERFSHHb92G6HrYpGanQ9jIwkmdG+K8d2egYkxr/RCdRfDERFRHVRYrML8vZfw4+GrEAJwd7DEN0PaoG2jeoYujcjgGI6IiOqYKxk5mLg2FnGpCgDAEH83fNrfG9ZSfiUQAQxHRER1hhACq44nYdbO88gvUsHO0hRfDPRFHx9nQ5dGVK0wHBER1QG3cgowdeMZ7L+QAQDo3FSOrwe3hqOtuYErI6p+GI6IiGq5P8/fxNSNZ5CZWwgzEyNM7eOFN4I8eLNYokdgOCIiqqXuFyoxa2c8Vh0vuS9ac0cbLBjWBl5OtgaujKh6YzgiIqqFzt3IxsS1Mbh6q+S+aGOe9cRHvZvD3NTYwJURVX8MR0REtYhSJfDT4WuYv/ciipQCDWykmPdqa3RuWt/QpRHVGAxHRES1xI2s+whdF4sTCXcAAH1aOmHOQF/Us+J90Yh0wXBERFQL/BF7A9O3nENOfjEszYwxs39LDPZ35X3RiCqA4YiIqAZT5BchfMs5bIktuS9aGzc7fDukDTzkVgaujKjmYjgiIqqh/km4gw/XxeJG1n0YSYD3uzdFSPcmMOV90YieCsMR6VVeYTG8w3cDAOIje8PSjL9iRPpWpFTh232X8MPBq1AJoJF9yX3R2rnzvmhE+sBvLiKiGuTqrVx8uC4WZ65nAwAGtXPFzAEteV80Ij3ivyaiWow9ebWHEAJr/knG59vP436REjILU8wZ6Iu+vrwvGpG+8ZOSiKiau51bgKkbz2Lf+ZsAgE5NHPD14NZwllkYuDKi2onhiIioGjtwMQMfrT+DzNwCmBkbYUqf5nizkyfvi0ZUiRiOiIiqofwiJebsPI+Vx5IAAM0crfHtED94u/C+aESVjeGIqAwcq0OGFJeajQ/WxuJyRi4AYHSQBz5+3qta3RfN0swEiV/0M3QZRJWCn/hERNWESiWw5Og1fLW75L5o9W2k+Hpwa3RtxvuiEVUlhiMiomogNes+Jv1+Gseu3QYA9PJ2xBevtII974tGVOUYjoiIDGz7mVR8suksFPnFsDA1xoz+3hjS3o33RSMykFp1jXkPDw9IJBKtx8cff6y1TnJyMvr37w8rKyvI5XJMmDABhYWFBqqYiOqy3PxihP4ei5A1MVDkF6O1qww7J3bG0A6NGIyIDKjW9RxFRkZi3Lhx6tfW1tbq50qlEv369UP9+vVx9OhR3L59G6+//jqEEFi4cKEhyiWiOmzgD3/j+t2S+6KN79YEE3o05X3RiKqBWheObGxs4OTkVOayPXv2ID4+HikpKXBxcQEAzJs3D6NHj8asWbNga8spskRUuYqUKvXz63fvw7WeBb4d0gb+HvYGrIqINNW6P1G+/PJLODg4oE2bNpg1a5bWKbNjx47Bx8dHHYwAoHfv3igoKEB0dPQj91lQUACFQqH1ICLS1fFrtzFw0d/q1y+2ccH/TezMYERUzdSqnqOJEyeibdu2qFevHv755x+EhYUhISEBS5YsAQCkp6fD0dFRa5t69erBzMwM6enpj9zvnDlzEBERUam1E1HtlZGTjzk7L2BzzA2t9jkDfXkNLaJqqNr3HM2cObPUIOuHHydPngQAfPjhh+jatStatWqFsWPHYvHixVi6dClu376t3l9ZgxyFEI8d/BgWFobs7Gz1IyUlRf9vlIhqHaVKYOXfiegx7xA2x9yARAIMbe9m6LKI6Amq/Z8sISEhGDp06GPX8fDwKLM9ICAAAHDlyhU4ODjAyckJJ06c0Frn7t27KCoqKtWjpEkqlUIqlepWOBHVaTHJd/HpH+dw7kbJafhWrjJ89qIPmjpaY20U/8Aiqs6qfTiSy+WQy+UV2jYmJgYA4OzsDAAIDAzErFmzkJaWpm7bs2cPpFIp2rVrp5+CiahOy8orxJe7LmJtVDKEAGzNTfBRHy8M79AIxkYS5BUWG7pEInqCah+OyuvYsWM4fvw4unXrBplMhqioKHz44YcYMGAAGjVqBADo1asXvL29MXLkSHz11Ve4c+cOJk+ejHHjxnGmGhE9FZVKYEP0dXyx6wLu3CuZCPJKW1eE9fWC3Jo9z0Q1Sa0JR1KpFOvWrUNERAQKCgrg7u6OcePGYcqUKep1jI2NsWPHDrz33nvo1KkTLCwsMHz4cHz99dcGrJyIarr4VAU+/eMcopPuAgCaO9rgs5d80MGTs9CIaqJaE47atm2L48ePP3G9Ro0aYfv27VVQERHVdjn5Rfhm72WsPJYIpUrAyswYHzzXDKM7efBijkQ1WK0JR0REVUUIgW1n0vD59nhk5BQAAPr5OmP6Cy3gLLMwcHVE9LQYjoiIdHD1Vi7C/ziHv66UXCLEw8ESkS/6oEuz+gaujIj0heGIiKgc7hcq8f2By/jp8DUUKQWkJkYY360J3urSGOamxoYuj4j0iOGIiOgJ9sbfxMytcbiRdR8A0K15fUQM8EEjB0sDV0ZElYHhiIjoEVLu5CFiWxz2nc8AALjIzDFjQEv08nZ87FX1iahmYziqJvIKi+EdvhsAEB/Zm/dbIjKggmIlfj58DQv3X0FBsQqmxhKM7dwY73dvwn+bRHUA/5UTEWk4ejkT4X+cw7XMewCAwMYO+OyllmjSwMbAlRFRVWE4IiICkJ6dj893xGP7mTQAQH0bKab3a4EBrV14Co2ojmE4IqI6rVipwoq/E/HN3ku4V6iEkQQYFeiB0F7NYGtuaujyiMgAKhSOjhw5gh9//BFXr17Fhg0b0LBhQ/z666/w9PTEs88+q+8aiYgqxcnEO5i+5RwupOcAAPwa2eGzF33g01Bm4MqIyJB0vr79xo0b0bt3b1hYWCAmJgYFBSVXh83JycHs2bP1XiARkb7dzi3A5PWnMWjxMVxIz4GdpSm+GOiLje8EMRgRke7h6PPPP8fixYvx888/w9T0vy7noKAgnDp1Sq/FERHpk1IlsPpEErrPO4QN0dcBAEPbu2H/pGAM7dAIRkYcW0REFTitdvHiRXTp0qVUu62tLbKysvRRExGR3p29no3pW87i9PVsAIC3sy0+e8kH7dzrGbgyIqpudA5Hzs7OuHLlCjw8PLTajx49isaNG+urLiIivci+X4R5ey7i1+NJEAKwkZogtFczjAxwh4mxzp3nRFQH6ByO3n77bUycOBHLli2DRCJBamoqjh07hsmTJyM8PLwyaiQi0pkQAptjbmD2zvPIzC0EALzYxgXT+rZAA1tzA1dHRNWZzuFoypQpyM7ORrdu3ZCfn48uXbpAKpVi8uTJCAkJqYwaiYh0cjE9B5/+cQ7/JNwBADxT3wqfveiDoCZyA1dGRDVBhabyz5o1C9OmTUN8fDxUKhW8vb1hbW2t79qIiHRyr6AYC/68jGVHE1CsEjA3NcKEHk0x9tnGMDPhKTQiKp8KXwTS0tIS/v7++qyFiKhChBDYdS4dkdvjkZadDwDo5e2I8P7ecK1naeDqiKimKVc4GjhwYLl3uGnTpgoXQ0Skq8TMewjfGofDl24BAFzrWSBiQEv0aOFo4MqIqKYqVziSyf67KJoQAps3b4ZMJlP3HEVHRyMrK0unEEVE9DTyi5RYdPAqFh+6isJiFcyMjfBO18Z4r1sTmJsaG7o8IqrByhWOli9frn4+depUvPrqq1i8eDGMjUs+gJRKJd577z3Y2tpWTpVERBoOXMjAjK1xSL6TBwDo3FSOyBd94Cm3MnBlRFQb6DzmaNmyZTh69Kg6GAGAsbExQkNDERQUhK+++kqvBRIRaZrwWwz2nc8AADjZmuPTF7zR19cJEgmvbk1E+qFzOCouLsb58+fRvHlzrfbz589DpVLprTAiogcKipTq5/vOZ8DYSII3O3lg4nPNYC2t8LwSIqIy6fyp8sYbb+DNN9/ElStXEBAQAAA4fvw4vvjiC7zxxht6L5CI6i4hBPadz0Dktjh1W9tGdpg90BdeTjyNT0SVQ+dw9PXXX8PJyQnffPMN0tLSAJTcUmTKlCmYNGmS3gskorrpSkYOIrbF48jlTK32X97sAGtz00dsRUT09HQOR0ZGRpgyZQqmTJkChUIBAByITUR6o8gvwoJ9l7Hy70QUqwTMjI0wKsgdS44kAACMjDi2iIgqV4VP1t+6dQsXL16ERCJB8+bNIZfzsvxEVHEqlcD66BTM3XURt++V3AvtuRYNML2fNxrYStXhiIiosukcju7du4f3338fv/zyi3oAtrGxMUaNGoWFCxfC0pJXoyUi3UQn3UXEtjicuZ4NAGhc3wrhL3gjuHkDAEBeYbEhyyOiOkbnmw2Fhobi0KFD2LZtG7KyspCVlYU//vgDhw4d4pgjItLJTUU+QtfF4pUf/saZ69mwlppger8W2DWxizoYERFVNZ17jjZu3IgNGzYgODhY3da3b19YWFjg1VdfxQ8//KDP+oioFiooVmLZ0UQs3H8ZeYUl0/Rf9XfFR729UN9GauDqiKiu0zkc5eXlwdGx9D2LGjRogLy8PL0URUS1kxAC+y9k4LPt8Ui8XfJ54dfIDjP7t0RrNzvDFkdE9C+dw1FgYCBmzJiBX375Bebm5gCA+/fvIyIiAoGBgXovkIhqh6u3chG5LR6H/r1BbH0bKT7u44WX/RpyBhoRVSs6h6MFCxagT58+cHV1RevWrSGRSBAbGwtzc3Ps3r27MmokohosJ78I3/15Gcv/Kpmab2oswZvPeuL97k15dWsiqpZ0/mTy8fHB5cuXsWrVKly4cAFCCAwdOhQjRoyAhYVFZdRIRDWQSiWw4dR1zN11EZm5BQCA7l4N8OkL3nX6BrGWZiZI/KKfocsgoseo0J9tFhYWGDdunL5rIaJaIib5LmZui8fplCwAgKe8ZGp+Ny/OQCOi6k/nqfwrV67Ejh071K+nTJkCOzs7BAUFISkpSa/FEVHNkqHIx6TfT+PlRX/jdEoWrKUm+KSvF3Z/0IXBiIhqDJ3D0ezZs9Wnz44dO4bvv/8ec+fOhVwux4cffqj3Aomo+issVuHHQ1fR7euD2HjqOgBgUDtX7J/cFW91eQZmJjp/1BARGYzOn1gpKSlo0qQJAGDLli0YNGgQ3nrrLcyZMwdHjhzRe4HldfDgQUgkkjIfUVFR6vXKWr548WKD1U1U0x24kIHe3x7GnP+7gHuFSrR2s8Pm94Lw9eDWaGBjbujyiIh0pvOYI2tra9y+fRuNGjXCnj171L1F5ubmuH//vt4LLK+goCCkpaVptX366afYt28f/P39tdqXL1+OPn36qF/LZLIqqZGoNrl2KxefbY/HgYslU/Pl1lJM7dMcr7R15dR8IqrRdA5HPXv2xNixY+Hn54dLly6hX7+SWRdxcXHw8PDQd33lZmZmBicnJ/XroqIibN26FSEhIZBItD+o7ezstNYlovLLLSjGwv2XsexoAoqUJVPz3+jkife7N4GNuamhyyMiemo6n1b73//+h8DAQNy6dQsbN26Eg4MDACA6OhrDhg3Te4EVtXXrVmRmZmL06NGlloWEhEAul6N9+/ZYvHix+ga6j1JQUACFQqH1IKprVCqBDdHX0e3rg/jx0DUUKQWCm9fHrg+64JO+LRiMiKjW0LnnyM7ODt9//32p9oiICL0UpC9Lly5F79694ebmptX+2WefoUePHrCwsMCff/6JSZMmITMzE9OnT3/kvubMmVPt3h9RVTqdkoUZW+MQ++/UfA8HS4T390Z3r9K3EiIiqunKFY7OnDkDHx8fGBkZ4cyZM49dt1WrVnop7IGZM2c+MZhERUVpjSu6fv06du/ejd9//73UupohqE2bNgCAyMjIx4ajsLAwhIaGql8rFIpSoYuoNrqVU4C5uy5gfXTJDDQrM2O836Mp3ujkAamJsYGrIyKqHOUKR23atEF6ejoaNGiANm3aQCKRQAihXv7gtUQigVKp1GuBISEhGDp06GPXeXis0/Lly+Hg4IABAwY8cf8BAQFQKBS4efNmmTfUBQCpVAqplHcKp7qjsFiFlX8n4rs/LyOnoBgAMLBtQ0zt4wVHW85AI6LarVzhKCEhAfXr11c/r0pyuRxyubzc6wshsHz5cowaNQqmpk8eAxETEwNzc3PY2dk9RZVEtcfBixmI3B6Pa7fuAQBaucowc0BLtG1Uz8CVERFVjXKFI3d39zKfV0f79+9HQkICxowZU2rZtm3bkJ6ejsDAQFhYWODAgQOYNm0a3nrrLfYMUZ2XmHkPn++Ix77zGQAAubUZpvT2wqB2nJpPRHVLhe6tdvHiRSxcuBDnz5+HRCKBl5cX3n//fTRv3lzf9els6dKlCAoKQosWLUotMzU1xaJFixAaGgqVSoXGjRsjMjIS48ePN0ClRNVDbkExvt9/BcuOJqBQqYKJkQSjgzww4bmmsOUMNCKqg3QORxs2bMCwYcPg7++PwMBAAMDx48fh4+ODNWvWYPDgwXovUhdr1qx55LI+ffpoXfyRqC4TQmBL7A3M2XkBGTkFAIAuzeoj/AVvNGlgbeDqiIgMR+dwNGXKFISFhSEyMlKrfcaMGZg6darBwxERPdmZ61mYuTUOp5KzAADuDpb4tJ83erRoUOqiqUREdY3O4Sg9PR2jRo0q1f7aa6/hq6++0ktRRFQ5MnML8NWui/g9OgVCAJZmxgjp3gRjnvXk1Hwion/pHI6Cg4Nx5MgR9c1nHzh69Cg6d+6st8KISL9W/p2IRQeuqqfmv+xXMjXfScap+UREmnQORwMGDMDUqVMRHR2NgIAAACVjjtavX4+IiAhs3bpVa10iMpz8ov+uO/blrosAAN+GMswc4I127vaGKouIqFrTORy99957AIBFixZh0aJFZS4DUCkXhCSi8olLzca6qBRsibmhbrO3MsOU3s0x2N8NxpyaT0T0SDqHoyfdpJWIDEORX4Q/YlPxe1QKzt7ILrV854Rn4SSzMEBlREQ1S4Wuc/RAfn4+zM05XoHIUIQQiEq8i7VRydh5Ng35RSV/vJgZG6FnS0e83MYFY3+JBgDYWvCaRURE5aFzOFIqlZg9ezYWL16Mmzdv4tKlS2jcuDE+/fRTeHh4lHllaiLSr4ycfGw6dQO/R6XgWuY9dXszR2sMad8IL/s1hL2VGfIKiw1YJRFRzaRzOJo1axZWrlyJuXPnYty4cep2X19ffPPNNwxHRJWkWKnC4cu3sPafFPx5IQNKVcnNn63MjNG/tQuGtHdDGzc7XqeIiOgp6RyOfvnlF/z000/o0aMH3nnnHXV7q1atcOHCBb0WR0RA8u08/H4yBeujU3BTUaBub9vIDkPbN0K/Vs6wkj7VGXIiItKg8yfqjRs3Sl3jCCgZqF1UVKSXoojquvwiJXbHpWNdVAr+vnpb3W5vZYaBfg0xpL0bmjraGLBCIqLaS+dw1LJlSxw5cgTu7u5a7evXr4efn5/eCiOqi86nKbAuKgWbY24g+37JHxsSCdC5aX0M8XfDc94NeCVrIqJKpnM4mjFjBkaOHIkbN25ApVJh06ZNuHjxIn755Rds3769MmokqtVy8ouw9XTJFPzT1/+bgt/QzgKD/V0xqJ0rXOtZGrBCIqK6Redw1L9/f6xbtw6zZ8+GRCJBeHg42rZti23btqFnz56VUSNRrSOEwMmku1gXlYIdZ9Jw/98rWZsaS9DL2wmvtnfDs03kvFgjEZEBVGgUZ+/evdG7d29910JU62XmFmDTqetYG5WCa7f+m4LfpIE1hrZ3w8t+DeFgLTVghURExCkuRJVMqRI4fPkW1v2Tgn3nb6L43yn4lmbGeKGVM4a0b4S2jTgFn4ioumA4IqokKXfysP5kCtZHX0dadr66vY2bHYa2d8MLrV1gzSn4RETVDj+ZifSooFiJPXE3sS4qBUevZKrb7SxNMdDPFUPau6G5E6fgExFVZwxHRHpwIf2/KfhZef9d76tzUzmGtHdDT29HTsEnIqohdApHRUVFaN68ObZv3w5vb+/KqomoRsgtKMa206lYG5WC0ylZ6nZnmTkG+7thcDtXuNlzCj4RUU2jUzgyNTVFQUEBB45SnSWEwKnkkin428+kIa+wZAq+iZEEPb0dMaS9Gzo3rc8p+ERENZjOp9Xef/99fPnll1iyZAlMTHhWjuqG27kF2HTqBtadTMGVjFx1+zP1rTCkvRsGtnWFnFPwiYhqBZ3TzYkTJ/Dnn39iz5498PX1hZWVldbyTZs26a04ourgg3WxOHAhA0XKkin4FqYPpuC7oZ17PfakEhHVMjqHIzs7O7zyyiuVUQtRtXArpwCrTySpX++JuwkAaO1mhyH+bujf2hk25qaGKo+IiCqZzuFo+fLllVEHkUEJIXAi4Q5WHU/C7rh0dS8RALwW0AgjOrqjhbOtASskIqKqUqFBQ8XFxTh48CCuXr2K4cOHw8bGBqmpqbC1tYW1tbW+aySqNIr8ImyKvo7VJ5JxWWMsUWtXmfomsJ/0bQFLM46vIyKqK3T+xE9KSkKfPn2QnJyMgoIC9OzZEzY2Npg7dy7y8/OxePHiyqiTSK/O3cjGquNJ+CM2VX3TV0szY7zYpiFGdGyExvWt4B2+28BVEhGRIegcjiZOnAh/f3+cPn0aDg4O6vaXX34ZY8eO1WtxRPp0v1CJbWdSsfp4krpXCACaOVrjtQB3vOTXELb/jiXKKyw2VJlERGRgOoejo0eP4q+//oKZmZlWu7u7O27cuKG3woj05eqtXKw+nowN0SlQ5JeEHjNjIzzv64QRHd3R3oMzzoiI6D86hyOVSgWlUlmq/fr167Cx4T2jqHooUqqwN/4mVh1Pwt9Xb6vb3ewtMLyDOwb787pERERUNp3DUc+ePfHtt9/ip59+AgBIJBLk5uZixowZ6Nu3r94LJNJFatZ9rP0nGWujUpCRUwAAMJIA3b0aYESAO7o2rQ8jXr2aiIgeQ+dw9M0336Bbt27w9vZGfn4+hg8fjsuXL0Mul+O3336rjBqJHkulEjh8+RZWHU/G/gs3ofp3Fn59GymGtnfD0A6N0NDOwrBFEhFRjaFzOHJxcUFsbCx+++03nDp1CiqVCmPGjMGIESNgYcEvIKo6t3MLsD76OtacSEbynTx1e2BjB7wW4I5eLR1hamxkwAqJiKgmqtDFWywsLPDmm2/izTff1Hc9RI8lhMDJpLtYfTwJO8+mo1CpAgDYmJtgUDtXjOjojiYNeK0tIiKquAqFo4sXL2LhwoU4f/48JBIJvLy8EBISAi8vL33XRwQAyMkvwpaYG1h9IhkX0nPU7a1cZXitozv6t3aBhZmxASskIqLaQudwtGHDBgwbNgz+/v4IDAwEABw/fhy+vr5Ys2YNBg8erPciqe6KT1Vg1Ykk/BFzA/cKS2ZJmpsa4cXWDTEioBFaudoZtkAiIqp1dA5HU6ZMQVhYGCIjI7XaZ8yYgalTpzIc0VPLL1Ji59k0rDqehFPJWer2Z+pb4bUAdwxs6wqZBW/8SkRElUPn0arp6ekYNWpUqfbXXnsN6enpeimqLLNmzUJQUBAsLS1hZ2dX5jrJycno378/rKysIJfLMWHCBBQWFmqtc/bsWXTt2hUWFhZo2LAhIiMjIYQoc39UtRIz72HWjngEzPkTob+fxqnkLJgYSdCvlTN+GxeAfaFd8UYnTwYjIiKqVDr3HAUHB+PIkSNo0qSJVvvRo0fRuXNnvRX2sMLCQgwePBiBgYFYunRpqeVKpRL9+vVD/fr1cfToUdy+fRuvv/46hBBYuHAhAEChUKBnz57o1q0boqKicOnSJYwePRpWVlaYNGlSpdVOj1asVGHf+QysPpGEI5cz1e0N7SwwvGMjDPZ3RQMbcwNWSEREdY3O4WjAgAGYOnUqoqOjERAQAKBkzNH69esRERGBrVu3aq2rLxEREQCAFStWlLl8z549iI+PR0pKClxcXAAA8+bNw+jRozFr1izY2tpi9erVyM/Px4oVKyCVSuHj44NLly5h/vz5CA0N5S0kqlB6dj7WRiVj7T8pSFfkAwAkEiC4WX28FuCO4OYNYMyLNdK/LM1MkPhFP0OXQUR1hM7h6L333gMALFq0CIsWLSpzGVBy5eyybjNSWY4dOwYfHx91MAKA3r17o6CgANHR0ejWrRuOHTuGrl27QiqVaq0TFhaGxMREeHp6lrnvgoICFBQUqF8rFIrKeyO1mEol8NfVTKw6noR95zOg/PdqjQ5WZni1vRuGd2gEN3tLA1dJRER1XYXurVYdpaenw9HRUautXr16MDMzU4+FSk9Ph4eHh9Y6D7ZJT09/ZDiaM2eOuueKdHf3XiE2RF/H6hNJSLz938UaO3ja47UAd/Ru6QipCafhExFR9VCh6xzpy8yZM58YOqKiouDv71+u/ZV1WkwIodX+8DoPBmM/7pRaWFgYQkND1a8VCgXc3NzKVVNddjolC+ujr2P7mTQUFv97sUapCQa2bYgRAe5o5sgbFRMRUfVj0HAUEhKCoUOHPnadh3t6HsXJyQknTpzQart79y6KiorUvUNOTk6lZtRlZGQAQKleJ01SqVTrVBw9mubMv2E///f/o6WLLV4LcMeA1i6wkhr0146IiOixDPotJZfLIZfL9bKvwMBAzJo1C2lpaXB2dgZQMkhbKpWiXbt26nU++eQTFBYWwszMTL2Oi4tLuUMYPdq1W7kI23RW/VpqYoQXWrngtYBGaONmxwHvRERUI9SYP+GTk5Nx584dJCcnQ6lUIjY2FgDQpEkTWFtbo1evXvD29sbIkSPx1Vdf4c6dO5g8eTLGjRsHW1tbAMDw4cMRERGB0aNH45NPPsHly5cxe/ZshIeH84v7KeQXKfHDwav44eBV9b3OAODA5K5wseMAayIiqllqTDgKDw/HypUr1a/9/PwAAAcOHEBwcDCMjY2xY8cOvPfee+jUqRMsLCwwfPhwfP311+ptZDIZ9u7di/Hjx8Pf3x/16tVDaGio1ngi0s3fVzIxbcs5JGTeAwA820SOo1dKrldkZ2lmyNKIiIgqpFzhSJep6w96afRtxYoVj7zG0QONGjXC9u3bH7uOr68vDh8+rMfK6qbM3ALM2nEem2NuAAAa2Egxo39LBDeXo+WMPQaujoiIqOLKFY7s7Mo/XqQqr21EVU+lElgblYIv/u88FPnFkEiAUQHumNS7OWzNTZFXWGzoEomIiJ5KucLRgQMH1M8TExPx8ccfY/To0QgMDARQcgHGlStXYs6cOZVTJVULF9IVmLb5HKKT7gIomYE2+2VftHazM2xhREREelSucNS1a1f188jISMyfPx/Dhg1Ttw0YMAC+vr746aef8Prrr+u/SjKovMJiLPjzMpYeSUCxSsDKzBiTejXHqEB3mBjrfO9iIiKiak3nAdnHjh3D4sWLS7X7+/tj7NixeimKqo8/z99E+B9xuJF1HwDQp6UTZgzwhrPMwsCVERERVQ6d/+x3c3MrMxz9+OOPvGp0LZKWfR/v/BqNMStP4kbWfTS0s8DS1/2xeGQ7BiMiIqrVdO45+uabb/DKK69g9+7dCAgIAAAcP34cV69excaNG/VeIFWtYqUKvxxLwrw9F3GvUAljIwnGdvbExB5NYWlWY678QEREVGE6f9v17dsXly9fxg8//IDz589DCIEXX3wR77zzDnuOarjTKVmYtuUszt0ouXRD20Z2mD3QF15OlXN5BiIioupIp3BUVFSEXr164ccff8SsWbMqqyaqYor8IszbfRG/HE+CEICtuQk+fr4FhrZ3g5ERrxxORER1i07hyNTUFOfOneOtNmoJIQR2nk1HxLY4ZOQUAABe9muIT/q2QH0b3miXiIjqJp0HZI8aNQpLly6tjFqoCiXfzsMbK6Iwfs0pZOQUwFNuhVVjOuKbIW0YjIiIqE7TecxRYWEhlixZgr1798Lf3x9WVlZay+fPn6+34kj/CotV+PnINXz352UUFKtgZmyEd4OfwbvBz8Dc1NjQ5RERERmczuHo3LlzaNu2LQDg0qVLWst4uq16i0q8g2mbz+LSzVwAQNAzDvjsJR88U9/awJURERFVHzqHI81biVDNcPdeIb74vwtYdzIFAOBgZYZp/VrgZb+GDLREREQP4YVrajEhBDaeuoHZO8/jzr1CAMCwDm6Y2scLdpZmBq6OiIioeqpQOIqKisL69euRnJyMwsJCrWWbNm3SS2H0dK5k5GL6lrM4fu0OAKC5ow1mvewDfw97A1dGRERUvek8W23t2rXo1KkT4uPjsXnzZhQVFSE+Ph779++HTCarjBpJB/lFSszfcxHPLziM49fuwNzUCFP7eGH7hGcZjIiIiMpB556j2bNn45tvvsH48eNhY2ODBQsWwNPTE2+//TacnZ0ro0YqpyOXb2H6lnNIup0HAOjWvD4iX/SBm72lgSsjIiKqOXQOR1evXkW/fv0AAFKpFPfu3YNEIsGHH36I7t27IyIiQu9F0uNl5OTj8+3nsfV0KgDA0VaKmf1boo+PEwdcExER6UjncGRvb4+cnBwAQMOGDXHu3Dn4+voiKysLeXl5ei+QHk2lEljzTzK+3HUBOfnFMJIAowI9MKlXM9iYmxq6PCIiohpJ53DUuXNn7N27F76+vnj11VcxceJE7N+/H3v37kWPHj0qo0YqQ3yqAp9sPovYlCwAgG9DGWa/7AtfV477IiIieho6h6Pvv/8e+fn5AICwsDCYmpri6NGjGDhwID799FO9F0ja7hUU49t9l7Dsr0QoVQLWUhNM7tUMIwM9YMybxBIRET21Cp1We8DIyAhTpkzBlClT9FoUlW1v/E3M+OMcUrNLwmlfXyeEv9ASTjJzA1dGRERUe+gcjkaMGIHg4GB07doVzZo1q4ya6CGpWfcxY2sc9sbfBAC41rPAZy/6oJtXAwNXRkREVPvoHI6sra0xb948vP3223ByckLXrl3RtWtXBAcHw8vLqzJqrLOKlSqs+DsR8/deQl6hEiZGEozr0hgTujeFhRlvEktERFQZdA5HP/74IwAgPT0dBw8exMGDB7FgwQKMHz8eDRo0QFpamt6LrItiU7LwyaaziE9TAAD83eth1su+aO5kY+DKiIiIarcK31vNxsYG9erVQ7169WBnZwcTExM4OTnps7Y667Pt8VgblQIhAJmFKcKe98Kr/m4w4oBrIiKiSqdzOJo6dSoOHTqE06dPw8fHB126dEFYWBi6dOkCOzu7SiixbhBCqJ//9k8KAGBg24aY1rcFHKylhiqLiIioztE5HH311VeoX78+ZsyYgRdffBEtWrSojLrqnKQ7/11A08PBErMH+iLoGbkBK6LawNLMBIlf9DN0GURENYrO4SgmJgaHDh3CwYMHMW/ePBgbG6sHZAcHBzMsVZCHg5X6+ZbxnWBnaWbAaoiIiOouncNR69at0bp1a0yYMAEAcPr0aXz77beYMGECVCoVlEql3ousa8xMjAxdAhERUZ1VoQHZMTEx6plqR44cgUKhQJs2bdCtWzd910dERERUpXQOR/Xq1UNubi5at26N4OBgjBs3Dl26dIGtrW1l1EdERERUpXQOR7/++ivDEBEREdVaOg9ueeGFF2Bra4srV65g9+7duH//PgDtqehERERENZXO4ej27dvo0aMHmjVrhr59+6qviD127FhMmjRJ7wUSERERVSWdw9GHH34IU1NTJCcnw9LSUt0+ZMgQ7Nq1S6/FEREREVU1nccc7dmzB7t374arq6tWe9OmTZGUlKS3woiIiIgMQeeeo3v37mn1GD2QmZkJqbTybnMxa9YsBAUFwdLSsszblJw+fRrDhg2Dm5sbLCws0KJFCyxYsEBrncTEREgkklIP9ngRERHRAzqHoy5duuCXX35Rv5ZIJFCpVPjqq68q9TpHhYWFGDx4MN59990yl0dHR6N+/fpYtWoV4uLiMG3aNISFheH7778vte6+ffuQlpamfnTv3r3S6iYiIqKapUL3VgsODsbJkydRWFiIKVOmIC4uDnfu3MFff/1VGTUCACIiIgAAK1asKHP5m2++qfW6cePGOHbsGDZt2oSQkBCtZQ4ODnBycqqUOomIiKhm07nnyNvbG2fOnEGHDh3Qs2dP3Lt3DwMHDkRMTAyeeeaZyqixwrKzs2Fvb1+qfcCAAWjQoAE6deqEDRs2PHE/BQUFUCgUWg8iIiKqnXTqOSoqKkKvXr3w448/qntyqqtjx47h999/x44dO9Rt1tbWmD9/Pjp16gQjIyNs3boVQ4YMwcqVK/Haa689cl9z5syp9u+XiIiI9EOnniNTU1OcO3cOEolELz985syZZQ6Q1nycPHlS5/3GxcXhxRdfRHh4OHr27Klul8vl+PDDD9GhQwf4+/sjMjIS7733HubOnfvY/YWFhSE7O1v9SElJ0bkmIiIiqhl0HnM0atQoLF26FF988cVT//CQkBAMHTr0set4eHjotM/4+Hh0794d48aNw/Tp05+4fkBAAJYsWfLYdaRSaaXOxCMiIqLqQ+dwVFhYiCVLlmDv3r3w9/eHlZWV1vL58+eXe19yuRxyuVzXEh4pLi4O3bt3x+uvv45Zs2aVa5uYmBg4OzvrrQYiIiKq2XQOR+fOnUPbtm0BAJcuXdJapq/TbWVJTk7GnTt3kJycDKVSidjYWABAkyZNYG1tjbi4OHTr1g29evVCaGgo0tPTAQDGxsaoX78+AGDlypUwNTWFn58fjIyMsG3bNnz33Xf48ssvK61uIiIiqll0DkcHDhyojDqeKDw8HCtXrlS/9vPzU9cTHByM9evX49atW1i9ejVWr16tXs/d3R2JiYnq159//jmSkpJgbGyMZs2aYdmyZY8djE1ERER1i0QIIQxdRE2jUCggk8mQnZ0NW1tbvewzr7AY3uG7AQDxkb1haaZzbq0W+D6IiKi6Ku/3t87XOSIiIiKqzRiOiIiIiDQwHBERERFpYDgiIiIi0sBwRERERKSB4YiIiIhIA8MRERERkQaGIyIiIiINDEdEREREGhiOiIiIiDQwHBERERFpYDgiIiIi0sBwRERERKSB4YiIiIhIg4mhCyCqjizNTJD4RT9Dl0FERAbAniMiIiIiDQxHRERERBoYjoiIiIg0MBwRERERaWA4IiIiItLAcERERESkgeGIiIiISAPDEREREZEGhiMiIiIiDQxHRERERBoYjoiIiIg0MBwRERERaWA4IiIiItLAcERERESkgeGIiIiISAPDEREREZEGhiMiIiIiDQxHRERERBoYjoiIiIg0MBwRERERaWA4IiIiItLAcERERESkgeGIiIiISEONCUezZs1CUFAQLC0tYWdnV+Y6Eomk1GPx4sVa65w9exZdu3aFhYUFGjZsiMjISAghquAdEBERUU1gYugCyquwsBCDBw9GYGAgli5d+sj1li9fjj59+qhfy2Qy9XOFQoGePXuiW7duiIqKwqVLlzB69GhYWVlh0qRJlVo/ERER1Qw1JhxFREQAAFasWPHY9ezs7ODk5FTmstWrVyM/Px8rVqyAVCqFj48PLl26hPnz5yM0NBQSiaTM7QoKClBQUKB+rVAoKvYmiIiIqNqrMafVyiskJARyuRzt27fH4sWLoVKp1MuOHTuGrl27QiqVqtt69+6N1NRUJCYmPnKfc+bMgUwmUz/c3Nwq8y0QERGRAdWqcPTZZ59h/fr12LdvH4YOHYpJkyZh9uzZ6uXp6elwdHTU2ubB6/T09EfuNywsDNnZ2epHSkpK5bwBIiIiMjiDnlabOXOm+nTZo0RFRcHf379c+5s+fbr6eZs2bQAAkZGRWu0Pnzp7MBj7UafUAEAqlWr1NhEREVHtZdBwFBISgqFDhz52HQ8PjwrvPyAgAAqFAjdv3oSjoyOcnJxK9RBlZGQAQKkeJSIiIqqbDBqO5HI55HJ5pe0/JiYG5ubm6qn/gYGB+OSTT1BYWAgzMzMAwJ49e+Di4vJUIYyIiIhqjxozWy05ORl37txBcnIylEolYmNjAQBNmjSBtbU1tm3bhvT0dAQGBsLCwgIHDhzAtGnT8NZbb6lPiQ0fPhwREREYPXo0PvnkE1y+fBmzZ89GeHj4Y0+rERERUd1RY8JReHg4Vq5cqX7t5+cHADhw4ACCg4NhamqKRYsWITQ0FCqVCo0bN0ZkZCTGjx+v3kYmk2Hv3r0YP348/P39Ua9ePYSGhiI0NLTK3w8RERFVTzUmHK1YseKx1zjq06eP1sUfH8XX1xeHDx/WY2VERERUm9SqqfxERERET4vhiIiIiEgDwxERERGRBoYjIiIiIg0MR0REREQaGI6IiIiINDAcEREREWlgOCIiIiLSwHBEREREpIHhiIiIiEgDwxERERGRBoYjIiIiIg0MR0REREQaTAxdANUulmYmSPyin6HLICIiqjD2HBERERFpYDgiIiIi0sBwRERERKSB4YiIiIhIA8MRERERkQaGIyIiIiINDEdEREREGhiOiIiIiDQwHBERERFpYDgiIiIi0sBwRERERKSB4YiIiIhIA8MRERERkQaGIyIiIiINDEdEREREGhiOiIiIiDQwHBERERFpYDgiIiIi0sBwRERERKSB4YiIiIhIA8MRERERkQaGIyIiIiINDEdEREREGmpMOJo1axaCgoJgaWkJOzu7UstXrFgBiURS5iMjIwMAkJiYWObyXbt2VfG7ISIiourKxNAFlFdhYSEGDx6MwMBALF26tNTyIUOGoE+fPlpto0ePRn5+Pho0aKDVvm/fPrRs2VL92t7evnKKJiIiohqnxoSjiIgIACU9RGWxsLCAhYWF+vWtW7ewf//+MoOUg4MDnJycKqVOIiIiqtlqzGk1Xf3yyy+wtLTEoEGDSi0bMGAAGjRogE6dOmHDhg1P3FdBQQEUCoXWg4iIiGqnWhuOli1bhuHDh2v1JllbW2P+/PnYsGEDdu7ciR49emDIkCFYtWrVY/c1Z84cyGQy9cPNza2yyyciIiIDMWg4mjlz5iMHUT94nDx5Uuf9Hjt2DPHx8RgzZoxWu1wux4cffogOHTrA398fkZGReO+99zB37tzH7i8sLAzZ2dnqR0pKis41ERERUc1g0DFHISEhGDp06GPX8fDw0Hm/S5YsQZs2bdCuXbsnrhsQEIAlS5Y8dh2pVAqpVKpzHURERFTzGDQcyeVyyOVyve4zNzcXv//+O+bMmVOu9WNiYuDs7KzXGoiIiKjmqjGz1ZKTk3Hnzh0kJydDqVQiNjYWANCkSRNYW1ur11u3bh2Ki4sxYsSIUvtYuXIlTE1N4efnByMjI2zbtg3fffcdvvzyy6p6G0RERFTN1ZhwFB4ejpUrV6pf+/n5AQAOHDiA4OBgdfvSpUsxcOBA1KtXr8z9fP7550hKSoKxsTGaNWuGZcuW4bXXXqvU2omIiKjmkAghhKGLqGkUCgVkMhmys7Nha2url33mFRbDO3w3ACA+sjcszWpMbiUiIqoRyvv9XWun8hMRERFVBLsnqglLMxMkftHP0GUQERHVeew5IiIiItLAcERERESkgeGIiIiISAPDEREREZEGhiMiIiIiDQxHRERERBoYjoiIiIg0MBwRERERaWA4IiIiItLAcERERESkgeGIiIiISAPDEREREZEGhiMiIiIiDQxHRERERBoYjoiIiIg0mBi6gJpICAEAUCgUBq6EiIiIyuvB9/aD7/FHYTiqgJycHACAm5ubgSshIiIiXeXk5EAmkz1yuUQ8KT5RKSqVCqmpqbCxsYFEItHbfhUKBdzc3JCSkgJbW1u97bc24zHTDY+Xbni8dMdjphseL909zTETQiAnJwcuLi4wMnr0yCL2HFWAkZERXF1dK23/tra2/EeiIx4z3fB46YbHS3c8Zrrh8dJdRY/Z43qMHuCAbCIiIiINDEdEREREGhiOqhGpVIoZM2ZAKpUaupQag8dMNzxeuuHx0h2PmW54vHRXFceMA7KJiIiINLDniIiIiEgDwxERERGRBoYjIiIiIg0MR0REREQaGI6q2KJFi+Dp6Qlzc3O0a9cOR44ceez6hw4dQrt27WBubo7GjRtj8eLFVVRp9aDL8dq0aRN69uyJ+vXrw9bWFoGBgdi9e3cVVls96Po79sBff/0FExMTtGnTpnILrGZ0PV4FBQWYNm0a3N3dIZVK8cwzz2DZsmVVVG31oOsxW716NVq3bg1LS0s4OzvjjTfewO3bt6uoWsM6fPgw+vfvDxcXF0gkEmzZsuWJ29Tlz31dj1elfe4LqjJr164Vpqam4ueffxbx8fFi4sSJwsrKSiQlJZW5/rVr14SlpaWYOHGiiI+PFz///LMwNTUVGzZsqOLKDUPX4zVx4kTx5Zdfin/++UdcunRJhIWFCVNTU3Hq1KkqrtxwdD1mD2RlZYnGjRuLXr16idatW1dNsdVARY7XgAEDRMeOHcXevXtFQkKCOHHihPjrr7+qsGrD0vWYHTlyRBgZGYkFCxaIa9euiSNHjoiWLVuKl156qYorN4ydO3eKadOmiY0bNwoAYvPmzY9dv65/7ut6vCrrc5/hqAp16NBBvPPOO1ptXl5e4uOPPy5z/SlTpggvLy+ttrffflsEBARUWo3Via7Hqyze3t4iIiJC36VVWxU9ZkOGDBHTp08XM2bMqFPhSNfj9X//939CJpOJ27dvV0V51ZKux+yrr74SjRs31mr77rvvhKura6XVWF2V58u+rn/uayrP8SqLPj73eVqtihQWFiI6Ohq9evXSau/Vqxf+/vvvMrc5duxYqfV79+6NkydPoqioqNJqrQ4qcrweplKpkJOTA3t7+8oosdqp6DFbvnw5rl69ihkzZlR2idVKRY7X1q1b4e/vj7lz56Jhw4Zo1qwZJk+ejPv371dFyQZXkWMWFBSE69evY+fOnRBC4ObNm9iwYQP69etXFSXXOHX5c18f9PW5zxvPVpHMzEwolUo4OjpqtTs6OiI9Pb3MbdLT08tcv7i4GJmZmXB2dq60eg2tIsfrYfPmzcO9e/fw6quvVkaJ1U5Fjtnly5fx8ccf48iRIzAxqVsfBxU5XteuXcPRo0dhbm6OzZs3IzMzE++99x7u3LlTJ8YdVeSYBQUFYfXq1RgyZAjy8/NRXFyMAQMGYOHChVVRco1Tlz/39UFfn/vsOapiEolE67UQolTbk9Yvq7220vV4PfDbb79h5syZWLduHRo0aFBZ5VVL5T1mSqUSw4cPR0REBJo1a1ZV5VU7uvyOqVQqSCQSrF69Gh06dEDfvn0xf/58rFixos70HgG6HbP4+HhMmDAB4eHhiI6Oxq5du5CQkIB33nmnKkqtker6535F6fNzv279qWhAcrkcxsbGpf66ysjIKPVXwgNOTk5lrm9iYgIHB4dKq7U6qMjxemDdunUYM2YM1q9fj+eee64yy6xWdD1mOTk5OHnyJGJiYhASEgKg5MtfCAETExPs2bMH3bt3r5LaDaEiv2POzs5o2LAhZDKZuq1FixYQQuD69eto2rRppdZsaBU5ZnPmzEGnTp3w0UcfAQBatWoFKysrdO7cGZ9//jl7Qh5Slz/3n4a+P/fZc1RFzMzM0K5dO+zdu1erfe/evQgKCipzm8DAwFLr79mzB/7+/jA1Na20WquDihwvoOQvh9GjR2PNmjV1bkyDrsfM1tYWZ8+eRWxsrPrxzjvvoHnz5oiNjUXHjh2rqnSDqMjvWKdOnZCamorc3Fx126VLl2BkZARXV9dKrbc6qMgxy8vLg5GR9leNsbExgP96ROg/dflzv6Iq5XP/qYZzk04eTIFdunSpiI+PFx988IGwsrISiYmJQgghPv74YzFy5Ej1+g+mdH744YciPj5eLF26tE5N6dT1eK1Zs0aYmJiI//3vfyItLU39yMrKMtRbqHK6HrOH1bXZaroer5ycHOHq6ioGDRok4uLixKFDh0TTpk3F2LFjDfUWqpyux2z58uXCxMRELFq0SFy9elUcPXpU+Pv7iw4dOhjqLVSpnJwcERMTI2JiYgQAMX/+fBETE6O+9AE/97Xperwq63Of4aiK/e9//xPu7u7CzMxMtG3bVhw6dEi97PXXXxddu3bVWv/gwYPCz89PmJmZCQ8PD/HDDz9UccWGpcvx6tq1qwBQ6vH6669XfeEGpOvvmKa6Fo6E0P14nT9/Xjz33HPCwsJCuLq6itDQUJGXl1fFVRuWrsfsu+++E97e3sLCwkI4OzuLESNGiOvXr1dx1YZx4MCBx34u8XNfm67Hq7I+9yVCsF+TiIiI6AGOOSIiIiLSwHBEREREpIHhiIiIiEgDwxERERGRBoYjIiIiIg0MR0REREQaGI6IiIiINDAcERERUbVw+PBh9O/fHy4uLpBIJNiyZYtO28+cORMSiaTUw8rKSqf9MBwRUbWUmJgIiUSC2NhYQ5dCRFXk3r17aN26Nb7//vsKbT958mSkpaVpPby9vTF48GCd9sNwRFTH3bp1C6ampsjLy0NxcTGsrKyQnJxs6LLg5uaGtLQ0+Pj4GLqUShUcHIwPPvjA4Psgqg6ef/55fP755xg4cGCZywsLCzFlyhQ0bNgQVlZW6NixIw4ePKhebm1tDScnJ/Xj5s2biI+Px5gxY3Sqw+Rp3gQR1XzHjh1DmzZtYGlpiRMnTsDe3h6NGjUydFkwNjaGk5PTI5cLIaBUKmFiwo8xorrijTfeQGJiItauXQsXFxds3rwZffr0wdmzZ9G0adNS6y9ZsgTNmjVD586ddfo57DkiquP+/vtvdOrUCQBw9OhR9fMnWb58OVq0aAFzc3N4eXlh0aJF6mUPTolt2rQJ3bp1g6WlJVq3bo1jx44BALKzs2FhYYFdu3Zp7XPTpk2wsrJCbm5uqdNqBw8ehEQiwe7du+Hv7w+pVIojR46goKAAEyZMQIMGDWBubo5nn30WUVFR6n0+2O7PP/+Ev78/LC0tERQUhIsXL6rXmTlzJtq0aYNly5ahUaNGsLa2xrvvvgulUom5c+fCyckJDRo0wKxZs7Tqzc7OxltvvYUGDRrA1tYW3bt3x+nTp0vt99dff4WHhwdkMhmGDh2KnJwcAMDo0aNx6NAhLFiwQD02IjExsczjvWjRIjRt2hTm5uZwdHTEoEGDnriP+Ph49O3bF9bW1nB0dMTIkSORmZmp3mdwcDBCQkIQEhICOzs7ODg4YPr06dC85eajfi5RVbt69Sp+++03rF+/Hp07d8YzzzyDyZMn49lnn8Xy5ctLrV9QUIDVq1fr3GsEAHiq29YSUY2UlJQkZDKZkMlkwtTUVJibmwuZTCbMzMyEVCoVMplMvPvuu4/c/qeffhLOzs5i48aN4tq1a2Ljxo3C3t5erFixQgghREJCggAgvLy8xPbt28XFixfFoEGDhLu7uygqKhJCCPHKK6+I1157TWu/r7zyihg2bJjWPmJiYoQQ/92tu1WrVmLPnj3iypUrIjMzU0yYMEG4uLiInTt3iri4OPH666+LevXqidu3b2tt17FjR3Hw4EERFxcnOnfuLIKCgtQ/d8aMGcLa2loMGjRIxMXFia1btwozMzPRu3dv8f7774sLFy6IZcuWCQDi2LFjQgghVCqV6NSpk+jfv7+IiooSly5dEpMmTRIODg7qn/1gvwMHDhRnz54Vhw8fFk5OTuKTTz4RQgiRlZUlAgMDxbhx40RaWppIS0sTxcXFpY53VFSUMDY2FmvWrBGJiYni1KlTYsGCBY/dR2pqqpDL5SIsLEycP39enDp1SvTs2VN069ZNvd+uXbsKa2trMXHiRHHhwgWxatUqYWlpKX766acn/lyiygZAbN68Wf36999/FwCElZWV1sPExES8+uqrpbZfs2aNMDExEWlpabr/7KcpnIhqpqKiIpGQkCBOnz4tTE1NRWxsrLhy5YqwtrYWhw4dEgkJCeLWrVuP3N7NzU2sWbNGq+2zzz4TgYGBQoj/gs2SJUvUy+Pi4gQAcf78eSGEEJs2bRLW1tbi3r17QgghsrOzhbm5udixY4fWPh4OR1u2bFHvMzc3V5iamorVq1er2woLC4WLi4uYO3eu1nb79u1Tr7Njxw4BQNy/f18IURJiLC0thUKhUK/Tu3dv4eHhIZRKpbqtefPmYs6cOUIIIf78809ha2sr8vPztY7DM888I3788cdH7vejjz4SHTt2VL/u2rWrmDhx4iOOdImNGzcKW1tbrf1oKmsfn376qejVq5dWW0pKigAgLl68qN6uRYsWQqVSqdeZOnWqaNGiRbl+LlFlejgcrV27VhgbG4sLFy6Iy5cvaz3KCkDdu3cXL730UoV+Nk+rEdVBJiYm8PDwwIULF9C+fXu0bt0a6enpcHR0RJcuXeDh4QG5XF7mtrdu3UJKSgrGjBkDa2tr9ePzzz/H1atXtdZt1aqV+rmzszMAICMjAwDQr18/mJiYYOvWrQCAjRs3wsbGBr169Xps7f7+/urnV69eRVFRkdapQFNTU3To0AHnz58vdy0A4OHhARsbG/VrR0dHeHt7w8jISKvtwTbR0dHIzc2Fg4OD1nFISEjQOg4P79fZ2Vnr55ZHz5494e7ujsaNG2PkyJFYvXo18vLyHrtNdHQ0Dhw4oFWbl5cXAGjVFxAQAIlEon4dGBiIy5cvQ6lUVujnElUWPz8/KJVKZGRkoEmTJlqPh8cnJiQk4MCBAxU7pQYOyCaqk1q2bImkpCQUFRVBpVLB2toaxcXFKC4uhrW1Ndzd3REXF1fmtiqVCgDw888/o2PHjlrLjI2NtV6bmpqqnz/4An6wvZmZGQYNGoQ1a9Zg6NChWLNmDYYMGfLEAdaa1ysR/46N0fxyf9D+cNvjanl4+YN1ymp7sI1KpYKzs7PWTJkH7OzsHrtfzZ9bHjY2Njh16hQOHjyIPXv2IDw8HDNnzkRUVJTWz9KkUqnQv39/fPnll6WWPQiHlfFziZ5Gbm4urly5on6dkJCA2NhY2Nvbo1mzZhgxYgRGjRqFefPmwc/PD5mZmdi/fz98fX3Rt29f9XbLli2Ds7Mznn/++QrVwZ4jojpo586diI2NhZOTE1atWoXY2Fj4+Pjg22+/RWxsLHbu3PnIbR0dHdGwYUNcu3at1F9vnp6eOtUxYsQI7Nq1C3FxcThw4ABGjBih0/ZNmjSBmZkZjh49qm4rKirCyZMn0aJFC532pau2bdsiPT0dJiYmpY7Do3rdymJmZgalUvnE9UxMTPDcc89h7ty5OHPmDBITE7F///5H7qNt27aIi4uDh4dHqfo0A+bx48e1tjt+/DiaNm2qDrqP+7lE+nby5En4+fnBz88PABAaGgo/Pz+Eh4cDKJkIMmrUKEyaNAnNmzfHgAEDcOLECbi5uan3oVKpsGLFCowePbrUH2zlxZ4jojrI3d0d6enpuHnzJl588UUYGRkhPj4eAwcOhIuLyxO3nzlzJiZMmABbW1s8//zzKCgowMmTJ3H37l2EhoaWu46uXbvC0dERI0aMgIeHBwICAnR6H1ZWVnj33Xfx0UcfqS9BMHfuXOTl5VW4O728nnvuOQQGBuKll17Cl19+iebNmyM1NRU7d+7ESy+9pHX673E8PDxw4sQJJCYmwtraGvb29lqn8gBg+/btuHbtGrp06YJ69eph586dUKlUaN68+SP3MX78ePz8888YNmwYPvroI8jlcly5cgVr167Fzz//rP7SSElJQWhoKN5++22cOnUKCxcuxLx588r1c4n0LTg4WGu25MNMTU0RERGBiIiIR65jZGSElJSUp6qDPUdEddTBgwfRvn17mJub48SJE2jYsGG5ghEAjB07FkuWLMGKFSvg6+uLrl27YsWKFTr3HEkkEgwbNgynT5/WudfogS+++AKvvPIKRo4cibZt2+LKlSvYvXs36tWrV6H9lZdEIsHOnTvRpUsXvPnmm2jWrBmGDh2KxMREODo6lns/kydPhrGxMby9vVG/fv0yL8BpZ2eHTZs2oXv37mjRogUWL16M3377DS1btnzkPlxcXPDXX39BqVSid+/e8PHxwcSJEyGTybTC16hRo3D//n106NAB48ePx/vvv4+33nqrXD+XqLaSiMdFNCIiqrWCg4PRpk0bfPvtt4YuhahaYc8RERERkQaGIyIiIiINPK1GREREpIE9R0REREQaGI6IiIiINDAcEREREWlgOCIiIiLSwHBEREREpIHhiIiIiEgDwxERERGRBoYjIiIiIg3/D5omjKY8WL2OAAAAAElFTkSuQmCC",
+ "text/plain": [
+ ""
+ ]
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "train_fn = functools.partial(\n",
+ " ppo.train, num_timesteps=10_000_000, num_evals=10, reward_scaling=0.1,\n",
+ " episode_length=1000, normalize_observations=True, action_repeat=1,\n",
+ " unroll_length=10, num_minibatches=32, num_updates_per_batch=8,\n",
+ " discounting=0.97, learning_rate=3e-4, entropy_cost=1e-3, num_envs=1024,\n",
+ " batch_size=1024, seed=0)\n",
+ "\n",
+ "x_data = []\n",
+ "y_data = []\n",
+ "ydataerr = []\n",
+ "env = envs.get_environment(\"trotting_anymal\", step_k = 13)\n",
+ "\n",
+ "def progress(num_steps, metrics):\n",
+ " x_data.append(num_steps)\n",
+ " y_data.append(metrics['eval/episode_reward'])\n",
+ " ydataerr.append(metrics['eval/episode_reward_std'])\n",
+ "\n",
+ "make_inference_fn, params, _= train_fn(environment=env, progress_fn=progress)\n",
+ "\n",
+ "plt.errorbar(x_data, y_data, yerr=ydataerr)\n",
+ "plt.xlabel('# environment steps')\n",
+ "plt.ylabel('reward per episode')"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "We see that PPO takes around 9e6 simulator steps to catch up to APG."
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "## Study 2: Quadruped Locomotion\n",
+ "\n",
+ "As we saw in the imitation learning example, FoPG methods benefit from detailed reward signals. To teach locomotion, we reward the feet based on the Raibert Heuristic. Similarly to [prior work](https://arxiv.org/abs/2403.14864), we use a gait schedule to incentivize opposite pairs of legs to move in sync at a fixed frequency. At the beginning of a new scheduled step, we calculate the target position for the feet at the end of the step. \n",
+ "\n",
+ "For each foot, we calculate:\n",
+ "\n",
+ "$$\n",
+ "p^* = h_0 + \\frac{\\Delta T}{2} v_0\n",
+ "$$\n",
+ "\n",
+ "Where $p^*$ is x, y component of the foot's target position, $h_0$ is the x, y component of the corresponding hip at lift-off, $\\Delta T$ is the scheduled step duration, and $v_0$ is the base velocity at lift-off. \n",
+ "\n",
+ "Due to their limited exploration power, FoPG methods benefit greatly from having an good \"initial guess\" of the policy - familiar terminology in Model Predictive Control and Trajectory Optimization. We formulate the problem as [residual learning](https://arxiv.org/abs/1512.03385). Let $\\phi$ be the parameters of a baseline policy that we already have, and let $f$ and $g$ be the neural networks for the learned and baseline policy. We freeze $\\phi$ and learn parameters $\\theta$, for the policy:\n",
+ "\n",
+ "$$\n",
+ "a_t = f(g(x_t; \\phi), x_t; \\theta) + g(x_t; \\phi)\n",
+ "$$\n",
+ "\n",
+ "We use the in-place trotting policy from last section as $\\phi$ and $x_t$ denotes the state at time t. In this example we track a 0.75 m/s velocity target, but since locomotion is stabler at faster trots, you can experiment with $\\phi$ for faster velocity targets!\n",
+ "\n",
+ "While it might seem more natural to \"hotstart\" the learning by simply initializing the parameters $\\theta$ as $\\phi$, with the policy $a_t = f(x_t; \\theta)$, we find that the residual method trains more stably in practice."
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "#### The RL Environment"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 25,
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "def axis_angle_to_quaternion(v: jp.ndarray, theta:jp.float_):\n",
+ " \"\"\" \n",
+ " axis angle representation: rotation of theta around v. \n",
+ " \"\"\" \n",
+ " return jp.concatenate([jp.cos(0.5*theta).reshape(1), jp.sin(0.5*theta)*v.reshape(3)])\n",
+ "\n",
+ "def get_config():\n",
+ " \"\"\"Returns reward config for anymal quadruped environment.\"\"\"\n",
+ "\n",
+ " def get_default_rewards_config():\n",
+ " default_config = config_dict.ConfigDict(\n",
+ " dict(\n",
+ " scales=config_dict.ConfigDict(\n",
+ " dict(\n",
+ " tracking_lin_vel = 1.0,\n",
+ " orientation = -1.0, # non-flat base\n",
+ " height = 0.5,\n",
+ " lin_vel_z=-1.0, # prevents the suicide policy\n",
+ " torque = -0.01,\n",
+ " feet_pos = -1, # Bad action hard-coding. \n",
+ " feet_height = -1, # prevents it from just standing still\n",
+ " joint_velocity = -0.001\n",
+ " )\n",
+ " ),\n",
+ " )\n",
+ " )\n",
+ " return default_config\n",
+ "\n",
+ " default_config = config_dict.ConfigDict(\n",
+ " dict(rewards=get_default_rewards_config(),))\n",
+ "\n",
+ " return default_config\n",
+ "\n",
+ "class FwdTrotAnymal(PipelineEnv):\n",
+ "\n",
+ " def __init__(\n",
+ " self,\n",
+ " termination_height: float=0.25,\n",
+ " **kwargs,\n",
+ " ):\n",
+ " \n",
+ " self.target_vel = kwargs.pop('target_vel', 0.75)\n",
+ " step_k = kwargs.pop('step_k', 25)\n",
+ " self.baseline_inference_fn = kwargs.pop(\"baseline_inference_fn\")\n",
+ " physics_steps_per_control_step = 10\n",
+ " kwargs['n_frames'] = kwargs.get(\n",
+ " 'n_frames', physics_steps_per_control_step)\n",
+ " self.termination_height = termination_height\n",
+ "\n",
+ " mj_model = mujoco.MjModel.from_xml_path(xml_path)\n",
+ " kp = 230\n",
+ " mj_model.actuator_gainprm[:, 0] = kp\n",
+ " mj_model.actuator_biasprm[:, 1] = -kp\n",
+ " self._init_q = mj_model.keyframe('standing').qpos\n",
+ " self._default_ap_pose = mj_model.keyframe('standing').qpos[7:]\n",
+ " self.reward_config = get_config()\n",
+ "\n",
+ " self.action_loc = self._default_ap_pose\n",
+ " self.action_scale = jp.array([0.2, 0.8, 0.8] * 4)\n",
+ " \n",
+ " self.target_h = self._init_q[2]\n",
+ "\n",
+ " sys = mjcf.load_model(mj_model)\n",
+ " super().__init__(sys=sys, **kwargs)\n",
+ " \n",
+ " \"\"\"\n",
+ " Kinematic references are used for gait scheduling.\n",
+ " \"\"\"\n",
+ "\n",
+ " kinematic_ref_qpos = make_kinematic_ref(\n",
+ " cos_wave, step_k, scale=0.3, dt=self.dt)\n",
+ " self.l_cycle = jp.array(kinematic_ref_qpos.shape[0])\n",
+ " self.kinematic_ref_qpos = jp.array(kinematic_ref_qpos + self._default_ap_pose)\n",
+ "\n",
+ " \"\"\"\n",
+ " Foot tracking\n",
+ " \"\"\"\n",
+ " gait_k = step_k * 2\n",
+ " self.gait_period = gait_k * self.dt\n",
+ "\n",
+ " self.step_k = step_k\n",
+ " self.feet_inds = jp.array([21,28,35,42]) # LF, RF, LH, RH\n",
+ " self.hip_inds = self.feet_inds - 6\n",
+ "\n",
+ " self.pipeline_step = jax.checkpoint(self.pipeline_step,\n",
+ " policy=jax.checkpoint_policies.dots_with_no_batch_dims_saveable)\n",
+ " \n",
+ " def reset(self, rng: jax.Array) -> State:\n",
+ " rng, key_xyz, key_ang, key_ax, key_q, key_qd = jax.random.split(rng, 6)\n",
+ "\n",
+ " qpos = jp.array(self._init_q)\n",
+ " qvel = jp.zeros(18)\n",
+ " \n",
+ " #### Add Randomness ####\n",
+ " \n",
+ " r_xyz = 0.2 * (jax.random.uniform(key_xyz, (3,))-0.5)\n",
+ " r_angle = (jp.pi/12) * (jax.random.uniform(key_ang, (1,)) - 0.5) # 15 deg range\n",
+ " r_axis = (jax.random.uniform(key_ax, (3,)) - 0.5)\n",
+ " r_axis = r_axis / jp.linalg.norm(r_axis)\n",
+ " r_quat = axis_angle_to_quaternion(r_axis, r_angle)\n",
+ "\n",
+ " r_joint_q = 0.2 * (jax.random.uniform(key_q, (12,)) - 0.5)\n",
+ " r_joint_qd = 0.1 * (jax.random.uniform(key_qd, (12,)) - 0.5)\n",
+ " \n",
+ " qpos = qpos.at[0:3].set(qpos[0:3] + r_xyz)\n",
+ " qpos = qpos.at[3:7].set(r_quat)\n",
+ " qpos = qpos.at[7:19].set(qpos[7:19] + r_joint_q)\n",
+ " qvel = qvel.at[6:18].set(qvel[6:18] + r_joint_qd)\n",
+ " \n",
+ " data = self.pipeline_init(qpos, qvel)\n",
+ "\n",
+ " # Ensure you're not sunken into the ground nor above it.\n",
+ " pen = jp.min(data.contact.dist)\n",
+ " qpos = qpos.at[2].set(qpos[2] - pen)\n",
+ " data = self.pipeline_init(qpos, qvel)\n",
+ "\n",
+ " state_info = {\n",
+ " 'rng': rng,\n",
+ " 'steps': 0.0,\n",
+ " 'reward_tuple': {\n",
+ " 'tracking_lin_vel': 0.0,\n",
+ " 'orientation': 0.0,\n",
+ " 'height': 0.0,\n",
+ " 'lin_vel_z': 0.0,\n",
+ " 'torque': 0.0,\n",
+ " 'joint_velocity': 0.0,\n",
+ " 'feet_pos': 0.0,\n",
+ " 'feet_height': 0.0\n",
+ " },\n",
+ " 'last_action': jp.zeros(12), # from MJX tutorial.\n",
+ " 'baseline_action': jp.zeros(12),\n",
+ " 'xy0': jp.zeros((4, 2)),\n",
+ " 'k0': 0.0,\n",
+ " 'xy*': jp.zeros((4, 2))\n",
+ " }\n",
+ "\n",
+ " x, xd = data.x, data.xd\n",
+ " _obs = self._get_obs(data.qpos, x, xd, state_info) # inner obs; to trotter\n",
+ " \n",
+ " action_key, key = jax.random.split(state_info['rng'])\n",
+ " state_info['rng'] = key\n",
+ " next_action, _ = self.baseline_inference_fn(_obs, action_key)\n",
+ "\n",
+ " obs = jp.concatenate([_obs, next_action])\n",
+ "\n",
+ " reward, done = jp.zeros(2)\n",
+ " metrics = {}\n",
+ " for k in state_info['reward_tuple']:\n",
+ " metrics[k] = state_info['reward_tuple'][k]\n",
+ " state = State(data, obs, reward, done, metrics, state_info)\n",
+ " return jax.lax.stop_gradient(state)\n",
+ "\n",
+ " def step(self, state: State, action: jax.Array) -> State:\n",
+ "\n",
+ " action = jp.clip(action, -1, 1)\n",
+ "\n",
+ " cur_base = state.obs[-12:]\n",
+ " action += cur_base\n",
+ " state.info['baseline_action'] = cur_base\n",
+ "\n",
+ " action = self.action_loc + (action * self.action_scale)\n",
+ "\n",
+ " data = self.pipeline_step(state.pipeline_state, action)\n",
+ " \n",
+ " # observation data\n",
+ " x, xd = data.x, data.xd\n",
+ " obs = self._get_obs(data.qpos, x, xd, state.info)\n",
+ "\n",
+ " # Terminate if flipped over or fallen down.\n",
+ " done = 0.0\n",
+ " done = jp.where(x.pos[0, 2] < self.termination_height, 1.0, done)\n",
+ " up = jp.array([0.0, 0.0, 1.0])\n",
+ " done = jp.where(jp.dot(math.rotate(up, x.rot[0]), up) < 0, 1.0, done)\n",
+ "\n",
+ " #### Foot Position Reference Updating ####\n",
+ "\n",
+ " # Detect the start of a new step\n",
+ " s = state.info['steps']\n",
+ " step_num = s // (self.step_k)\n",
+ " even_step = step_num % 2 == 0\n",
+ " new_step = (s % self.step_k) == 0\n",
+ " new_even_step = jp.logical_and(new_step, even_step)\n",
+ " new_odd_step = jp.logical_and(new_step, jp.logical_not(even_step))\n",
+ "\n",
+ " # Apply railbert heuristic to calculate target foot position, after step\n",
+ " hip_xy = data.geom_xpos[self.hip_inds][:,:2] # 4 x 2\n",
+ " v_body = data.qvel[0:2]\n",
+ " step_period = self.gait_period/2\n",
+ " raibert_xy = hip_xy + (step_period/2) * v_body\n",
+ "\n",
+ " # Update. \n",
+ " cur_tars = state.info['xy*']\n",
+ " i_RFLH = jp.array([1, 2])\n",
+ " i_LFRH = jp.array([0, 3])\n",
+ " feet_xy = data.geom_xpos[self.feet_inds][:,:2]\n",
+ " \n",
+ " # With the trotting gait, we will move one pair of opposite legs, \n",
+ " # and keep the other pair fixed in place.\n",
+ " case_c1 = raibert_xy.at[i_LFRH].set(feet_xy[i_LFRH]) \n",
+ " case_c2 = raibert_xy.at[i_RFLH].set(feet_xy[i_RFLH])\n",
+ " xy_tars = jp.where(new_even_step, case_c1, cur_tars)\n",
+ " xy_tars = jp.where(new_odd_step, case_c2, xy_tars)\n",
+ " state.info['xy*'] = xy_tars\n",
+ "\n",
+ " # Save timestep and location at start of step.\n",
+ " state.info['k0'] = jp.where(new_step,\n",
+ " state.info['steps'],\n",
+ " state.info['k0'])\n",
+ " state.info['xy0'] = jp.where(new_step, \n",
+ " feet_xy,\n",
+ " state.info['xy0'])\n",
+ "\n",
+ " # reward\n",
+ " reward_tuple = {\n",
+ " 'tracking_lin_vel': (\n",
+ " self._reward_tracking_lin_vel(jp.array([self.target_vel, 0, 0]), x, xd)\n",
+ " * self.reward_config.rewards.scales.tracking_lin_vel\n",
+ " ),\n",
+ " 'orientation': (\n",
+ " self._reward_orientation(x)\n",
+ " * self.reward_config.rewards.scales.orientation\n",
+ " ),\n",
+ " 'lin_vel_z': (\n",
+ " self._reward_lin_vel_z(xd)\n",
+ " * self.reward_config.rewards.scales.lin_vel_z\n",
+ " ),\n",
+ " 'height': (\n",
+ " self._reward_height(data.qpos) \n",
+ " * self.reward_config.rewards.scales.height\n",
+ " ),\n",
+ " 'torque': (\n",
+ " self._reward_action(data.qfrc_actuator)\n",
+ " * self.reward_config.rewards.scales.torque\n",
+ " ),\n",
+ " 'joint_velocity': (\n",
+ " self._reward_joint_velocity(data.qvel)\n",
+ " * self.reward_config.rewards.scales.joint_velocity\n",
+ " ),\n",
+ " 'feet_pos': (\n",
+ " self._reward_feet_pos(data, state)\n",
+ " * self.reward_config.rewards.scales.feet_pos\n",
+ " ),\n",
+ " 'feet_height': (\n",
+ " self._reward_feet_height(data, state.info)\n",
+ " * self.reward_config.rewards.scales.feet_height\n",
+ " )\n",
+ " }\n",
+ " \n",
+ " reward = sum(reward_tuple.values())\n",
+ "\n",
+ " # state management\n",
+ " state.info['reward_tuple'] = reward_tuple\n",
+ " state.info['last_action'] = action\n",
+ "\n",
+ " for k in state.info['reward_tuple'].keys():\n",
+ " state.metrics[k] = state.info['reward_tuple'][k]\n",
+ "\n",
+ " # next action\n",
+ " action_key, key = jax.random.split(state.info['rng'])\n",
+ " state.info['rng'] = key\n",
+ " next_action, _ = self.baseline_inference_fn(obs, action_key)\n",
+ " obs = jp.concatenate([obs, next_action])\n",
+ "\n",
+ " state = state.replace(\n",
+ " pipeline_state=data, obs=obs, reward=reward,\n",
+ " done=done)\n",
+ " return state\n",
+ "\n",
+ " def _get_obs(self, qpos: jax.Array, x: Transform, xd: Motion,\n",
+ " state_info: Dict[str, Any]) -> jax.Array:\n",
+ "\n",
+ " inv_base_orientation = math.quat_inv(x.rot[0])\n",
+ " local_rpyrate = math.rotate(xd.ang[0], inv_base_orientation)\n",
+ "\n",
+ " obs_list = []\n",
+ " # yaw rate\n",
+ " obs_list.append(jp.array([local_rpyrate[2]]) * 0.25)\n",
+ " # projected gravity\n",
+ " obs_list.append(\n",
+ " math.rotate(jp.array([0.0, 0.0, -1.0]), inv_base_orientation))\n",
+ " # motor angles\n",
+ " angles = qpos[7:19]\n",
+ " obs_list.append(angles - self._default_ap_pose)\n",
+ " # last action\n",
+ " obs_list.append(state_info['last_action'])\n",
+ " # gait schedule\n",
+ " kin_ref = self.kinematic_ref_qpos[jp.array(state_info['steps']%self.l_cycle, int)]\n",
+ " obs_list.append(kin_ref)\n",
+ "\n",
+ " obs = jp.clip(jp.concatenate(obs_list), -100.0, 100.0)\n",
+ "\n",
+ " return obs\n",
+ "\n",
+ " # ------------ reward functions----------------\n",
+ " def _reward_tracking_lin_vel(\n",
+ " self, commands: jax.Array, x: Transform, xd: Motion) -> jax.Array:\n",
+ " # Tracking of linear velocity commands (xy axes)\n",
+ " local_vel = math.rotate(xd.vel[0], math.quat_inv(x.rot[0]))\n",
+ " lin_vel_error = jp.sum(jp.square(commands[:2] - local_vel[:2]))\n",
+ " lin_vel_reward = jp.exp(-lin_vel_error)\n",
+ " return lin_vel_reward\n",
+ " def _reward_orientation(self, x: Transform) -> jax.Array:\n",
+ " # Penalize non flat base orientation\n",
+ " up = jp.array([0.0, 0.0, 1.0])\n",
+ " rot_up = math.rotate(up, x.rot[0])\n",
+ " return jp.sum(jp.square(rot_up[:2]))\n",
+ " def _reward_lin_vel_z(self, xd: Motion) -> jax.Array:\n",
+ " # Penalize z axis base linear velocity\n",
+ " return jp.clip(jp.square(xd.vel[0, 2]), 0, 10)\n",
+ " def _reward_joint_velocity(self, qvel):\n",
+ " return jp.clip(jp.sqrt(jp.sum(jp.square(qvel[6:]))), 0, 100)\n",
+ " def _reward_height(self, qpos) -> jax.Array:\n",
+ " return jp.exp(-jp.abs(qpos[2] - self.target_h)) # Not going to be > 1 meter tall.\n",
+ " def _reward_action(self, action) -> jax.Array:\n",
+ " return jp.sqrt(jp.sum(jp.square(action)))\n",
+ " def _reward_feet_pos(self, data, state): \n",
+ " dt = (state.info['steps'] - state.info['k0']) * self.dt # scalar\n",
+ " step_period = self.gait_period / 2\n",
+ " xyt = state.info['xy0'] + (state.info['xy*'] - state.info['xy0']) * (dt/step_period)\n",
+ "\n",
+ " feet_pos = data.geom_xpos[self.feet_inds][:, :2]\n",
+ "\n",
+ " rews = jp.sum(jp.square(feet_pos - xyt), axis=1) \n",
+ " rews = jp.clip(rews, 0, 10)\n",
+ " return jp.sum(rews)\n",
+ " def _reward_feet_height(self, data, state_info):\n",
+ " \"\"\" \n",
+ " Feet height tracks rectified sine waves \n",
+ " \"\"\"\n",
+ " h_tar = 0.1\n",
+ " t = state_info['steps'] * self.dt\n",
+ " offset = self.gait_period/2\n",
+ " ref1 = jp.sin((2*jp.pi/self.gait_period)*t) # RF and LH feet\n",
+ " ref2 = jp.sin((2*jp.pi/self.gait_period)*(t - offset)) # LF and RH\n",
+ " \n",
+ " ref1, ref2 = ref1 * h_tar, ref2 * h_tar\n",
+ " h_tars = jp.array([ref2, ref1, ref1, ref2])\n",
+ " h_tars = h_tars.clip(min=0, max=None) + 0.02 # offset height of feet.\n",
+ " \n",
+ " feet_height = data.geom_xpos[self.feet_inds][:,2]\n",
+ " errs = jp.clip(jp.square(feet_height - h_tars), 0, 10)\n",
+ " return jp.sum(errs)\n",
+ " \n",
+ "envs.register_environment('anymal', FwdTrotAnymal)\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "#### Residual Learning via FoPG's\n",
+ "Takes 15 minutes on a NVIDIA 3060 TI GPU"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 30,
+ "metadata": {},
+ "outputs": [],
+ "source": [
+ "# Reconstruct the trotting inference function\n",
+ "make_networks_factory = functools.partial(\n",
+ " apg_networks.make_apg_networks,\n",
+ " hidden_layer_sizes=(256, 128)\n",
+ ")\n",
+ "\n",
+ "nets = make_networks_factory(observation_size=1, # Observation_size argument doesn't matter since it's only used for param init.\n",
+ " action_size=12,\n",
+ " preprocess_observations_fn=running_statistics.normalize)\n",
+ "\n",
+ "make_inference_fn = apg_networks.make_inference_fn(nets)\n",
+ "\n",
+ "# Configure locomotion training\n",
+ "make_networks_factory = functools.partial(\n",
+ " apg_networks.make_apg_networks,\n",
+ " hidden_layer_sizes=(128, 64)\n",
+ ")\n",
+ "\n",
+ "epochs = 499\n",
+ "\n",
+ "train_fn = functools.partial(apg.train,\n",
+ " episode_length=1000,\n",
+ " policy_updates=epochs,\n",
+ " horizon_length=32,\n",
+ " num_envs=64,\n",
+ " learning_rate=1.5e-4,\n",
+ " schedule_decay=0.995,\n",
+ " num_eval_envs=64,\n",
+ " num_evals=10 + 1,\n",
+ " use_float64=True,\n",
+ " normalize_observations=True,\n",
+ " network_factory=make_networks_factory)\n",
+ "\n",
+ "model_path = '/tmp/trotting_2hz_policy'\n",
+ "params = model.load_params(model_path)\n",
+ "baseline_inference_fn = make_inference_fn(params)\n",
+ "\n",
+ "env_kwargs = dict(target_vel=0.75, step_k=13, \n",
+ " baseline_inference_fn=baseline_inference_fn)"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 31,
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "text/plain": [
+ ""
+ ]
+ },
+ "execution_count": 31,
+ "metadata": {},
+ "output_type": "execute_result"
+ },
+ {
+ "data": {
+ "image/png": "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",
+ "text/plain": [
+ ""
+ ]
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "x_data = []\n",
+ "y_data = []\n",
+ "ydataerr = []\n",
+ "times = [datetime.now()]\n",
+ "\n",
+ "def progress(it, metrics):\n",
+ " times.append(datetime.now())\n",
+ " x_data.append(it)\n",
+ " y_data.append(metrics['eval/episode_reward'])\n",
+ " ydataerr.append(metrics['eval/episode_reward_std'])\n",
+ "\n",
+ "env = envs.get_environment(\"anymal\", **env_kwargs)\n",
+ "eval_env = envs.get_environment(\"anymal\", **env_kwargs)\n",
+ "\n",
+ "make_inference_fn, params, _= train_fn(environment=env,\n",
+ " progress_fn=progress,\n",
+ " eval_env=eval_env)\n",
+ "\n",
+ "plt.errorbar(x_data, y_data, yerr=ydataerr)"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 32,
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "text/html": [
+ "
"
+ ],
+ "text/plain": [
+ ""
+ ]
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "demo_env = envs.training.EpisodeWrapper(env, \n",
+ " episode_length=1000, \n",
+ " action_repeat=1)\n",
+ "\n",
+ "render_rollout(\n",
+ " jax.jit(demo_env.reset),\n",
+ " jax.jit(demo_env.step),\n",
+ " jax.jit(make_inference_fn(params)),\n",
+ " demo_env,\n",
+ " n_steps=200,\n",
+ " camera=\"track\"\n",
+ ")"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "**A note on sample efficiency**\n",
+ "\n",
+ "Let's compare with PPO, again using 1e7 samples:"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": 11,
+ "metadata": {},
+ "outputs": [
+ {
+ "data": {
+ "text/plain": [
+ "Text(0, 0.5, 'reward per episode')"
+ ]
+ },
+ "execution_count": 11,
+ "metadata": {},
+ "output_type": "execute_result"
+ },
+ {
+ "data": {
+ "image/png": "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",
+ "text/plain": [
+ ""
+ ]
+ },
+ "metadata": {},
+ "output_type": "display_data"
+ }
+ ],
+ "source": [
+ "train_fn = functools.partial(\n",
+ " ppo.train, num_timesteps=10_000_000, num_evals=10, reward_scaling=0.1,\n",
+ " episode_length=1000, normalize_observations=True, action_repeat=1,\n",
+ " unroll_length=10, num_minibatches=32, num_updates_per_batch=8,\n",
+ " discounting=0.97, learning_rate=3e-4, entropy_cost=1e-3, num_envs=1024,\n",
+ " batch_size=1024, seed=0)\n",
+ "\n",
+ "x_data = []\n",
+ "y_data = []\n",
+ "ydataerr = []\n",
+ "\n",
+ "env = envs.get_environment(\"anymal\", **env_kwargs)\n",
+ "\n",
+ "def progress(num_steps, metrics):\n",
+ " x_data.append(num_steps)\n",
+ " y_data.append(metrics['eval/episode_reward'])\n",
+ " ydataerr.append(metrics['eval/episode_reward_std'])\n",
+ "\n",
+ "make_inference_fn, params, _= train_fn(environment=env, progress_fn=progress)\n",
+ "\n",
+ "plt.errorbar(x_data, y_data, yerr=ydataerr)\n",
+ "plt.xlabel('# environment steps')\n",
+ "plt.ylabel('reward per episode')"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "metadata": {},
+ "source": [
+ "We see that PPO struggles to learn locomotion in this setup, even with over 10x the number of simulator steps. \n",
+ "\n",
+ "Rather than indicating a shortcoming of PPO, this study demonstrates a policy-learning setup that effectively leverages FoPG methods. It involves learning small, accurate perturbations from a good baseline - optimizing to the local minima in a deep valley. FoPG's are precise enough to guide these perturbations using nuanced reward signals, such as our foot placement spline.\n",
+ "\n",
+ "In contrast, RL algorithms such as PPO benefit from [policy-learning setups](https://colab.research.google.com/github/google-deepmind/mujoco/blob/main/mjx/tutorial.ipynb) that have less structured rewards. Unlike FoPG methods, they [benefit greatly](https://www.science.org/doi/abs/10.1126/scirobotics.adg1462) from sparse, non-differentiable rewards such as a large penalty for falling."
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "mujoco",
+ "language": "python",
+ "name": "python3"
+ },
+ "language_info": {
+ "codemirror_mode": {
+ "name": "ipython",
+ "version": 3
+ },
+ "file_extension": ".py",
+ "mimetype": "text/x-python",
+ "name": "python",
+ "nbconvert_exporter": "python",
+ "pygments_lexer": "ipython3",
+ "version": "3.10.13"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 2
+}