diff --git a/.claude/skills/compass/SKILL.md b/.claude/skills/compass/SKILL.md
new file mode 100644
index 0000000..a9cd42e
--- /dev/null
+++ b/.claude/skills/compass/SKILL.md
@@ -0,0 +1,394 @@
+---
+name: compass
+description: >
+ End-to-end COMPASS robot navigation pipeline orchestrator. Handles SAGE-10k scene
+ search/download, USD conversion, COMPASS training environment setup, scene registration,
+ residual RL training, and evaluation. Use this skill whenever the user mentions COMPASS,
+ SAGE, robot navigation training, USD scene generation, residual RL, embodiment training
+ (carter/h1/spot/g1/digit), IsaacLab training, or wants to generate 3D environments for
+ robot training. Also triggers for: "train on a new scene", "set up sage", "generate a
+ warehouse", "evaluate a checkpoint", "run compass", "search sage-10k", or any navigation
+ policy training task.
+allowed-tools:
+ - Bash
+ - Read
+ - Edit
+ - Write
+ - Grep
+ - Glob
+ - AskUserQuestion
+ - WebFetch
+ - Agent
+---
+
+You orchestrate the COMPASS robot navigation training pipeline — from scene search to trained policy. You're adaptive: interactive and explanatory during setup, autonomous and efficient for repeated operations like training runs.
+
+COMPASS trains cross-embodiment navigation policies using residual RL on top of X-Mobility (a pretrained VLA). SAGE-10k provides 10,000 pre-generated indoor scenes across 50 room types.
+
+## Skill Scripts
+
+This skill bundles two helper scripts in its own directory:
+- `scripts/sage10k_search.py` — search SAGE-10k dataset by text query
+- `scripts/sage10k_to_usd.py` — convert SAGE-10k scenes to USD (uses only Isaac Sim native APIs, no extra deps)
+
+The scripts are located relative to this skill's base directory. Use the full path when invoking them:
+```
+/scripts/sage10k_search.py
+/scripts/sage10k_to_usd.py
+```
+
+## Workflow Routing
+
+| Workflow | Trigger |
+|----------|---------|
+| **Search SAGE-10k** | User wants a scene from the SAGE-10k dataset (default for new scenes) |
+| **Setup COMPASS** | User wants to install COMPASS deps, or deps are missing when needed |
+| **Setup SAGE** | User wants full local SAGE installation for custom generation (rare) |
+| **Register Scene** | User has a USD file to add to COMPASS (auto-triggered after conversion) |
+| **Train** | User wants to run residual RL training on a scene |
+| **Evaluate** | User wants to evaluate a trained checkpoint |
+| **Full Pipeline** | User gives a scene description — chain: search SAGE-10k → download → convert USD → verify in viewer → register → preview train (num_envs=1, GUI) → full train |
+
+If the user gives a scene description like "a cluttered warehouse" or "bedroom", treat it as **Full Pipeline** using SAGE-10k search. Only use local SAGE if explicitly requested.
+
+**IMPORTANT**: Before Train, Evaluate, or Full Pipeline, ALWAYS run the Prerequisites Check first. If anything is missing, auto-route to the relevant Setup step. Never assume the environment is ready.
+
+---
+
+## Prerequisites Check
+
+Run this before ANY operation. Use `dangerouslyDisableSandbox: true` for GPU commands. Run all checks in parallel where possible. Report what's ready and what's missing.
+
+```bash
+# Step 1: GPU (MUST use dangerouslyDisableSandbox: true)
+nvidia-smi --query-gpu=name,memory.total,memory.used --format=csv,noheader
+
+# Step 2-3: Conda env + Isaac Lab
+conda env list 2>/dev/null | grep -i isaac
+echo "ISAACLAB_PATH=$ISAACLAB_PATH"
+test -f "$ISAACLAB_PATH/isaaclab.sh" && echo "isaaclab.sh: OK" || echo "isaaclab.sh: MISSING"
+
+# Step 4: Base policy
+for p in ./model.ckpt ./x_mobility_ckpt/model.ckpt ~/afm_base_policy.ckpt; do
+ test -f "$p" && echo "Found base policy: $p"
+done
+
+# Step 5: USD assets
+ls compass/rl_env/exts/mobility_es/mobility_es/usd/ 2>/dev/null
+```
+
+Report summary, then proceed or guide setup for missing pieces.
+
+---
+
+## Execution Environment Rules
+
+These rules apply to ALL commands. Violating them causes failures.
+
+1. **Conda env wrapper**: ALL `isaaclab.sh` and Isaac Sim Python commands MUST use:
+ ```bash
+ conda run -n ${ISAACLAB_PATH}/isaaclab.sh -p ...
+ ```
+ Or for plain Python with Isaac Sim imports:
+ ```bash
+ conda run -n python ...
+ ```
+
+2. **GPU access**: ALL GPU commands MUST use `dangerouslyDisableSandbox: true`. The Claude Code sandbox blocks NVIDIA driver access — without this flag, `nvidia-smi` fails and Isaac Sim cannot find CUDA.
+
+3. **Background execution**: Training and evaluation are long-running. Use `run_in_background: true` so the user isn't blocked. Note: `conda run` buffers stdout — check progress via log files instead:
+ ```bash
+ # Find latest log
+ ls -t /tmp/isaaclab/logs/ | head -1
+ # Or check the Kit log for errors
+ find /home/*/miniconda3/envs/*/lib/python*/site-packages/isaacsim/kit/logs/Kit -name "kit_*.log" -newer /tmp/isaaclab/logs/ 2>/dev/null
+ ```
+
+4. **Killing processes**: When killing training, use `kill -9` on the Python process directly — the `conda run` wrapper may leave orphan processes:
+ ```bash
+ ps aux | grep "run.py.*" | grep -v grep | awk '{print $2}' | xargs kill -9
+ ```
+
+---
+
+## Setup COMPASS
+
+Skip steps already detected in Prerequisites Check.
+
+### Step 1: Install Isaac Lab 3.0.0-beta1
+```bash
+git clone https://github.com/isaac-sim/IsaacLab.git --branch v3.0.0-beta1
+cd IsaacLab && ./isaaclab.sh --install
+export ISAACLAB_PATH=/path/to/IsaacLab
+```
+
+### Step 2: Install COMPASS dependencies
+```bash
+conda run -n ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -r requirements.txt
+conda run -n ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install x_mobility/x_mobility-0.1.0-py3-none-any.whl
+conda run -n ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -e compass/rl_env/exts/mobility_es/
+```
+
+### Step 3: Download base policy
+Ask user for existing checkpoint path, or download:
+```bash
+conda run -n huggingface-cli login --token
+conda run -n huggingface-cli download nvidia/X-Mobility --local-dir ./x_mobility_ckpt
+```
+
+### Step 4: Download USD assets
+Download `compass_usds.zip` from HuggingFace `nvidia/COMPASS`, extract to `compass/rl_env/exts/mobility_es/mobility_es/usd/`.
+
+---
+
+## Search SAGE-10k (Recommended for new scenes)
+
+The SAGE-10k dataset (`nvidia/SAGE-10k`) has 10,000 pre-generated indoor scenes across 50 room types. No SAGE installation needed.
+
+### Step 1: Search for matching scenes
+```bash
+conda run -n python /scripts/sage10k_search.py "" --top 5 --sample-size 50
+```
+First run builds a scene index from the HF API (cached afterward). Results show room type, style, object count, and description.
+
+### Step 2: Present options to user
+Show top results. Let user pick one.
+
+### Step 3: Download the selected scene
+```bash
+# Download specific scene zip
+huggingface-cli download nvidia/SAGE-10k --repo-type dataset \
+ --include "scenes/" --local-dir ./sage_10k_cache
+
+# Extract
+mkdir -p ./sage_10k_scenes/
+unzip ./sage_10k_cache/scenes/ -d ./sage_10k_scenes//
+```
+
+### Step 4: Convert to USD
+Use the bundled converter (only needs Isaac Sim native APIs — no extra deps):
+```bash
+# MUST use dangerouslyDisableSandbox: true
+conda run -n python /scripts/sage10k_to_usd.py \
+ ./sage_10k_scenes// \
+ ./compass/rl_env/exts/mobility_es/mobility_es/usd//.usd
+```
+This script:
+- Initializes Isaac Sim headless for `pxr` access
+- Parses PLY meshes with proper binary format (separate vertex/texcoord elements)
+- Scales objects to match layout dimensions
+- Creates walls and floors from room geometry
+- Applies textures with UV mapping
+- Sets all objects as static collision (appropriate for navigation training)
+
+### Step 5: Verify USD in Isaac Sim viewer
+**ALWAYS** launch the Isaac Sim viewer after conversion so the user can visually verify the scene looks correct (geometry, collisions, textures) before proceeding. Use `dangerouslyDisableSandbox: true` and `run_in_background: true`:
+```bash
+conda run -n python -c "
+from isaacsim import SimulationApp
+app = SimulationApp({'headless': False, 'width': 1280, 'height': 720})
+import omni
+omni.usd.get_context().open_stage('./compass/rl_env/exts/mobility_es/mobility_es/usd//.usd')
+while app.is_running():
+ app.update()
+app.close()
+" &
+```
+Tell the user the viewer is open and to close it when they're done inspecting. Ask if the scene looks good before proceeding. Enable collision visualization via **Show > Physics > Colliders**.
+
+### Step 6: Register and train
+Proceed to **Register Scene** → **Train**.
+
+---
+
+## Register Scene
+
+Edit two files. Read each file first to find insertion points.
+
+### File 1: `compass/rl_env/exts/mobility_es/mobility_es/config/environments.py`
+
+**Add to `USD_PATHS` dict:**
+```python
+'':
+ os.path.join(os.path.dirname(__file__), "../usd//.usd"),
+```
+
+**Add scene config at end of file:**
+```python
+ = EnvSceneAssetCfg(
+ prim_path="{ENV_REGEX_NS}/",
+ init_state=AssetBaseCfg.InitialStateCfg(
+ pos=(0, 0, 0.01),
+ rot=(1.0, 0.0, 0.0, 0.0),
+ ),
+ spawn=sim_utils.UsdFileCfg(
+ usd_path=USD_PATHS[''],
+ scale=(1.0, 1.0, 1.0),
+ rigid_props=sim_utils.RigidBodyPropertiesCfg(
+ disable_gravity=None,
+ solver_position_iteration_count=4,
+ solver_velocity_iteration_count=1,
+ ),
+ ),
+ pose_sample_range={"x": (-3, 3), "y": (-3, 3), "yaw": (-3.14, 3.14)},
+ env_spacing=20,
+)
+```
+For SAGE-10k rooms (typically 4-6m), use `pose_sample_range` ±3m and `env_spacing` 20. For larger scenes, increase both.
+
+### File 2: `run.py`
+
+**Add to `EnvSceneAssetCfgMap` (around line 118-128):**
+```python
+'': environments.,
+```
+
+---
+
+## Train
+
+**Remember**: `conda run`, `dangerouslyDisableSandbox: true`.
+
+### Step 1: Preview training (ALWAYS do this first)
+**ALWAYS** start with a preview run: `--num_envs 1` WITHOUT `--headless`, so the user can verify the robot spawns correctly in the scene and the environment looks right. Use `run_in_background: true`:
+```bash
+conda run -n ${ISAACLAB_PATH}/isaaclab.sh -p run.py \
+ -c configs/train_config.gin \
+ --enable_cameras \
+ -o _preview \
+ -b \
+ --logger tensorboard \
+ --video \
+ --embodiment \
+ --environment \
+ --num_envs 1
+```
+Tell the user the preview is running with the GUI open. Ask them to verify:
+1. The robot spawns in a valid location (not clipping through objects)
+2. The scene geometry and collisions look correct
+3. The robot can navigate without issues
+
+Once the user confirms the preview looks good, kill the preview process and proceed to full-scale training.
+
+### Step 2: Full-scale training
+After user confirms the preview, launch the full training run with `run_in_background: true`:
+```bash
+conda run -n ${ISAACLAB_PATH}/isaaclab.sh -p run.py \
+ -c configs/train_config.gin \
+ --enable_cameras \
+ -o \
+ -b \
+ -n \
+ -r \
+ --logger tensorboard \
+ --headless \
+ --video \
+ --embodiment \
+ --environment \
+ --num_envs
+```
+
+Remove `--headless` if the user wants GUI mode. For GUI mode with SAGE-10k scenes (many meshes), use `--num_envs 1` to avoid OOM.
+
+### OSMO cluster submission
+
+The Python launcher in [osmo/run_osmo.py](../../../osmo/run_osmo.py) handles build+push+submit and is the recommended entry point:
+```bash
+export WANDB_API_KEY=
+export HF_TOKEN=
+export COMPASS_OSMO_REGISTRY=nvcr.io//
+
+python osmo/run_osmo.py train \
+ --experiment-name \
+ --wandb-project \
+ --base-policy-ckpt
+```
+
+For direct `osmo workflow submit` invocation (advanced), see the [OSMO cloud submission](https://nvlabs.github.io/COMPASS/docs/osmo.html) handbook page. Workflow YAMLs live in [osmo/workflows/](../../../osmo/workflows/).
+
+### Defaults
+| Parameter | Default | Source |
+|-----------|---------|--------|
+| num_iterations | 1000 | train_config.gin |
+| num_envs | 64 | train_config.gin |
+| num_steps_per_iteration | 256 | shared.gin |
+| seed | 20 | train_config.gin |
+| embodiment | g1 | shared.gin |
+
+### Valid embodiments
+`carter`, `h1`, `spot`, `g1`, `digit`
+
+### Built-in environments
+`warehouse_single_rack`, `galileo_lab`, `simple_office`, `combined_single_rack`, `combined_multi_rack`, `random_envs`, `hospital`, `warehouse_multi_rack`
+
+### Outputs
+- Checkpoints: `/model_*.pt`
+- Videos: `/videos/`
+- Logs: TensorBoard in `/` or W&B
+
+---
+
+## Evaluate
+
+```bash
+CKPT=$(ls /model_*.pt | sort -V | tail -n 1)
+
+conda run -n ${ISAACLAB_PATH}/isaaclab.sh -p run.py \
+ -c configs/eval_config.gin \
+ --enable_cameras \
+ -o \
+ -b \
+ -p $CKPT \
+ -n \
+ -r eval_ \
+ --logger tensorboard \
+ --headless \
+ --video \
+ --video_interval 1 \
+ --embodiment \
+ --environment
+```
+
+---
+
+## Visualize Scene in Isaac Sim
+
+To inspect a USD scene before training (check collision meshes, layout, etc.):
+```bash
+conda run -n python -c "
+from isaacsim import SimulationApp
+app = SimulationApp({'headless': False, 'width': 1280, 'height': 720})
+import omni
+omni.usd.get_context().open_stage('')
+while app.is_running():
+ app.update()
+app.close()
+" &
+```
+Use `dangerouslyDisableSandbox: true`. Enable collision visualization: **Show > Physics > Colliders**.
+
+---
+
+## Setup SAGE (Local — Advanced)
+
+Only needed for fully custom scene generation. SAGE has heavy deps (pytorch3d, TRELLIS, VLM servers) and requires a multi-GPU machine. SAGE-10k search is strongly preferred.
+
+See the SAGE repo README for full setup: https://github.com/NVlabs/sage
+
+---
+
+## Key File Locations
+
+| File | Purpose |
+|------|---------|
+| `run.py` | Main entry point + `EnvSceneAssetCfgMap` (lines 118-128) |
+| `compass/rl_env/exts/mobility_es/mobility_es/config/environments.py` | Scene definitions, `USD_PATHS`, `EnvSceneAssetCfg` class |
+| `compass/rl_env/exts/mobility_es/mobility_es/usd/` | USD asset directories |
+| `configs/train_config.gin` | Training parameters |
+| `configs/eval_config.gin` | Evaluation parameters |
+| `configs/shared.gin` | Shared config (embodiment, environment, steps) |
+| `osmo/workflows/rl_es_train_workflow.yaml` | OSMO training workflow template |
+| `osmo/run_osmo.py` | Python launcher for OSMO submission (train / eval / record / distill) |
+
+## W&B Artifact Format
+`//:` — e.g. `//x_mobility:v1`
diff --git a/.claude/skills/compass/scripts/sage10k_search.py b/.claude/skills/compass/scripts/sage10k_search.py
new file mode 100755
index 0000000..86d24e5
--- /dev/null
+++ b/.claude/skills/compass/scripts/sage10k_search.py
@@ -0,0 +1,297 @@
+#!/usr/bin/env python3
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+"""Search SAGE-10k dataset for scenes matching a text query.
+
+Uses the HuggingFace API to list scenes, downloads layout JSONs on demand,
+and caches them locally for fast repeated searches.
+
+Usage:
+ python scripts/sage10k_search.py "bedroom with desk"
+ python scripts/sage10k_search.py "warehouse" --top 10
+ python scripts/sage10k_search.py --list-room-types
+ python scripts/sage10k_search.py "kitchen" --download --output-dir ./sage_scenes
+"""
+
+import argparse
+import json
+import os
+import random
+import re
+import sys
+import zipfile
+
+from huggingface_hub import HfApi, hf_hub_download
+
+DATASET_ID = "nvidia/SAGE-10k"
+DEFAULT_CACHE_DIR = os.path.join(os.path.dirname(__file__), "..", "sage_10k_cache")
+
+
+def get_api():
+ return HfApi()
+
+
+def list_scene_files(api, cache_dir):
+ """List all scene zip files in the dataset, with caching."""
+ index_path = os.path.join(cache_dir, "scene_index.json")
+ if os.path.exists(index_path):
+ with open(index_path) as f:
+ return json.load(f)
+
+ print("Building scene index from HuggingFace API (first time only)...", file=sys.stderr)
+ files = []
+ for item in api.list_repo_tree(DATASET_ID, path_in_repo="scenes", repo_type="dataset"):
+ name = getattr(item, "rfilename", None) or getattr(item, "path", "")
+ if name.endswith(".zip"):
+ files.append(name)
+
+ os.makedirs(cache_dir, exist_ok=True)
+ with open(index_path, "w") as f:
+ json.dump(files, f)
+ print(f"Indexed {len(files)} scenes.", file=sys.stderr)
+ return files
+
+
+def extract_layout_id(zip_filename):
+ """Extract layout ID from zip filename like '20251213_020526_layout_84b703fb.zip'."""
+ match = re.search(r"layout_([a-f0-9]+)", zip_filename)
+ return match.group(1) if match else os.path.splitext(os.path.basename(zip_filename))[0]
+
+
+def download_layout_json(_api, zip_path, cache_dir):
+ """Download a scene zip and extract its layout JSON."""
+ layout_id = extract_layout_id(zip_path)
+ json_cache = os.path.join(cache_dir, "layouts", f"{layout_id}.json")
+
+ if os.path.exists(json_cache):
+ with open(json_cache) as f:
+ return json.load(f)
+
+ local_zip = hf_hub_download(
+ repo_id=DATASET_ID,
+ filename=zip_path,
+ repo_type="dataset",
+ local_dir=os.path.join(cache_dir, "zips"),
+ )
+
+ os.makedirs(os.path.join(cache_dir, "layouts"), exist_ok=True)
+ with zipfile.ZipFile(local_zip) as zf:
+ json_files = [n for n in zf.namelist() if n.endswith(".json") and "layout" in n.lower()]
+ if not json_files:
+ json_files = [n for n in zf.namelist() if n.endswith(".json")]
+ if json_files:
+ data = json.loads(zf.read(json_files[0]))
+ with open(json_cache, "w") as f:
+ json.dump(data, f)
+ return data
+ return None
+
+
+def extract_scene_metadata(layout_data):
+ """Extract searchable metadata from a layout JSON."""
+ meta = {
+ "id": layout_data.get("id", "unknown"),
+ "description": layout_data.get("description", ""),
+ "building_style": layout_data.get("building_style", ""),
+ "room_types": [],
+ "object_count": 0,
+ "rooms": [],
+ }
+ for room in layout_data.get("rooms", []):
+ room_type = room.get("room_type", "unknown")
+ objects = room.get("objects", [])
+ meta["room_types"].append(room_type)
+ meta["object_count"] += len(objects)
+ meta["rooms"].append({
+ "room_type": room_type,
+ "object_count": len(objects),
+ })
+ return meta
+
+
+def score_match(query, meta):
+ """Score how well a scene matches the query. Higher = better match."""
+ query_lower = query.lower()
+ query_words = set(query_lower.split())
+ score = 0
+
+ for rt in meta["room_types"]:
+ rt_lower = rt.lower()
+ if query_lower in rt_lower or rt_lower in query_lower:
+ score += 10
+ for word in query_words:
+ if word in rt_lower:
+ score += 5
+
+ desc_lower = meta["description"].lower()
+ for word in query_words:
+ if word in desc_lower:
+ score += 3
+
+ style_lower = meta["building_style"].lower()
+ for word in query_words:
+ if word in style_lower:
+ score += 2
+
+ return score
+
+
+def search_scenes(query, scene_files, api, cache_dir, top_n=5, sample_size=100):
+ """Search scenes by downloading and checking layout JSONs.
+
+ To avoid downloading all 10K scenes, we first filter by filename patterns,
+ then sample and download layout JSONs for detailed matching.
+ """
+ query_lower = query.lower()
+
+ # Phase 1: Score by filename (free, no downloads)
+ filename_scored = []
+ for f in scene_files:
+ fname_lower = os.path.basename(f).lower()
+ fscore = 0
+ for word in query_lower.split():
+ if word in fname_lower:
+ fscore += 5
+ filename_scored.append((f, fscore))
+
+ # Phase 2: Download layout JSONs for a sample of scenes
+ # Prioritize filename matches, then take random sample
+ filename_scored.sort(key=lambda x: -x[1])
+ candidates = [f for f, s in filename_scored[:sample_size]]
+
+ results = []
+ for i, zip_path in enumerate(candidates):
+ print(f"\rSearching... ({i+1}/{len(candidates)})", end="", file=sys.stderr)
+ try:
+ layout = download_layout_json(api, zip_path, cache_dir)
+ if layout is None:
+ continue
+ meta = extract_scene_metadata(layout)
+ meta["zip_path"] = zip_path
+ score = score_match(query, meta)
+ if score > 0:
+ results.append((score, meta))
+ except Exception as e: # pylint: disable=broad-exception-caught
+ print(f"\nWarning: failed to process {zip_path}: {e}", file=sys.stderr)
+ continue
+
+ print("", file=sys.stderr)
+ results.sort(key=lambda x: -x[0])
+ return results[:top_n]
+
+
+def list_room_types(scene_files, api, cache_dir, sample_size=50):
+ """Sample scenes to discover available room types."""
+ room_types = set()
+ sample = random.sample(scene_files, min(sample_size, len(scene_files)))
+ for i, zip_path in enumerate(sample):
+ print(f"\rSampling room types... ({i+1}/{len(sample)})", end="", file=sys.stderr)
+ try:
+ layout = download_layout_json(api, zip_path, cache_dir)
+ if layout:
+ meta = extract_scene_metadata(layout)
+ room_types.update(meta["room_types"])
+ except Exception: # pylint: disable=broad-exception-caught
+ continue
+ print("", file=sys.stderr)
+ return sorted(room_types)
+
+
+def download_scene(_api, zip_path, output_dir, cache_dir):
+ """Download and extract a full scene."""
+ local_zip = hf_hub_download(
+ repo_id=DATASET_ID,
+ filename=zip_path,
+ repo_type="dataset",
+ local_dir=os.path.join(cache_dir, "zips"),
+ )
+
+ layout_id = extract_layout_id(zip_path)
+ scene_dir = os.path.join(output_dir, layout_id)
+ os.makedirs(scene_dir, exist_ok=True)
+
+ with zipfile.ZipFile(local_zip) as zf:
+ zf.extractall(scene_dir)
+
+ print(f"Scene extracted to: {scene_dir}")
+ return scene_dir
+
+
+def main():
+ parser = argparse.ArgumentParser(description="Search SAGE-10k scenes")
+ parser.add_argument("query", nargs="?", help="Search query (e.g. 'bedroom with desk')")
+ parser.add_argument("--top", type=int, default=5, help="Number of results")
+ parser.add_argument("--sample-size",
+ type=int,
+ default=100,
+ help="Number of scenes to sample for search")
+ parser.add_argument("--cache-dir", default=DEFAULT_CACHE_DIR, help="Cache directory")
+ parser.add_argument("--list-room-types", action="store_true", help="List discovered room types")
+ parser.add_argument("--download", action="store_true", help="Download the top result")
+ parser.add_argument("--output-dir",
+ default="./sage_10k_scenes",
+ help="Output directory for downloads")
+ parser.add_argument("--json", action="store_true", help="Output as JSON")
+ args = parser.parse_args()
+
+ api = get_api()
+ scene_files = list_scene_files(api, args.cache_dir)
+
+ if args.list_room_types:
+ types = list_room_types(scene_files, api, args.cache_dir)
+ print("Discovered room types:")
+ for t in types:
+ print(f" - {t}")
+ return
+
+ if not args.query:
+ parser.error("Please provide a search query or use --list-room-types")
+
+ results = search_scenes(args.query,
+ scene_files,
+ api,
+ args.cache_dir,
+ top_n=args.top,
+ sample_size=args.sample_size)
+
+ if not results:
+ print("No matching scenes found. Try a broader query or increase --sample-size.")
+ return
+
+ if args.json:
+ print(json.dumps([{"score": s, **m} for s, m in results], indent=2))
+ else:
+ print(f"\nTop {len(results)} matches for '{args.query}':\n")
+ for i, (_, meta) in enumerate(results, 1):
+ room_types = ", ".join(meta["room_types"]) or "unknown"
+ print(f" {i}. {meta['id']}")
+ print(f" Room types: {room_types}")
+ print(f" Style: {meta['building_style'] or 'N/A'}")
+ print(f" Objects: {meta['object_count']}")
+ print(f" Description: {meta['description'][:100]}..."
+ if len(meta.get('description', '')) > 100 else
+ f" Description: {meta['description'] or 'N/A'}")
+ print(f" File: {meta['zip_path']}")
+ print()
+
+ if args.download and results:
+ _, top_meta = results[0]
+ print(f"Downloading top result: {top_meta['id']}...")
+ scene_dir = download_scene(api, top_meta["zip_path"], args.output_dir, args.cache_dir)
+ print(f"Done. Scene at: {scene_dir}")
+
+
+if __name__ == "__main__":
+ main()
diff --git a/.claude/skills/compass/scripts/sage10k_to_usd.py b/.claude/skills/compass/scripts/sage10k_to_usd.py
new file mode 100755
index 0000000..e15d490
--- /dev/null
+++ b/.claude/skills/compass/scripts/sage10k_to_usd.py
@@ -0,0 +1,359 @@
+#!/usr/bin/env python3
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+"""Convert a SAGE-10k scene to a single USD file for COMPASS training.
+
+Uses only Isaac Sim native APIs (pxr) and numpy — no extra dependencies.
+Reads the layout JSON + PLY objects and creates a simulation-ready USD scene.
+
+Usage:
+ # Must run inside Isaac Sim environment
+ conda run -n env_isaaclab python scripts/sage10k_to_usd.py \
+
+
+Example:
+ conda run -n env_isaaclab python scripts/sage10k_to_usd.py \
+ ./sage_10k_scenes/teen_bedroom/layout_ed24dd11.json \
+ ./compass/rl_env/exts/mobility_es/mobility_es/usd/teen_bedroom/teen_bedroom.usd
+"""
+
+import argparse
+import json
+import math
+import os
+import struct
+
+import numpy as np
+
+# Initialize Isaac Sim before importing pxr
+from isaacsim import SimulationApp
+
+_app = SimulationApp({"headless": True})
+
+
+def parse_ply(ply_path):
+ """Parse a SAGE-10k PLY file.
+
+ These PLYs have separate vertex and texcoord elements, and faces with
+ both vertex_indices and texcoord_indices lists.
+
+ Returns: (verts, faces, uvs, face_uvs)
+ verts: (N, 3) float32 vertex positions
+ faces: (F, 3) int32 vertex indices per face
+ uvs: (M, 2) float32 texture coordinates (separate element)
+ face_uvs: (F, 3) int32 texcoord indices per face, or None
+ """
+ with open(ply_path, "rb") as f:
+ # Parse header
+ header_lines = []
+ while True:
+ line = f.readline().decode("ascii").strip()
+ header_lines.append(line)
+ if line == "end_header":
+ break
+
+ n_verts = 0
+ n_texcoords = 0
+ n_faces = 0
+ is_binary = any("binary_little_endian" in l for l in header_lines)
+
+ for line in header_lines:
+ parts = line.split()
+ if len(parts) >= 3 and parts[0] == "element":
+ if parts[1] == "vertex":
+ n_verts = int(parts[2])
+ elif parts[1] == "texcoord":
+ n_texcoords = int(parts[2])
+ elif parts[1] == "face":
+ n_faces = int(parts[2])
+
+ # Count face property lists to know how many index lists per face
+ face_list_count = sum(1 for l in header_lines
+ if l.startswith("property list") and header_lines.index(l) > next(
+ i for i, x in enumerate(header_lines) if "element face" in x))
+
+ if is_binary:
+ # Read vertices (x, y, z as float32)
+ verts = np.frombuffer(f.read(n_verts * 12), dtype=np.float32).reshape(n_verts, 3).copy()
+
+ # Read texcoords (s, t as float32)
+ uvs = None
+ if n_texcoords > 0:
+ uvs = np.frombuffer(f.read(n_texcoords * 8),
+ dtype=np.float32).reshape(n_texcoords, 2).copy()
+
+ # Read faces
+ faces = []
+ face_uvs = []
+ for i in range(n_faces):
+ # First list: vertex_indices
+ n = struct.unpack("= 2:
+ n2 = struct.unpack("= 4:
+ # Triangulate quads
+ faces.append((vi[0], vi[1], vi[2]))
+ faces.append((vi[0], vi[2], vi[3]))
+ if ti and len(ti) >= 4:
+ face_uvs.append((ti[0], ti[1], ti[2]))
+ face_uvs.append((ti[0], ti[2], ti[3]))
+
+ faces = np.array(faces, dtype=np.int32)
+ face_uvs = np.array(face_uvs, dtype=np.int32) if face_uvs else None
+ else:
+ raise NotImplementedError("Only binary PLY supported")
+
+ return verts, faces, uvs, face_uvs
+
+
+def load_layout(json_path):
+ """Load and parse a SAGE-10k layout JSON."""
+ with open(json_path) as f:
+ return json.load(f)
+
+
+def create_usd_scene(layout_data, layout_dir, output_usd_path):
+ """Create a USD scene from SAGE layout data using pxr APIs."""
+ from pxr import Gf, Usd, UsdGeom, Vt, UsdPhysics, PhysxSchema, Sdf, UsdShade # pylint: disable=import-outside-toplevel
+
+ os.makedirs(os.path.dirname(output_usd_path), exist_ok=True)
+
+ stage = Usd.Stage.CreateNew(output_usd_path)
+ UsdGeom.SetStageUpAxis(stage, UsdGeom.Tokens.z)
+ UsdGeom.SetStageMetersPerUnit(stage, 1.0)
+
+ world = UsdGeom.Xform.Define(stage, "/World")
+ stage.SetDefaultPrim(world.GetPrim())
+
+ # NOTE: No GroundPlane or PhysicsScene here — COMPASS provides its own
+ # terrain plane and physics scene. Adding them causes duplicate collision
+ # surfaces that trigger illegal_contact termination on wheeled robots.
+
+ obj_count = 0
+ objects_dir = os.path.join(layout_dir, "objects")
+
+ for room in layout_data.get("rooms", []):
+ room_id = room.get("id", "room")
+ room_path = f"/World/Room_{room_id[:8]}"
+ UsdGeom.Xform.Define(stage, room_path)
+
+ # Process walls
+ for wall in room.get("walls", []):
+ wall_id = wall.get("id", "wall")[:8]
+ sp = wall.get("start_point", {})
+ ep = wall.get("end_point", {})
+ h = wall.get("height", 2.7)
+ t = wall.get("thickness", 0.1)
+
+ sx, sy = sp.get("x", 0), sp.get("y", 0)
+ ex, ey = ep.get("x", 0), ep.get("y", 0)
+
+ dx, dy = ex - sx, ey - sy
+ length = math.sqrt(dx * dx + dy * dy)
+ if length < 0.01:
+ continue
+
+ # Create wall as a box mesh
+ nx, ny = -dy / length, dx / length
+ hw = t / 2
+ pts = [
+ Gf.Vec3f(sx - nx * hw, sy - ny * hw, 0),
+ Gf.Vec3f(ex - nx * hw, ey - ny * hw, 0),
+ Gf.Vec3f(ex + nx * hw, ey + ny * hw, 0),
+ Gf.Vec3f(sx + nx * hw, sy + ny * hw, 0),
+ Gf.Vec3f(sx - nx * hw, sy - ny * hw, h),
+ Gf.Vec3f(ex - nx * hw, ey - ny * hw, h),
+ Gf.Vec3f(ex + nx * hw, ey + ny * hw, h),
+ Gf.Vec3f(sx + nx * hw, sy + ny * hw, h),
+ ]
+ faces_idx = [0, 1, 2, 3, 4, 7, 6, 5, 0, 4, 5, 1, 2, 6, 7, 3, 0, 3, 7, 4, 1, 5, 6, 2]
+ face_counts = [4, 4, 4, 4, 4, 4]
+
+ wall_mesh = UsdGeom.Mesh.Define(stage, f"{room_path}/wall_{wall_id}")
+ wall_mesh.CreatePointsAttr(Vt.Vec3fArray(pts))
+ wall_mesh.CreateFaceVertexCountsAttr(Vt.IntArray(face_counts))
+ wall_mesh.CreateFaceVertexIndicesAttr(Vt.IntArray(faces_idx))
+ wall_prim = wall_mesh.GetPrim()
+ UsdPhysics.CollisionAPI.Apply(wall_prim)
+ PhysxSchema.PhysxCollisionAPI.Apply(wall_prim)
+
+ # Process floor
+ dims = room.get("dimensions", {})
+ rw = dims.get("width", 5)
+ rl = dims.get("length", 5)
+ rpos = room.get("position", {})
+ rx, ry = rpos.get("x", 0), rpos.get("y", 0)
+
+ floor_mesh = UsdGeom.Mesh.Define(stage, f"{room_path}/floor")
+ floor_mesh.CreatePointsAttr(
+ Vt.Vec3fArray([
+ Gf.Vec3f(rx - rw / 2, ry - rl / 2, 0.001),
+ Gf.Vec3f(rx + rw / 2, ry - rl / 2, 0.001),
+ Gf.Vec3f(rx + rw / 2, ry + rl / 2, 0.001),
+ Gf.Vec3f(rx - rw / 2, ry + rl / 2, 0.001),
+ ]))
+ floor_mesh.CreateFaceVertexCountsAttr(Vt.IntArray([4]))
+ floor_mesh.CreateFaceVertexIndicesAttr(Vt.IntArray([0, 1, 2, 3]))
+ # NOTE: No collision on floor — robot drives on COMPASS terrain plane.
+ # Adding floor collision causes duplicate ground surfaces and resets.
+
+ # Process objects from PLY files
+ for obj in room.get("objects", []):
+ obj_id = obj.get("source_id", obj.get("id", ""))[:8]
+ if not obj_id:
+ continue
+
+ ply_path = os.path.join(objects_dir, f"{obj_id}.ply")
+ if not os.path.exists(ply_path):
+ continue
+
+ try:
+ verts, faces, uvs, face_uvs = parse_ply(ply_path)
+ except Exception as e: # pylint: disable=broad-exception-caught
+ print(f"Warning: failed to parse {ply_path}: {e}")
+ continue
+
+ # Scale PLY vertices to match the object's target dimensions
+ obj_dims = obj.get("dimensions", {})
+ tw = obj_dims.get("width", 1.0)
+ tl = obj_dims.get("length", 1.0)
+ th = obj_dims.get("height", 1.0)
+
+ # Compute current bounding box of PLY mesh
+ bbox_min = verts.min(axis=0)
+ bbox_max = verts.max(axis=0)
+ bbox_size = bbox_max - bbox_min
+ bbox_size = np.maximum(bbox_size, 1e-6) # avoid div by zero
+
+ # Center the mesh at origin, then scale to target dimensions
+ center = (bbox_min + bbox_max) / 2
+ verts = verts - center
+ scale = np.array([tw / bbox_size[0], tl / bbox_size[1], th / bbox_size[2]],
+ dtype=np.float32)
+ verts = verts * scale
+
+ # Shift so bottom of mesh is at z=0
+ verts[:, 2] -= verts[:, 2].min()
+
+ pos = obj.get("position", {})
+ rot = obj.get("rotation", {})
+ ox = pos.get("x", 0)
+ oy = pos.get("y", 0)
+ oz = pos.get("z", 0)
+ rx_deg = rot.get("x", 0)
+ ry_deg = rot.get("y", 0)
+ rz_deg = rot.get("z", 0)
+
+ obj_path = f"{room_path}/obj_{obj_id}_{obj_count}"
+ obj_count += 1
+
+ obj_mesh = UsdGeom.Mesh.Define(stage, obj_path)
+ obj_mesh.CreatePointsAttr(Vt.Vec3fArray.FromNumpy(verts))
+ face_counts = np.full(len(faces), 3, dtype=np.int32)
+ obj_mesh.CreateFaceVertexCountsAttr(Vt.IntArray.FromNumpy(face_counts))
+ obj_mesh.CreateFaceVertexIndicesAttr(Vt.IntArray.FromNumpy(faces.flatten()))
+
+ # Apply transform
+ xformable = UsdGeom.Xformable(obj_mesh.GetPrim())
+ xformable.AddTranslateOp().Set(Gf.Vec3d(ox, oy, oz))
+ if rx_deg != 0:
+ xformable.AddRotateXOp().Set(float(rx_deg))
+ if ry_deg != 0:
+ xformable.AddRotateYOp().Set(float(ry_deg))
+ if rz_deg != 0:
+ xformable.AddRotateZOp().Set(float(rz_deg))
+
+ # Apply texture if available
+ tex_path = os.path.join(objects_dir, f"{obj_id}_texture.png")
+ if os.path.exists(tex_path) and uvs is not None:
+ try:
+ # Use face_uvs indices if available, otherwise fall back to vertex indices
+ if face_uvs is not None and len(face_uvs) == len(faces):
+ uv_indices = np.clip(face_uvs.flatten(), 0, len(uvs) - 1)
+ else:
+ uv_indices = np.clip(faces.flatten(), 0, len(uvs) - 1)
+ tex_coords_arr = uvs[uv_indices].reshape(-1, 2)
+
+ mat_path = f"{obj_path}_mat"
+ material = UsdShade.Material.Define(stage, mat_path)
+ shader = UsdShade.Shader.Define(stage, f"{mat_path}/PBRShader")
+ shader.CreateIdAttr("UsdPreviewSurface")
+ shader.CreateInput("roughness", Sdf.ValueTypeNames.Float).Set(0.8)
+ material.CreateSurfaceOutput().ConnectToSource(shader.ConnectableAPI(),
+ "surface")
+
+ st_reader = UsdShade.Shader.Define(stage, f"{mat_path}/stReader")
+ st_reader.CreateIdAttr("UsdPrimvarReader_float2")
+ st_input = material.CreateInput("frame:stPrimvarName", Sdf.ValueTypeNames.Token)
+ st_input.Set("st")
+ st_reader.CreateInput("varname",
+ Sdf.ValueTypeNames.Token).ConnectToSource(st_input)
+
+ tex_sampler = UsdShade.Shader.Define(stage, f"{mat_path}/diffuseTexture")
+ tex_sampler.CreateIdAttr("UsdUVTexture")
+ tex_sampler.CreateInput("file", Sdf.ValueTypeNames.Asset).Set(tex_path)
+ tex_sampler.CreateInput("st", Sdf.ValueTypeNames.Float2).ConnectToSource(
+ st_reader.ConnectableAPI(), "result")
+ tex_sampler.CreateOutput("rgb", Sdf.ValueTypeNames.Float3)
+ shader.CreateInput("diffuseColor", Sdf.ValueTypeNames.Color3f).ConnectToSource(
+ tex_sampler.ConnectableAPI(), "rgb")
+
+ primvar = UsdGeom.PrimvarsAPI(obj_mesh).CreatePrimvar(
+ "st", Sdf.ValueTypeNames.TexCoord2fArray, UsdGeom.Tokens.faceVarying)
+ primvar.Set(Vt.Vec2fArray.FromNumpy(tex_coords_arr))
+
+ obj_mesh.GetPrim().ApplyAPI(UsdShade.MaterialBindingAPI)
+ UsdShade.MaterialBindingAPI(obj_mesh).Bind(material)
+ except Exception as e: # pylint: disable=broad-exception-caught
+ print(f"Warning: texture failed for {obj_id}: {e}")
+
+ # Add collision — all objects are static for navigation training
+ obj_prim = obj_mesh.GetPrim()
+ UsdPhysics.CollisionAPI.Apply(obj_prim)
+ ps_collision = PhysxSchema.PhysxCollisionAPI.Apply(obj_prim)
+ ps_collision.CreateContactOffsetAttr(0.005)
+ ps_collision.CreateRestOffsetAttr(0.001)
+
+ stage.GetRootLayer().Save()
+ print(f"USD scene saved to: {output_usd_path}")
+ print(f" Rooms: {len(layout_data.get('rooms', []))}")
+ print(f" Objects loaded: {obj_count}")
+ return output_usd_path
+
+
+def main():
+ parser = argparse.ArgumentParser(description="Convert SAGE-10k scene to USD")
+ parser.add_argument("layout_json", help="Path to layout JSON file")
+ parser.add_argument("output_usd", help="Output USD file path")
+ args = parser.parse_args()
+
+ layout_data = load_layout(args.layout_json)
+ layout_dir = os.path.dirname(os.path.abspath(args.layout_json))
+ create_usd_scene(layout_data, layout_dir, args.output_usd)
+
+
+if __name__ == "__main__":
+ main()
+ _app.close()
diff --git a/.dockerignore b/.dockerignore
index 6505ce0..e29ee71 100644
--- a/.dockerignore
+++ b/.dockerignore
@@ -1,2 +1,7 @@
./compass/rl_env/exts/mobility_es/mobility_es/usd
./venv
+./assets
+./.cache
+./.git
+./.nv
+./.nvidia-omniverse
diff --git a/.github/workflows/docs.yml b/.github/workflows/docs.yml
new file mode 100644
index 0000000..fcf69e1
--- /dev/null
+++ b/.github/workflows/docs.yml
@@ -0,0 +1,90 @@
+# Build the COMPASS docs site (academic landing + Sphinx handbook) and deploy
+# it to GitHub Pages.
+#
+# Triggers:
+# - pull_request touching docs/ or this workflow -> build only (validates
+# `make html` -W and uploads the rendered _site/ as an artifact reviewers
+# can download from the run page).
+# - push to main touching docs/ or this workflow -> build + deploy.
+# - workflow_dispatch -> build + deploy on demand (any branch).
+#
+# Repo settings -> Pages -> Source must be "GitHub Actions" (not "Deploy from
+# a branch") for this to take over from the legacy gh_page branch.
+
+name: Build and deploy docs
+
+on:
+ pull_request:
+ paths:
+ - "docs/**"
+ - ".github/workflows/docs.yml"
+ push:
+ branches: [main]
+ paths:
+ - "docs/**"
+ - ".github/workflows/docs.yml"
+ workflow_dispatch: {}
+
+permissions:
+ contents: read
+ pages: write
+ id-token: write
+
+jobs:
+ build:
+ runs-on: ubuntu-latest
+ steps:
+ - name: Check out repo
+ uses: actions/checkout@v4
+ with:
+ # The Bulma project page lives under docs/project_page/ with a
+ # handful of LFS-tracked images and videos. Pull them so they
+ # actually appear in the deployed site.
+ lfs: true
+
+ - name: Set up Python
+ uses: actions/setup-python@v5
+ with:
+ python-version: "3.11"
+
+ - name: Install Sphinx + nvidia-sphinx-theme + extensions
+ working-directory: docs/handbook
+ run: |
+ python -m pip install --upgrade pip
+ pip install -r requirements.txt
+
+ - name: Build handbook (warnings -> errors)
+ working-directory: docs/handbook
+ run: make html
+
+ - name: Stage academic landing + handbook under _site/
+ run: |
+ mkdir -p _site
+ cp -r docs/project_page/. _site/
+ cp -r docs/handbook/_build/html _site/docs
+
+ - name: Configure Pages
+ uses: actions/configure-pages@v5
+
+ - name: Upload site artifact
+ uses: actions/upload-pages-artifact@v3
+ with:
+ path: _site
+
+ deploy:
+ # Only deploy on push to main or manual dispatch; PR builds stop after
+ # the artifact upload above so the PR check validates the build without
+ # touching the live Pages site.
+ if: github.event_name != 'pull_request'
+ needs: build
+ runs-on: ubuntu-latest
+ environment:
+ name: github-pages
+ url: ${{ steps.deployment.outputs.page_url }}
+ concurrency:
+ group: pages
+ cancel-in-progress: true
+ steps:
+ - name: Deploy to Pages
+ id: deployment
+ uses: actions/deploy-pages@v4
diff --git a/.github/workflows/pre-commit.yml b/.github/workflows/pre-commit.yml
new file mode 100644
index 0000000..661910e
--- /dev/null
+++ b/.github/workflows/pre-commit.yml
@@ -0,0 +1,31 @@
+# Run the repo's pre-commit hooks on every PR + push to main.
+# Hooks are pinned in .pre-commit-config.yaml (yapf, pylint, nbstripout,
+# clang-format, requirements-txt-fixer, trailing-whitespace, end-of-file-fixer,
+# check-added-large-files). pylint runs without project deps because
+# `.pylintrc` disables `import-error`.
+
+name: pre-commit
+
+on:
+ pull_request:
+ push:
+ branches: [main]
+
+jobs:
+ pre-commit:
+ runs-on: ubuntu-latest
+ steps:
+ - uses: actions/checkout@v4
+
+ - uses: actions/setup-python@v5
+ with:
+ python-version: "3.11"
+ cache: pip
+
+ - name: Install clang-format binary
+ # mirrors-clang-format @ v13.0.0 expects clang-format on PATH; install
+ # via apt for reproducibility (slightly faster on cold cache than the
+ # hook's own download).
+ run: sudo apt-get update && sudo apt-get install -y clang-format
+
+ - uses: pre-commit/action@v3.0.1
diff --git a/.gitignore b/.gitignore
index 68efd40..33b1d19 100644
--- a/.gitignore
+++ b/.gitignore
@@ -7,6 +7,7 @@ cscope.*
imgui.ini
.dazel_run
venv/
+.venv/
.clangd/
# Local setups
@@ -36,3 +37,17 @@ ros2_deployment/assets/
*.onnx
*.engine
*.trt
+
+# Docker dev environment (assets downloaded by docker/prepare_assets.sh, caches
+# from container-side pip / pre-commit / huggingface routed under HOME=/workspace/COMPASS).
+/assets/
+/.cache/
+/.nv/
+/.nvidia-omniverse/
+
+# Sphinx handbook local build output (CI publishes from a separate _site/).
+/docs/handbook/_build/
+
+# Local staging dir produced by mimicking the docs.yml workflow (cp -r
+# docs/project_page/. _site/ && cp -r docs/handbook/_build/html _site/docs).
+/_site/
diff --git a/CLAUDE.md b/CLAUDE.md
new file mode 100644
index 0000000..52204eb
--- /dev/null
+++ b/CLAUDE.md
@@ -0,0 +1,89 @@
+# CLAUDE.md
+
+This file provides guidance to Claude Code (claude.ai/code) when working with code in this repository.
+
+## Project
+
+COMPASS is a cross-embodiment mobility policy framework: imitation learning + residual RL specialists per embodiment, distilled into one generalist policy, exported to ONNX/TensorRT, deployed via ROS2. Built on Isaac Lab 2.1 / Isaac Sim 4.5 and on top of NVIDIA's [X-Mobility](https://github.com/NVlabs/X-MOBILITY) base policy.
+
+End-to-end pipeline (each stage has a top-level script):
+1. `run.py` — train residual RL specialist (or evaluate any policy) in Isaac Lab
+2. `record.py` — roll out specialists to collect HDF5 distillation data
+3. `distillation_train.py` — distill specialists into one generalist (PyTorch Lightning)
+4. `onnx_conversion.py` — export specialist or generalist policy to ONNX + JIT
+5. `trt_conversion.py` — convert ONNX → TensorRT engine
+6. `ros2_deployment/` — ROS2 nodes that consume the TRT engine in Isaac Sim or on real robots
+
+## Critical: how to invoke Python
+
+Scripts that touch Isaac Lab / Isaac Sim **must** run through the Isaac Lab Python wrapper:
+
+```bash
+${ISAACLAB_PATH}/isaaclab.sh -p run.py ...
+${ISAACLAB_PATH}/isaaclab.sh -p record.py ...
+${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -r requirements.txt
+```
+
+Pure-PyTorch scripts can use plain Python:
+
+```bash
+python3 distillation_train.py ...
+python3 onnx_conversion.py ...
+python3 trt_conversion.py ...
+python3 scripts/hdf5_to_lerobot_episodic.py ...
+```
+
+Environments are created via `python3 -m venv venv && source venv/bin/activate`, but pip installs that need Isaac Lab's site-packages still go through `isaaclab.sh -p -m pip install`.
+
+GPU memory scales with the number of envs in residual RL: 32 envs ≈ 30 GB. Reduce if constrained.
+
+## Repository layout
+
+- `compass/` — main Python package
+ - `residual_rl/` — actor-critic that adds a residual on top of the X-Mobility base policy
+ - `distillation/` — generalist distillation (PyTorch Lightning trainer, HDF5 data module)
+ - `rl_env/exts/mobility_es/` — Isaac Lab extension defining embodiments (H1, Carter, Spot, G1, Digit) and scenes; see https://nvlabs.github.io/COMPASS/docs/extending.html for adding new ones
+ - `utils/` — shared helpers
+- `configs/` — Gin config files (`train_`, `eval_`, `record_`, `distillation_`, `shared`, `x_mobility_`) plus a YAML template (`distillation_dataset_config_template.yaml`) for selecting specialist checkpoints and split ratios when collecting distillation data
+- `x_mobility/x_mobility-0.1.0-py3-none-any.whl` — vendored X-Mobility wheel (installed via pip; imported as `model.x_mobility`)
+- `ros2_deployment/` — ROS2 packages and container scripts for deploying COMPASS; see https://nvlabs.github.io/COMPASS/docs/deployment/ros2.html (Isaac Sim / sim2real / object nav) and https://nvlabs.github.io/COMPASS/docs/deployment/isaac_sim.html (Isaac Sim setup)
+- `docker/` — `Dockerfile.rl` and `Dockerfile.distillation` (PyTorch 24.01 base for distillation; RL training is normally run on the host with Isaac Lab installed)
+- `scripts/hdf5_to_lerobot_episodic.py` — converts HDF5 distillation datasets to GR00T LeRobot format
+
+## External assets that must be downloaded manually
+
+- X-Mobility base checkpoint: https://huggingface.co/nvidia/X-Mobility/blob/main/x_mobility-nav2-semantic_action_path.ckpt
+- Residual-RL environment USDs: https://huggingface.co/nvidia/COMPASS/blob/main/compass_usds.zip — unzip into `compass/rl_env/exts/mobility_es/mobility_es/usd/`
+
+Most scripts take the X-Mobility checkpoint via `-b/--base-policy-path` and write outputs under `-o/--output-dir`.
+
+## Adding a new embodiment or scene
+
+1. Follow https://nvlabs.github.io/COMPASS/docs/extending.html to extend the Isaac Lab `mobility_es` extension.
+2. Register the new entry in `EmbodimentEnvCfgMap` and/or `EnvSceneAssetCfgMap` in `run.py`.
+3. Reference it via Gin config or CLI flag.
+
+## Linting and formatting
+
+No test suite. No CI config. Quality is enforced via pre-commit (`.pre-commit-config.yaml`):
+
+- `yapf` — Google style, column limit 100 (`.style.yapf`)
+- `pylint` v3.0.3 (`.pylintrc` — many checks disabled; max-line-length 100)
+- `clang-format` for C/C++ in ROS2 packages
+- `nbstripout`, `trailing-whitespace`, `end-of-file-fixer`, `requirements-txt-fixer`
+
+Run before committing:
+
+```bash
+pre-commit run --all-files
+```
+
+## Configuration system
+
+Hyperparameters use [`gin-config`](https://github.com/google/gin-config), not argparse. Common pattern: pass one or more `.gin` files via `-c/--config-files`, optionally with command-line overrides. `configs/shared.gin` is included by other configs.
+
+Logging defaults to TensorBoard at `/tensorboard/`. Add `--logger wandb` plus `--wandb-{run,project,entity}-name` flags for W&B.
+
+## Commits
+
+All commits must be DCO-signed (`git commit -s -m "..."`). Unsigned commits are rejected. See `CONTRIBUTING.md`.
diff --git a/README.md b/README.md
index c0aeab1..997fdb7 100644
--- a/README.md
+++ b/README.md
@@ -2,13 +2,14 @@
-[](https://isaac-sim.github.io/IsaacLab/v2.1.0/index.html)
+[](https://isaac-sim.github.io/IsaacLab/v3.0.0-beta1/index.html)
[](https://docs.isaacsim.omniverse.nvidia.com/4.5.0/index.html)
[](https://ubuntu.com/blog/tag/22-04-lts)
[](https://opensource.org/licenses/Apache-2.0)
[[Website]](https://nvlabs.github.io/COMPASS/)
+[[Documentation]](https://nvlabs.github.io/COMPASS/docs/)
[[arXiv]](https://arxiv.org/abs/2502.16372)
@@ -20,258 +21,56 @@ This repository provides the official PyTorch implementation of [COMPASS](https:
+COMPASS is a framework for cross-embodiment mobility that combines:
-COMPASS is a novel framework for cross-embodiment mobility that combines:
- Imitation Learning (IL) for strong baseline performance
- Residual Reinforcement Learning (RL) for embodiment-specific adaptation
- Policy distillation to create a unified, generalist policy
-## Quick Start
+## Quick start
-🚀 **Get started in 3 steps:**
-1. [Install Isaac Lab and dependencies](#installation)
-2. [Train your own specialists or deploy on robots](#usage)
-3. [Data generation for GR00T post-training](#gr00t-post-training-with-compass-datasets)
-
-## Installation
-
-
-📦 Complete Installation Guide (click to expand)
-
-### 1. Isaac Lab Installation
-* Install Isaac Lab and the residual RL mobility extension by following this [instruction](compass/rl_env/README.md).
-
-### 2. Environment Setup
-* Create and activate a virtual environment:
- ```bash
- python3 -m venv venv
- source venv/bin/activate
- ```
-
-### 3. Dependencies
-* Install the required packages:
- ```bash
- ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -r requirements.txt
- ```
-
-### 4. X-Mobility Installation
-* Install the [X-Mobility](https://github.com/NVlabs/X-MOBILITY) package:
- ```bash
- ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install x_mobility/x_mobility-0.1.0-py3-none-any.whl
- ```
-* Download the pre-trained X-Mobility checkpoint from: https://huggingface.co/nvidia/X-Mobility/blob/main/x_mobility-nav2-semantic_action_path.ckpt
-
-### 5. Residual RL environment USDs
-* Download the residual RL environment USDs from: https://huggingface.co/nvidia/COMPASS/blob/main/compass_usds.zip
-* Unzip and place the downloaded USDs in the `compass/rl_env/exts/mobility_es/mobility_es/usd` directory
-
-
-
-
-## Usage
-
-
-🤖 Training Residual RL Specialists (click to expand)
-
-### Residual RL Specialists
-
-* Train with the default configurations in `configs/train_config.gin`:
- ```bash
- ${ISAACLAB_PATH}/isaaclab.sh -p run.py \
- -c configs/train_config.gin \
- -o \
- -b \
- --enable_camera
- ```
-
-* Evaluate trained model:
- ```bash
- ${ISAACLAB_PATH}/isaaclab.sh -p run.py \
- -c configs/eval_config.gin \
- -o \
- -b \
- -p \
- --enable_camera \
- --video \
- --video_interval
- ```
-
-> **NOTE**: The GPU memory usage is proportional to the number of environments in residual RL training. For example, 32 environments will use around 30GB memory, so reduce the number of environments if you have limited GPU memory.
-
-
-
-
-🧠 Policy Distillation (click to expand)
-
-### Policy Distillation
-
-* Collect specialist data:
- * Update specialists policy checkpoint paths in [dataset_config_template](configs/distillation_dataset_config_template.yaml)
- * Run data collection:
- ```bash
- ${ISAACLAB_PATH}/isaaclab.sh -p record.py \
- -c configs/distillation_dataset_config_template.yaml \
- -o \
- -b \
- --dataset-name
- ```
-
-* Train generalist policy:
- ```bash
- python3 distillation_train.py \
- --config-files configs/distillation_config.gin \
- --dataset-path \
- --output-dir
- ```
-
-* Evaluate generalist policy:
- ```bash
- ${ISAACLAB_PATH}/isaaclab.sh -p run.py \
- -c configs/eval_config.gin \
- -o \
- -b \
- -d \
- --enable_camera \
- --video \
- --video_interval
- ```
-
-
-
-
-📤 Model Export (click to expand)
-
-### Model Export
-
-* Export RL specialist policy to ONNX or JIT formats:
- ```bash
- python3 onnx_conversion.py \
- -b \
- -r \
- -o \
- -j
- ```
-
-* Export generalist policy to ONNX or JIT formats:
- ```bash
- python3 onnx_conversion.py \
- -b \
- -g \
- -e \
- -o \
- -j
- ```
-
-* Convert the ONNX to TensorRT:
- ```bash
- python3 trt_conversion.py -o -t
- ```
-
-
-
-
-🔧 Add New Embodiment or Scene (click to expand)
-
-### Add New Embodiment or Scene
-
-* Follow this [instruction](compass/rl_env/README.md) to add a new embodiment or scene to the Isaac Lab RL environment.
-* Register the new embodiment or scene to the `EmbodimentEnvCfgMap` and `EnvSceneAssetCfgMap` in [run.py](run.py), then update the configs or use command line arguments to select the new embodiment or scene.
-
-
-
-
-🚀 ROS2 Deployment (click to expand)
-
-### ROS2 Deployment
-
-To deploy COMPASS in Isaac Sim or on real robots using ROS2, please follow the detailed instructions in [ros2_deployment/README.md](ros2_deployment/README.md). This guide covers containerized workflows, and Isaac Sim integration.
-
-
-
-
-
-📊 Logging Options (click to expand)
-
-### Logging
-
-The training and evaluation scripts use TensorBoard for logging by default. Weights & Biases (W&B) logging is also supported for more advanced experiment tracking features.
-
-**To use TensorBoard (default):**
-- Logs will be saved to `/tensorboard/`
-- View logs with: `tensorboard --logdir=/tensorboard/`
-
-**To use Weights & Biases:**
-1. Install and set up W&B: `pip install wandb` and follow the [setup instructions](https://docs.wandb.ai/quickstart)
-2. Log in to your W&B account: `wandb login`
-3. Add the `--logger wandb` flag to your command:
- ```bash
- ${ISAACLAB_PATH}/isaaclab.sh -p run.py \
- -c configs/train_config.gin \
- -o \
- --enable_camera \
- --logger wandb \
- --wandb-run-name "experiment_name" \
- --wandb-project-name "project_name" \
- --wandb-entity-name "your_username_or_team"
- ```
-
-
-
-
-## GR00T Post-training with COMPASS Datasets
-
-The COMPASS distillation datasets can also be used to train VLA models like [GR00T](https://github.com/NVIDIA/Isaac-GR00T), to enhance their navigation capabilities.
-
-
-🤖 GR00T Post-training Steps (click to expand)
-
-**Step 1: Collect the datasets and convert to GR00T Lerobot format**
-
-Follow the steps described above in the "🤖 Training Residual RL Specialists" and "🧠 Policy Distillation" sections to train a specialist policy and generate the corresponding specialist datasets.
-
-Use the following command to convert the distillation dataset from HDF5 to the GR00T Lerobot episodic format:
- ```bash
- python scripts/hdf5_to_lerobot_episodic.py --hdf5-dir --output-path
- ```
-
-**Step 2: Post-train the GR00T model**
-
-Once the dataset is converted, follow the post-training [instructions](https://github.com/NVIDIA/Isaac-GR00T/tree/main/getting_started) provided in the GR00T repo. A ready-to-use navigation data configuration for post-training is available in this [branch](https://github.com/NVIDIA/Isaac-GR00T/compare/main...liuw/nav_fine_tune).
-
-**Step 3: Evaluate the post-trained GR00T model**
+```bash
+git clone https://github.com/NVlabs/COMPASS.git && cd COMPASS
-To evaluate the post-trained GR00T model, first launch the inference server from within the GR00T repository by following the setup instructions provided there. Ensure that the data configuration matches the one used during training, and the port number is set as 8888.
+export HF_TOKEN=hf_xxx # https://huggingface.co/settings/tokens
+./docker/run.sh assets # USDs + X-Mobility ckpt → ./assets/ (~5 min)
+./docker/run.sh build # build the dev image (~10 min)
+source ./docker/activate # venv-like activation (prompt: (compass-rl))
-Once the server is running, start the COMPASS evaluation with the following command:
-```bash
-${ISAACLAB_PATH}/isaaclab.sh -p run.py \
- -c configs/eval_config.gin \
- -o \
- -b \
- --enable_camera \
- --gr00t-policy
+python run.py -c configs/train_config.gin -o /tmp/out -b ./assets/x_mobility.ckpt --enable_cameras
```
-You can modify the evaluation parameters in the eval_config.gin file as needed.
-
+`python` is now a shim that runs inside the container. Edit code with your host
+editor — the bind-mount means changes hot-reload. `deactivate` to leave;
+`./docker/run.sh down` to stop the container.
+
+## Documentation
+Everything else — install details, training / distillation / export workflows,
+ROS2 deployment, OSMO cloud submission, GR00T post-training, agentic skills,
+auto-OMap generation, and contributing — lives in the **handbook**:
+> 📖 ** **
## License
+
COMPASS is released under the Apache License 2.0. See [LICENSE](LICENSE) for additional details.
-## Core Contributors
-Wei Liu, Huihua Zhao, Chenran Li, Joydeep Biswas, Soha Pouya, Yan Chang
+## Core contributors
+Wei Liu, Huihua Zhao, Chenran Li, Joydeep Biswas, Soha Pouya, Yan Chang
## Acknowledgments
+
We would like to acknowledge the following projects where parts of the codes in this repo is derived from:
+
- [RSL_RL](https://github.com/leggedrobotics/rsl_rl/tree/main)
- [Isaac Lab](https://github.com/isaac-sim/IsaacLab)
## Citation
+
If you find this work useful in your research, please consider citing:
+
```bibtex
@article{liu2025compass,
title={COMPASS: Cross-embodiment Mobility Policy via Residual RL and Skill Synthesis},
@@ -279,3 +78,4 @@ If you find this work useful in your research, please consider citing:
journal={arXiv preprint arXiv:2502.16372},
year={2025}
}
+```
diff --git a/compass/__init__.py b/compass/__init__.py
index 7ab23ee..3159bfe 100644
--- a/compass/__init__.py
+++ b/compass/__init__.py
@@ -12,4 +12,3 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
diff --git a/compass/residual_rl/__init__.py b/compass/residual_rl/__init__.py
index 7ab23ee..3159bfe 100644
--- a/compass/residual_rl/__init__.py
+++ b/compass/residual_rl/__init__.py
@@ -12,4 +12,3 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
diff --git a/compass/rl_env/README.md b/compass/rl_env/README.md
deleted file mode 100644
index f943180..0000000
--- a/compass/rl_env/README.md
+++ /dev/null
@@ -1,100 +0,0 @@
-# Isaac Lab Extension for Mobility Embodiment Specialist using Residual RL
-
-## Overview
-
-This directory contains Isaac Lab extension for mobility embodiment specialist with residual RL.
-
-## Installation
-
-1. First, install Isaac Lab v2.1.0 and Isaac Sim 4.5 by following the [Isaac Lab installation guide](https://isaac-sim.github.io/IsaacLab/v2.1.0/source/setup/installation/index.html).
-
- The repo has been tested in Isaac Lab v2.1.0, so follow the steps below to set the correct version:
- ```bash
- # Clone the Isaac Lab repository
- git clone git@github.com:isaac-sim/IsaacLab.git
-
- # Switch to the correct version
- cd IsaacLab
- git fetch origin
- git checkout v2.1.0
-
- # Install Isaac Lab
- ./isaaclab.sh --install
- ```
- > **NOTE**: There might be error messages about RSL_RL not found during installation, we can safely ignore it as a custimized RSL_RL libary is used for residual RL training.
-
-
-2. Install the mobility_es extension in this directory after Isaac Lab and Sim are installed:
-
- ```bash
- # Set Isaac Lab path
- export ISAACLAB_PATH=
-
- # Install the extension
- ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -e exts/mobility_es
- ```
-
-## Usage
-
-### Running the Environment
-
-```bash
-${ISAACLAB_PATH}/isaaclab.sh -p scripts/play.py --enable_cameras
-```
-
-### Adding New Embodiments
-
-To add a new robot embodiment, follow these steps:
-
-1. **Create Robot Configuration**:
- - Follow Isaac Lab [instructions](https://isaac-sim.github.io/IsaacLab/main/source/how-to/write_articulation_cfg.html) to add a new robot articulation configuration in [exts/mobility_es/mobility_es/config/robots.py](exts/mobility_es/mobility_es/config/robots.py)
- - Ensure proper joint configurations, collision properties, and physics parameters are set
-
-2. **Create Environment Configuration**:
- - Create a new RL environment class that inherits from `GoalReachingEnvCfg` in [exts/mobility_es/mobility_es/config/env_cfg.py](exts/mobility_es/mobility_es/config/env_cfg.py)
- - Override the following components as needed:
-
- | Component | Description |
- |-----------|-------------|
- | `scene.robot` | Set robot articulation configuration |
- | `scene.camera` | Configure camera settings |
- | `actions` | Define action item for the embodiment |
- | `observations` | Configure RL observations |
- | `events` | Configure RL events |
- | `rewards` | Configure RL rewards |
- | `terminations` | Configure RL terminations |
-
- > **NOTE**: Each embodiment should define its own action term as a low-level controller that maps velocity commands to joint positions. We have pre-defined action terms for different robot embodiments in [exts/mobility_es/mobility_es/mdp/action](exts/mobility_es/mobility_es/mdp/action) that can be re-configured for new embodiments.
-
-3. **Register and Verify Environment**:
- - Import your new environment in the play.py script [scripts/play.py](scripts/play.py)
- - Verify the environment is functional by running the play.py script with the new environment
-
-
-3. **Examples of Existing Embodiments**:
-- [H1 Humanoid Robot](exts/mobility_es/mobility_es/config/h1_env_cfg.py)
-- [Carter Mobile Robot](exts/mobility_es/mobility_es/config/carter_env_cfg.py)
-- [Spot Quadruped Robot](exts/mobility_es/mobility_es/config/spot_env_cfg.py)
-- [G1 Humanoid Robot](exts/mobility_es/mobility_es/config/g1_env_cfg.py)
-- [Digit Humanoid Robot](exts/mobility_es/mobility_es/config/digit_env_cfg.py)
-
-
-### Adding New Scenes
-
-To add a new scene, follow these steps:
-
-1. **Create Scene Configuration**:
- - Follow Isaac Lab [instructions](https://isaac-sim.github.io/IsaacLab/main/source/tutorials/02_scene/create_scene.html) to add a new scene configuration in [exts/mobility_es/mobility_es/config/environments.py](exts/mobility_es/mobility_es/config/environments.py), make sure to inherit from `EnvSceneAssetCfg` with proper parameters like pose_sample_range, env_spacing, replicate_physics, etc.
-
-
-2. **Add Occupancy Map [Optional]**:
- - We use occupancy map for collision-free pose sampling, while optional, we recommend adding the occupancy map for the new scene to improve sampling efficiency.
- - For occupancy map generation, follow this [insturction](https://docs.omniverse.nvidia.com/isaacsim/latest/features/ext_omni_isaac_occupancy_map.html) to create the occupancy map with the new scene USD file in Isaac Sim. Make sure to rotate the occupancy map properly to match the scene orientation and set the origin as the top-left of the image in the occupancy_map.yaml file.
-
- 
-
- - Add the occupancy_map.yaml path in `OMAP_PATHS` in [exts/mobility_es/mobility_es/config/environments.py](exts/mobility_es/mobility_es/config/environments.py) with key as the scene name and value as the occupancy map yaml path.
-
-3. **Register and Verify Scene**:
- - Import your new scene in the play.py script [scripts/play.py](scripts/play.py)
- - Verify the scene is functional by running the play.py script with the new scene by setting `env_cfg.scene.environment = MyNewSceneCfg()`
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/__init__.py b/compass/rl_env/exts/mobility_es/mobility_es/__init__.py
index 9ce6247..ef95fbd 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/__init__.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/__init__.py
@@ -12,7 +12,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""
Python module serving as a project/extension template.
"""
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/config/__init__.py b/compass/rl_env/exts/mobility_es/mobility_es/config/__init__.py
index 7ab23ee..3159bfe 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/config/__init__.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/config/__init__.py
@@ -12,4 +12,3 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/config/carter_env_cfg.py b/compass/rl_env/exts/mobility_es/mobility_es/config/carter_env_cfg.py
index 847c0ff..931cf25 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/config/carter_env_cfg.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/config/carter_env_cfg.py
@@ -21,6 +21,7 @@
from isaaclab.managers import ObservationTermCfg as ObsTerm
from isaaclab.managers import EventTermCfg as EventTerm
from isaaclab.managers import SceneEntityCfg
+from isaaclab.managers import ActionTermCfg
from mobility_es.config import scene_assets
from mobility_es.config import robots
@@ -32,8 +33,7 @@
class CarterActionsCfg:
"""Action specifications for the MDP."""
- drive_joints = mdp.ActionTermCfg(class_type=NonHolonomicPerfectControlAction,
- asset_name="robot")
+ drive_joints = ActionTermCfg(class_type=NonHolonomicPerfectControlAction, asset_name="robot")
@configclass
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/config/digit_env_cfg.py b/compass/rl_env/exts/mobility_es/mobility_es/config/digit_env_cfg.py
index df3cfdf..e79031f 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/config/digit_env_cfg.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/config/digit_env_cfg.py
@@ -24,7 +24,7 @@
from isaaclab.managers import ObservationTermCfg as ObsTerm
from isaaclab.managers import SceneEntityCfg
from isaaclab.utils import configclass
-from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise
+from isaaclab.utils.noise import UniformNoiseCfg as Unoise
from mobility_es.config import scene_assets
from mobility_es.config.robots import digit, DIGIT_ACTUATED_JOINT_NAMES
@@ -58,7 +58,7 @@ def __post_init__(self):
self.scene.camera = scene_assets.camera.replace(
prim_path="{ENV_REGEX_NS}/Robot/torso_base/front_cam")
self.scene.camera.offset = CameraCfg.OffsetCfg(pos=(0.06, 0.0, -0.065),
- rot=(-0.2705, 0.6532, -0.6532, 0.2705981),
+ rot=(0.6532, -0.6532, 0.2705981, -0.2705),
convention="ros")
self.actions = DigitActionsCfg()
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/config/env_cfg.py b/compass/rl_env/exts/mobility_es/mobility_es/config/env_cfg.py
index 3c65a2a..5e7fad5 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/config/env_cfg.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/config/env_cfg.py
@@ -27,7 +27,8 @@
from isaaclab.sensors import ContactSensorCfg
from isaaclab.scene import InteractiveSceneCfg
from isaaclab.utils import configclass
-from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise
+from isaaclab.utils.noise import UniformNoiseCfg as Unoise
+from isaaclab_physx.physics import PhysxCfg
from mobility_es.config import environments
from mobility_es.config import scene_assets
@@ -311,10 +312,10 @@ def __post_init__(self):
# general settings
self.decimation = 20
self.episode_length_s = EPISODE_LENGTH_S
- self.rerender_on_reset = True
+ self.num_rerenders_on_reset = 1
# simulation settings
self.sim.dt = 0.005
- self.sim.physx.bounce_threshold_velocity = 0.2
+ self.sim.physics = PhysxCfg(bounce_threshold_velocity=0.2)
# default friction material
self.sim.physics_material.static_friction = 1.0
self.sim.physics_material.dynamic_friction = 1.0
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/config/environments.py b/compass/rl_env/exts/mobility_es/mobility_es/config/environments.py
index 7d90eba..9af0bc0 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/config/environments.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/config/environments.py
@@ -84,7 +84,7 @@ class EnvSceneAssetCfg(AssetBaseCfg):
prim_path="{ENV_REGEX_NS}/CombinedSingleRack",
init_state=AssetBaseCfg.InitialStateCfg(
pos=(0, 0, 0.01),
- rot=(1.0, 0.0, 0.0, 0.0),
+ rot=(0.0, 0.0, 0.0, 1.0),
),
spawn=sim_utils.UsdFileCfg(
usd_path=USD_PATHS['CombinedSingleRack'],
@@ -107,7 +107,7 @@ class EnvSceneAssetCfg(AssetBaseCfg):
prim_path="{ENV_REGEX_NS}/CombinedMultiRack",
init_state=AssetBaseCfg.InitialStateCfg(
pos=(0, 0, 0.01),
- rot=(1.0, 0.0, 0.0, 0.0),
+ rot=(0.0, 0.0, 0.0, 1.0),
),
spawn=sim_utils.UsdFileCfg(
usd_path=USD_PATHS['CombinedMultiRack'],
@@ -130,7 +130,7 @@ class EnvSceneAssetCfg(AssetBaseCfg):
prim_path="{ENV_REGEX_NS}/GalileoLab",
init_state=AssetBaseCfg.InitialStateCfg(
pos=(0, 0, 0.01),
- rot=(1.0, 0.0, 0.0, 0.0),
+ rot=(0.0, 0.0, 0.0, 1.0),
),
spawn=sim_utils.UsdFileCfg(
usd_path=USD_PATHS['GalileoLab'],
@@ -149,7 +149,7 @@ class EnvSceneAssetCfg(AssetBaseCfg):
prim_path="{ENV_REGEX_NS}/WarehouseSingleRack",
init_state=AssetBaseCfg.InitialStateCfg(
pos=(0, 0, 0.01),
- rot=(1.0, 0.0, 0.0, 0.0),
+ rot=(0.0, 0.0, 0.0, 1.0),
),
spawn=sim_utils.UsdFileCfg(
usd_path=USD_PATHS['WarehouseSingleRack'],
@@ -167,7 +167,7 @@ class EnvSceneAssetCfg(AssetBaseCfg):
prim_path="{ENV_REGEX_NS}/WarehouseMultiRack",
init_state=AssetBaseCfg.InitialStateCfg(
pos=(0, 0, 0.01),
- rot=(1.0, 0.0, 0.0, 0.0),
+ rot=(0.0, 0.0, 0.0, 1.0),
),
spawn=sim_utils.UsdFileCfg(
usd_path=USD_PATHS['WarehouseMultiRack'],
@@ -190,7 +190,7 @@ class EnvSceneAssetCfg(AssetBaseCfg):
prim_path="{ENV_REGEX_NS}/SimpleOffice",
init_state=AssetBaseCfg.InitialStateCfg(
pos=(0, 0, 0.01),
- rot=(1.0, 0.0, 0.0, 0.0),
+ rot=(0.0, 0.0, 0.0, 1.0),
),
spawn=sim_utils.UsdFileCfg(
usd_path=USD_PATHS['SimpleOffice'],
@@ -209,7 +209,7 @@ class EnvSceneAssetCfg(AssetBaseCfg):
prim_path="{ENV_REGEX_NS}/Hospital",
init_state=AssetBaseCfg.InitialStateCfg(
pos=(0, 0, 0.01),
- rot=(1.0, 0.0, 0.0, 0.0),
+ rot=(0.0, 0.0, 0.0, 1.0),
),
spawn=sim_utils.UsdFileCfg(
usd_path=USD_PATHS['Hospital'],
@@ -233,7 +233,7 @@ class EnvSceneAssetCfg(AssetBaseCfg):
prim_path="{ENV_REGEX_NS}/RandomEnvs",
init_state=AssetBaseCfg.InitialStateCfg(
pos=(0, 0, 0.01),
- rot=(1.0, 0.0, 0.0, 0.0),
+ rot=(0.0, 0.0, 0.0, 1.0),
),
spawn=sim_utils.MultiUsdFileCfg(
usd_path=[USD_PATHS['SimpleOffice'], USD_PATHS['GalileoLab'], USD_PATHS['SimpleWarehouse']],
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/config/g1_env_cfg.py b/compass/rl_env/exts/mobility_es/mobility_es/config/g1_env_cfg.py
index 76dd33d..ca2a782 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/config/g1_env_cfg.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/config/g1_env_cfg.py
@@ -50,7 +50,7 @@ def __post_init__(self):
self.scene.camera = scene_assets.camera.replace(
prim_path="{ENV_REGEX_NS}/Robot/torso_link/front_cam")
self.scene.camera.offset = CameraCfg.OffsetCfg(pos=(0.1, 0.0, 0.45),
- rot=(-0.2705, 0.6532, -0.6532, 0.2705981),
+ rot=(0.6532, -0.6532, 0.2705981, -0.2705),
convention="ros")
self.actions = G1ActionsCfg()
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/config/h1_env_cfg.py b/compass/rl_env/exts/mobility_es/mobility_es/config/h1_env_cfg.py
index 513d5b8..39b4123 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/config/h1_env_cfg.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/config/h1_env_cfg.py
@@ -50,7 +50,7 @@ def __post_init__(self):
self.scene.camera = scene_assets.camera.replace(
prim_path="{ENV_REGEX_NS}/Robot/torso_link/front_cam")
self.scene.camera.offset = CameraCfg.OffsetCfg(pos=(0.15, 0.0, 0.65),
- rot=(-0.2705, 0.6532, -0.6532, 0.2705981),
+ rot=(0.6532, -0.6532, 0.2705981, -0.2705),
convention="ros")
self.actions = H1ActionsCfg()
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/config/robots.py b/compass/rl_env/exts/mobility_es/mobility_es/config/robots.py
index 85f6dee..f268d0f 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/config/robots.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/config/robots.py
@@ -40,7 +40,7 @@
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.02),
- rot=(1, 0.0, 0.0, 0),
+ rot=(0.0, 0.0, 0.0, 1),
joint_pos={
"joint_wheel_left": 0.0,
"joint_wheel_right": 0.0,
@@ -62,7 +62,7 @@
"joint_caster_left",
"joint_caster_right",
],
- velocity_limit=1000,
+ velocity_limit_sim=360.0,
stiffness=0.0,
damping=0.0,
),
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/config/scene_assets.py b/compass/rl_env/exts/mobility_es/mobility_es/config/scene_assets.py
index 14022c7..b867cc7 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/config/scene_assets.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/config/scene_assets.py
@@ -43,6 +43,6 @@
horizontal_aperture=20.955,
clipping_range=(0.1, 20.0)),
offset=CameraCfg.OffsetCfg(pos=(0.10434, 0.0, 0.37439),
- rot=(0.5, -0.5, 0.5, -0.5),
+ rot=(-0.5, 0.5, -0.5, 0.5),
convention="ros"),
)
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/mdp/__init__.py b/compass/rl_env/exts/mobility_es/mobility_es/mdp/__init__.py
index 7ab23ee..3159bfe 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/mdp/__init__.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/mdp/__init__.py
@@ -12,4 +12,3 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/__init__.py b/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/__init__.py
index 7ab23ee..3159bfe 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/__init__.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/__init__.py
@@ -12,4 +12,3 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/action_visualization.py b/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/action_visualization.py
index c4da327..fb79895 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/action_visualization.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/action_visualization.py
@@ -16,6 +16,7 @@
from __future__ import annotations
import torch
+import warp as wp
import isaaclab.utils.math as math_utils
from isaaclab.markers import VisualizationMarkers
@@ -38,7 +39,7 @@ def visualize(self, base_action, residual_action):
if not self._base_markers or not self._residual_markers:
self._initialize_action_markers()
# Visualize base action.
- robot_pos_w = self.robot.data.root_pos_w.clone()
+ robot_pos_w = wp.to_torch(self.robot.data.root_pos_w).clone()
robot_pos_w[:, 2] += ACTION_HEIGHT
base_action_arrow_scale, base_action_arrow_quat = self._resolve_xy_velocity_to_arrow(
base_action[:, :2])
@@ -78,7 +79,7 @@ def _resolve_xy_velocity_to_arrow(
zeros = torch.zeros_like(heading_angle)
arrow_quat = math_utils.quat_from_euler_xyz(zeros, zeros, heading_angle)
# convert everything back from base to world frame
- base_quat_w = self.robot.data.root_quat_w
+ base_quat_w = wp.to_torch(self.robot.data.root_quat_w)
arrow_quat = math_utils.quat_mul(base_quat_w, arrow_quat)
return arrow_scale, arrow_quat
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/non_holonomic_perfect_control_action.py b/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/non_holonomic_perfect_control_action.py
index 08dbdca..501d699 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/non_holonomic_perfect_control_action.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/mdp/action/non_holonomic_perfect_control_action.py
@@ -16,10 +16,11 @@
from __future__ import annotations
import torch
+import warp as wp
from collections.abc import Sequence
from isaaclab.assets.articulation import Articulation
-from isaaclab.envs.mdp.actions import ActionTerm, ActionTermCfg
+from isaaclab.managers import ActionTerm, ActionTermCfg
from mobility_es.mdp.action.action_visualization import ActionVisualizer
from mobility_es.wrapper.env_wrapper import RLESEnvWrapper
@@ -61,19 +62,16 @@ def process_actions(self, actions):
self._processed_actions = self.raw_actions[:, (0, 5)]
def apply_actions(self):
- # Get current asset state
- root_state = self._asset.data.root_state_w
-
# Extract linear_x and angular_z from actions
linear_x = self.processed_actions[:, 0]
angular_z = self.processed_actions[:, 1]
- # Get current position and orientation quaternion
- pos = root_state[:, :3]
- quat = root_state[:, 3:7]
+ # Get current position and orientation quaternion (xyzw: x=0, y=1, z=2, w=3)
+ pos = wp.to_torch(self._asset.data.root_link_pos_w).clone()
+ quat = wp.to_torch(self._asset.data.root_link_quat_w)
- # Convert quaternion to yaw angle
- yaw = 2 * torch.atan2(quat[:, 3], quat[:, 0])
+ # Convert quaternion to yaw angle (xyzw convention: x=0, y=1, z=2, w=3)
+ yaw = 2 * torch.atan2(quat[:, 2], quat[:, 3])
# Update yaw with angular velocity
dt = self._env.physics_dt
@@ -83,23 +81,24 @@ def apply_actions(self):
pos[:, 0] += linear_x * torch.cos(new_yaw) * dt
pos[:, 1] += linear_x * torch.sin(new_yaw) * dt
- # Convert new yaw to quaternion (rotation around z-axis only)
+ # Convert new yaw to quaternion (rotation around z-axis only, xyzw convention)
new_quat = torch.zeros_like(quat)
- new_quat[:, 0] = torch.cos(new_yaw / 2)
- new_quat[:, 3] = torch.sin(new_yaw / 2)
-
- # Update root state
- root_state[:, :3] = pos
- root_state[:, 3:7] = new_quat
- root_state[:, 7:10] = torch.stack([
- linear_x * torch.cos(new_yaw), linear_x * torch.sin(new_yaw),
- torch.zeros_like(linear_x)
+ new_quat[:, 2] = torch.sin(new_yaw / 2) # z component
+ new_quat[:, 3] = torch.cos(new_yaw / 2) # w component
+
+ # Write new pose and velocity separately (root_state_w API removed in IsaacLab 3.0)
+ new_pose = torch.cat([pos, new_quat], dim=-1)
+ new_vel = torch.stack([
+ linear_x * torch.cos(new_yaw),
+ linear_x * torch.sin(new_yaw),
+ torch.zeros_like(linear_x),
+ torch.zeros_like(angular_z),
+ torch.zeros_like(angular_z),
+ angular_z,
],
- dim=1)
- root_state[:, 10:13] = torch.stack(
- [torch.zeros_like(angular_z),
- torch.zeros_like(angular_z), angular_z], dim=1)
- self._asset.write_root_state_to_sim(root_state)
+ dim=1)
+ self._asset.write_root_pose_to_sim_index(root_pose=new_pose)
+ self._asset.write_root_velocity_to_sim_index(root_velocity=new_vel)
def reset(self, env_ids: Sequence[int] | None = None) -> None:
self._raw_actions[env_ids] = 0.0
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/mdp/command/__init__.py b/compass/rl_env/exts/mobility_es/mobility_es/mdp/command/__init__.py
index 7ab23ee..3159bfe 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/mdp/command/__init__.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/mdp/command/__init__.py
@@ -12,4 +12,3 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/mdp/command/uniform_collision_free_pose_command.py b/compass/rl_env/exts/mobility_es/mobility_es/mdp/command/uniform_collision_free_pose_command.py
index 10c773f..444b9a7 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/mdp/command/uniform_collision_free_pose_command.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/mdp/command/uniform_collision_free_pose_command.py
@@ -18,6 +18,7 @@
import random
import torch
+import warp as wp
from typing import TYPE_CHECKING
from collections.abc import Sequence
@@ -29,7 +30,7 @@
from mobility_es.mdp.command.commands_cfg import UniformCollisionFreePose2dCommandCfg
-class UniformCollisionFreePoseCommand(commands.pose_2d_command.UniformPose2dCommand):
+class UniformCollisionFreePoseCommand(commands.UniformPose2dCommand):
"""Command generator that generates pose commands containing a 3-D position and heading.
The command generator samples uniform 2D positions around the environment origin. It sets
@@ -73,7 +74,8 @@ def _resample_command(self, env_ids: Sequence[int]):
num_resample_trials = 0
while num_resample_trials < self.cfg.max_resample_trial:
# Obtain origins for the robots
- self.pos_command_w[resample_env_ids] = self.robot.data.root_pos_w[resample_env_ids]
+ self.pos_command_w[resample_env_ids] = wp.to_torch(
+ self.robot.data.root_pos_w)[resample_env_ids]
# Offset the position command by the current root position
r = torch.empty(len(resample_env_ids), device=self.device)
# Randomize the position
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/mdp/events.py b/compass/rl_env/exts/mobility_es/mobility_es/mdp/events.py
index 6026141..0349d27 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/mdp/events.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/mdp/events.py
@@ -16,6 +16,7 @@
from __future__ import annotations
import torch
+import warp as wp
import isaaclab.utils.math as math_utils
from isaaclab.managers import SceneEntityCfg
@@ -30,8 +31,9 @@ def sample_root_state_uniform(env: RLESEnvWrapper,
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot")):
# extract the used quantities (to enable type-hinting)
asset = env.scene[asset_cfg.name]
- # get default root state
- root_states = asset.data.default_root_state[env_ids].clone()
+ # get default root state (pose and velocity separately in IsaacLab 3.0)
+ default_root_pose = wp.to_torch(asset.data.default_root_pose)[env_ids].clone()
+ default_root_vel = wp.to_torch(asset.data.default_root_vel)[env_ids].clone()
# Sample poses
pose_range_list = [
@@ -43,10 +45,10 @@ def sample_root_state_uniform(env: RLESEnvWrapper,
rand_samples = math_utils.sample_uniform(pose_ranges[:, 0],
pose_ranges[:, 1], (len(env_ids), 6),
device=asset.device)
- positions = root_states[:, 0:3] + env.scene.env_origins[env_ids] + rand_samples[:, 0:3]
+ positions = default_root_pose[:, 0:3] + env.scene.env_origins[env_ids] + rand_samples[:, 0:3]
orientations_delta = math_utils.quat_from_euler_xyz(rand_samples[:, 3], rand_samples[:, 4],
rand_samples[:, 5])
- orientations = math_utils.quat_mul(root_states[:, 3:7], orientations_delta)
+ orientations = math_utils.quat_mul(default_root_pose[:, 3:7], orientations_delta)
# Sample velocities
velocity_range_list = [
@@ -56,7 +58,7 @@ def sample_root_state_uniform(env: RLESEnvWrapper,
rand_samples = math_utils.sample_uniform(velocity_ranges[:, 0],
velocity_ranges[:, 1], (len(env_ids), 6),
device=asset.device)
- velocities = root_states[:, 7:13] + rand_samples
+ velocities = default_root_vel + rand_samples
return positions, orientations, velocities
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/mdp/observations.py b/compass/rl_env/exts/mobility_es/mobility_es/mdp/observations.py
index aa517b6..fc9b86b 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/mdp/observations.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/mdp/observations.py
@@ -16,6 +16,7 @@
from __future__ import annotations
import torch
+import warp as wp
from isaaclab.assets import RigidObject
from isaaclab.managers import SceneEntityCfg
@@ -31,7 +32,7 @@ def root_speed(
) -> torch.Tensor:
"""The speed of the root, which is the normalization of the linear velocity"""
asset: RigidObject = env.scene[asset_cfg.name]
- return torch.norm(asset.data.root_lin_vel_w, dim=1).unsqueeze(1)
+ return torch.norm(wp.to_torch(asset.data.root_lin_vel_w), dim=1).unsqueeze(1)
def root_yaw_rate(
@@ -40,7 +41,7 @@ def root_yaw_rate(
) -> torch.Tensor:
"""The yaw rate of the root"""
asset: RigidObject = env.scene[asset_cfg.name]
- return asset.data.root_ang_vel_w[:, 2].unsqueeze(1)
+ return wp.to_torch(asset.data.root_ang_vel_w)[:, 2].unsqueeze(1)
def camera_img(env: RLESEnvWrapper, data_type: str = "rgb"):
@@ -68,8 +69,8 @@ def camera_to_world(env: RLESEnvWrapper):
batch_size = pos_w.shape[0]
R_w_c = torch.zeros((batch_size, 3, 3), device=pos_w.device)
- # Extract quaternion components
- w, x, y, z = quat_w_world[:, 0], quat_w_world[:, 1], quat_w_world[:, 2], quat_w_world[:, 3]
+ # Extract quaternion components (xyzw convention: x=0, y=1, z=2, w=3)
+ x, y, z, w = quat_w_world[:, 0], quat_w_world[:, 1], quat_w_world[:, 2], quat_w_world[:, 3]
# Fill rotation matrix using quaternion
R_w_c[:, 0, 0] = 1 - 2 * (y**2 + z**2)
@@ -153,7 +154,7 @@ def foot_print(
) -> torch.Tensor:
"""Represent the foot print of the asset as a rectangle that is offset to the asset root."""
robot: RigidObject = env.scene[asset_cfg.name]
- root_pos = robot.data.root_pos_w - env.scene.env_origins
+ root_pos = wp.to_torch(robot.data.root_pos_w) - env.scene.env_origins
root_pos_2d = root_pos[:, :2]
def create_footprint_tensor(length, width, device):
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/mdp/termination.py b/compass/rl_env/exts/mobility_es/mobility_es/mdp/termination.py
index c18ef0e..e8ad4f5 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/mdp/termination.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/mdp/termination.py
@@ -16,6 +16,7 @@
from __future__ import annotations
import torch
+import warp as wp
from isaaclab.assets import RigidObject
from isaaclab.managers import SceneEntityCfg
@@ -37,8 +38,8 @@ def goal_reached(
robot: RigidObject = env.scene[robot_cfg.name]
# Check if the robot velocity is below the threshold
- root_linear_vel = torch.norm(robot.data.root_lin_vel_w, dim=1)
- root_angular_vel = robot.data.root_ang_vel_w[:, 2].abs()
+ root_linear_vel = torch.norm(wp.to_torch(robot.data.root_lin_vel_w), dim=1)
+ root_angular_vel = wp.to_torch(robot.data.root_ang_vel_w)[:, 2].abs()
vel_threshold = torch.logical_and(root_linear_vel < linear_vel_threshold,
root_angular_vel < angular_vel_threshold)
@@ -56,6 +57,6 @@ def goal_reached(
def nan_pose(env: RLESEnvWrapper, robot_cfg: SceneEntityCfg = SceneEntityCfg("robot")):
# Check if the robot pose is nan, which can happen when the robot explodes in simulation.
- nan_pos = torch.isnan(env.scene[robot_cfg.name].data.root_pos_w)
- nan_quat = torch.isnan(env.scene[robot_cfg.name].data.root_quat_w)
+ nan_pos = torch.isnan(wp.to_torch(env.scene[robot_cfg.name].data.root_pos_w))
+ nan_quat = torch.isnan(wp.to_torch(env.scene[robot_cfg.name].data.root_quat_w))
return torch.logical_or(torch.any(nan_pos, dim=1), torch.any(nan_quat, dim=1))
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/mdp/utils.py b/compass/rl_env/exts/mobility_es/mobility_es/mdp/utils.py
index 15a0d92..db9a5cb 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/mdp/utils.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/mdp/utils.py
@@ -16,6 +16,7 @@
from __future__ import annotations
import torch
+import warp as wp
from typing import TYPE_CHECKING
import isaaclab.utils.math as math_utils
@@ -38,7 +39,7 @@ def goal_pose_in_robot_frame(
# Compute offset.
robot = env.scene[robot_cfg.name]
- robot_yaw = math_utils.euler_xyz_from_quat(robot.data.root_quat_w)[2].reshape(
+ robot_yaw = math_utils.euler_xyz_from_quat(wp.to_torch(robot.data.root_quat_w))[2].reshape(
(goal_pose.shape[0], 1))
offset_vec = torch.cat([
offset[0] * torch.cos(robot_yaw) - offset[1] * torch.sin(robot_yaw),
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/utils/__init__.py b/compass/rl_env/exts/mobility_es/mobility_es/utils/__init__.py
index 7ab23ee..3159bfe 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/utils/__init__.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/utils/__init__.py
@@ -12,4 +12,3 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
diff --git a/compass/rl_env/exts/mobility_es/mobility_es/utils/occupancy_map.py b/compass/rl_env/exts/mobility_es/mobility_es/utils/occupancy_map.py
index a0f0107..a864a5d 100644
--- a/compass/rl_env/exts/mobility_es/mobility_es/utils/occupancy_map.py
+++ b/compass/rl_env/exts/mobility_es/mobility_es/utils/occupancy_map.py
@@ -46,6 +46,19 @@ def __init__(self, cfg):
yaml_file_path = val
break
+ # Fallback: when OMAP_PATHS has no entry for the scene, look for an
+ # auto-generated map at /omap/occupancy_map.yaml — this is
+ # where scripts/generate_omap_from_usd.py emits its output by default.
+ # Skipped when the scene uses MultiUsdFileCfg (no single USD path).
+ if yaml_file_path is None:
+ spawn_cfg = getattr(cfg.environment, "spawn", None)
+ usd_path = getattr(spawn_cfg, "usd_path", None) if spawn_cfg is not None else None
+ if isinstance(usd_path, str) and usd_path:
+ candidate = os.path.join(os.path.dirname(usd_path), "omap", "occupancy_map.yaml")
+ if os.path.exists(candidate):
+ yaml_file_path = candidate
+ print(f"Auto-discovered omap sibling of USD: {candidate}")
+
if yaml_file_path and os.path.exists(yaml_file_path):
print(f'Loaded omap for env {env_prim_path}')
self._load_grid_map(yaml_file_path)
diff --git a/compass/rl_env/exts/mobility_es/pyproject.toml b/compass/rl_env/exts/mobility_es/pyproject.toml
new file mode 100644
index 0000000..8d32633
--- /dev/null
+++ b/compass/rl_env/exts/mobility_es/pyproject.toml
@@ -0,0 +1,3 @@
+[build-system]
+requires = ["setuptools>=45", "wheel", "toml"]
+build-backend = "setuptools.build_meta"
diff --git a/compass/rl_env/exts/mobility_es/setup.py b/compass/rl_env/exts/mobility_es/setup.py
index 20f6343..f320a04 100644
--- a/compass/rl_env/exts/mobility_es/setup.py
+++ b/compass/rl_env/exts/mobility_es/setup.py
@@ -12,7 +12,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Installation script for the 'mobility_es' python package."""
import os
diff --git a/compass/rl_env/scripts/__init__.py b/compass/rl_env/scripts/__init__.py
index 7ab23ee..3159bfe 100644
--- a/compass/rl_env/scripts/__init__.py
+++ b/compass/rl_env/scripts/__init__.py
@@ -12,4 +12,3 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
diff --git a/compass/utils/logger.py b/compass/utils/logger.py
index b53a428..f9c3904 100644
--- a/compass/utils/logger.py
+++ b/compass/utils/logger.py
@@ -12,7 +12,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""
Flexible logging system that supports both Weights & Biases and TensorBoard.
"""
diff --git a/dev_env_plan.md b/dev_env_plan.md
new file mode 100644
index 0000000..7cb0d0c
--- /dev/null
+++ b/dev_env_plan.md
@@ -0,0 +1,177 @@
+# Docker-as-venv dev environment plan
+
+> Quality-of-life follow-up to the COMPASS 2.0 release. Live shape of the work
+> is in this file; tracker entry is in `release_tracker.md` § 7.
+
+## Context
+
+Pre-PR-7 first-run UX is **6–8 manual steps and ~30–60 min**: clone Isaac Lab,
+checkout `v3.0.0-beta1`, `./isaaclab.sh --install`, set `ISAACLAB_PATH`, create
+a venv, `pip install -r requirements.txt` through the wrapper, install the
+X-Mobility wheel, download the X-Mobility checkpoint, download `compass_usds.zip`
+and unzip. The bare-metal path also breaks on the wrong host Python / stale
+Vulkan SDK.
+
+PR-1 (`liuw/isaaclab_3.0_migration`) already bakes those installs into
+`docker/Dockerfile.rl`, so the *image* is one-step ready. PR-7 fills in the
+host-facing UX.
+
+**Goal:** cut first-run UX to **"3 commands, ~3 min after the image build"**
+**and** make the steady-state dev loop feel like a Python venv — host-side
+editor, host-side shell, but every `python`/`pip`/`tensorboard` invocation
+transparently routed through the container.
+
+## Three-layer dev model
+
+```
+Host shell ──► shim PATH ──► docker exec ──► daemon container
+(your editor, (auto-set by (compass-rl image,
+ your terminal, `source docker/activate`) repo bind-mounted at
+ your prompt) /workspace/COMPASS)
+```
+
+`source docker/activate` brings up a long-running daemon container if needed,
+prepends a tmp shim dir to `PATH`, and rewrites `PS1` to show `(compass-rl)`.
+The shims (`python`, `pip`, `isaaclab.sh`, `tensorboard`, `pytest`, `yapf`,
+`pylint`, `pre-commit`) each `docker exec` the same-named binary inside the
+container, with the host CWD translated to the container path. `deactivate`
+reverts PATH/PS1 and removes the shim dir; the container keeps running until
+`./docker/run.sh down`.
+
+## Layout
+
+```
+COMPASS/
+├── docker/
+│ ├── Dockerfile.rl # +5 lines vs PR-1: WORKDIR /workspace/COMPASS, python wrapper
+│ ├── Dockerfile.distillation
+│ ├── run.sh # build/assets/up/down/exec/shell/status
+│ ├── activate # source me; shim PATH + (compass-rl) prompt
+│ ├── prepare_assets.sh # HF downloader (USDs + X-Mobility ckpt)
+│ └── README.md # subcommand reference + troubleshooting
+├── osmo/ # unchanged (uses the same image, different launcher)
+└── README.md # Quick Start leads with ./docker/run.sh
+```
+
+Everything Docker-related lives under `docker/`. No new top-level dir, no
+`run.sh`-vs-`run.py` confusion at the repo root.
+
+## Elegance: one bind-mount covers everything
+
+Single source of truth for mount + env args is `_compass_run_args()` inside
+`docker/run.sh`. The complete list:
+
+```bash
+-v "${REPO_ROOT}:/workspace/COMPASS" # repo (covers code + configs + ./assets/)
+-v "/tmp/.X11-unix:/tmp/.X11-unix:rw" # X server socket
+-v "${HOME}/.cache/compass/kit:/isaac-sim/kit/cache" # writable shader cache
+-e HOME=/workspace/COMPASS # routes pip / pre-commit / hf caches into the bind-mount
+-e DISPLAY=$DISPLAY
+-e WANDB_API_KEY=$WANDB_API_KEY
+-e HF_TOKEN=$HF_TOKEN
+-e ACCEPT_EULA=Y
+-e OMNI_KIT_ALLOW_ROOT=1
+--gpus all
+--net=host
+--user "$(id -u):$(id -g)"
+--passwd-entry "$(id -un):x:$(id -u):$(id -g):COMPASS dev:/workspace/COMPASS:/bin/bash"
+--workdir /workspace/COMPASS
+```
+
+That's it: **three bind-mounts, six env vars**. Compare to
+`robotic_grounding/workflow/run.sh:101-218` which mounts ~10 paths individually
+because it isn't structured around a single repo root.
+
+### Why `/workspace/COMPASS` instead of `/workspace`
+
+The base image (`nvcr.io/nvidia/isaac-lab:3.0.0-beta1`) already places Isaac Lab
+at `/workspace/isaaclab`. Bind-mounting `$(pwd) → /workspace` would shadow it.
+Mounting at `/workspace/COMPASS` keeps `/workspace/isaaclab` accessible at its
+expected `${ISAACLAB_PATH}` path while still putting the host repo at a stable
+location inside the container.
+
+## Container naming
+
+```bash
+COMPASS_CONTAINER="compass-$(id -un)-$(printf '%s' "${REPO_ROOT}" | sha1sum | cut -c1-8)"
+```
+
+Hash of the absolute repo path → multiple checkouts of COMPASS coexist without
+colliding, and the same checkout always lands on the same container name.
+
+## `python` wrapper (Dockerfile.rl change)
+
+`isaaclab.sh` is a Python CLI (it `exec`s `python -c "from isaaclab.cli import cli; cli()" "$@"`),
+so symlinking `python → isaaclab.sh` would put you inside the CLI rather than at
+a Python prompt. Instead the Dockerfile installs a real wrapper:
+
+```dockerfile
+RUN printf '#!/usr/bin/env bash\nexec "${ISAACLAB_PATH}/_isaac_sim/python.sh" "$@"\n' \
+ > /usr/local/bin/python \
+ && chmod +x /usr/local/bin/python \
+ && ln -sf /usr/local/bin/python /usr/local/bin/python3
+```
+
+Now `python run.py` inside the container resolves directly to Isaac Sim's
+bundled `python.sh`, bypassing the CLI overhead and matching what
+`isaaclab.sh -p` would have done.
+
+## Git workflow
+
+`git` itself runs **on the host** — no shim. Repo is on host, SSH/GPG keys are
+on host, `git commit -s` (DCO) and `git push` work without extra plumbing.
+File ownership stays consistent because the container runs as
+`--user "$(id -u):$(id -g)"`.
+
+The wrinkle: pre-commit hooks (yapf, pylint, clang-format) live in the
+container's Python, not on the host. So:
+
+- **Activate before committing.** `pre-commit` is in the shim list, so when
+ host `git commit -s` invokes it via PATH, the shim routes the hook into the
+ container.
+- **Hook-env cache** lives at `./.cache/pre-commit/` (inside the bind-mount),
+ surviving `down` + `up`. `.cache/` is gitignored.
+
+## Files
+
+| Path | Status | Why |
+|------|--------|-----|
+| `docker/run.sh` | NEW | Subcommand wrapper around `docker {build,run,exec,rm}`; single source of truth for mount/env args |
+| `docker/activate` | NEW | Sourced; shim PATH, PS1 prefix, `deactivate` |
+| `docker/prepare_assets.sh` | NEW | HF downloader (USDs + X-Mobility ckpt) |
+| `docker/README.md` | NEW | Subcommand reference + troubleshooting |
+| `docker/Dockerfile.rl` | MODIFIED | `WORKDIR /workspace/COMPASS`; install paths under `/workspace/COMPASS`; `python`/`python3` wrapper |
+| `.dockerignore` | MODIFIED | Add `./assets/`, `./.cache/`, `./.git/` |
+| `.gitignore` | MODIFIED | Add `/assets/`, `/.cache/` |
+| `README.md` | MODIFIED | Quick Start leads with `./docker/run.sh` + `source ./docker/activate`; bare-metal moves under "Manual install" |
+| `release_tracker.md` | MODIFIED | Item #7 status flipped 🟡; checklist progress |
+
+## Branch + commit
+
+- Branch `liuw/dev_environment`, off `liuw/auto_omap_from_usd` (PR-5 head, latest
+ in the stack).
+- Single squashed DCO-signed commit titled
+ "Add Docker-as-venv dev environment (`docker/run.sh` + `docker/activate`)".
+
+## Verification
+
+1. **`./docker/run.sh build`** — image builds; `docker images | grep compass-rl` shows the tag.
+2. **`./docker/run.sh assets`** — fresh `./assets/` dir gets `usd/` and `x_mobility.ckpt`; second run is a no-op.
+3. **`./docker/run.sh up`** — daemon container starts; `./docker/run.sh status` reports `running` with the path-hashed name.
+4. **`source ./docker/activate`** — prompt becomes `(compass-rl) …`; `which python` resolves to the shim dir; `python -V` reports Isaac Sim's bundled Python.
+5. **CWD translation** — `cd compass/rl_env/exts/mobility_es && python -c 'import os; print(os.getcwd())'` prints `/workspace/COMPASS/compass/rl_env/exts/mobility_es`.
+6. **End-to-end smoke** — from the activated shell:
+ `python run.py -c configs/train_config.gin -o /tmp/out -b ./assets/x_mobility.ckpt --num_envs 1 --enable_camera --headless` reaches first PPO iteration.
+7. **`deactivate`** — prompt + PATH revert; shim dir removed from `/tmp`.
+8. **`./docker/run.sh down`** — container removed; `docker ps -a | grep compass-` returns nothing.
+9. **OSMO compatibility** — `osmo/run_osmo.py train ... --image ` still works.
+10. **Pre-commit clean (activated shell)** — `pre-commit run --files docker/run.sh docker/activate docker/prepare_assets.sh docker/README.md docker/Dockerfile.rl README.md`.
+11. **Git commit signs cleanly** — `git commit -s -m "test" --allow-empty` from an activated shell completes; resulting commit shows DCO trailer.
+
+## Out of scope
+
+- Replacing `osmo/run_osmo.py` — different concern; same image.
+- Removing the bare-metal install in `compass/rl_env/README.md` — kept for non-Docker users.
+- `docker compose` — single container, single image; compose adds a dep without UX gain.
+- VSCode `.devcontainer` — orthogonal; works alongside the activate model.
+- Pushing branches / opening PRs — held per current standing instruction.
diff --git a/docker/Dockerfile.rl b/docker/Dockerfile.rl
index 04b3166..77f71c8 100644
--- a/docker/Dockerfile.rl
+++ b/docker/Dockerfile.rl
@@ -1,5 +1,26 @@
-FROM nvcr.io/nvidia/isaac-lab:2.1.0
+FROM nvcr.io/nvidia/isaac-lab:3.0.0-beta1
-WORKDIR /workspace
+# Omniverse runtime env (required for any kit / pip step run as root in the container).
+ENV ACCEPT_EULA=Y
+ENV OMNI_KIT_ALLOW_ROOT=1
-COPY . /workspace
+# COMPASS lives in /workspace/COMPASS so /workspace/isaaclab (from the base image)
+# is preserved when docker/run.sh bind-mounts the host repo at runtime.
+WORKDIR /workspace/COMPASS
+
+COPY . /workspace/COMPASS
+
+# Install COMPASS dependencies, the X-Mobility wheel, and the mobility_es Isaac Lab extension
+# into Isaac Lab's bundled Python environment.
+RUN ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -r /workspace/COMPASS/requirements.txt \
+ && ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install /workspace/COMPASS/x_mobility/x_mobility-0.1.0-py3-none-any.whl \
+ && ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -e /workspace/COMPASS/compass/rl_env/exts/mobility_es
+
+# Provide a `python` / `python3` on PATH that runs Isaac Lab's bundled Python directly.
+# `docker/activate` on the host shims host-side `python` to `docker exec ... python`,
+# so a host-side `python run.py` ends up as Isaac Sim's python.sh executing run.py
+# — no `${ISAACLAB_PATH}/isaaclab.sh -p` boilerplate at any call site.
+RUN printf '#!/usr/bin/env bash\nexec "${ISAACLAB_PATH}/_isaac_sim/python.sh" "$@"\n' \
+ > /usr/local/bin/python \
+ && chmod +x /usr/local/bin/python \
+ && ln -sf /usr/local/bin/python /usr/local/bin/python3
diff --git a/docker/activate b/docker/activate
new file mode 100644
index 0000000..b4f25d6
--- /dev/null
+++ b/docker/activate
@@ -0,0 +1,132 @@
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Source this file (don't execute it) for a Python-venv-like dev experience
+# that runs commands inside the COMPASS docker container.
+#
+# source ./docker/activate # sets up shim PATH + (compass-rl) prompt prefix
+# python run.py … # actually runs inside the container
+# deactivate # revert
+#
+# What it does:
+# 1. Ensures the container is running (./docker/run.sh up).
+# 2. Generates a tmp dir of shim scripts for python / pip / etc. and prepends
+# it to PATH. Each shim `docker exec`s the same-named binary inside the
+# container, with the host CWD translated to the container path.
+# 3. Adds a `(compass-rl) ` prefix to PS1 so you know you're activated.
+# 4. Defines a `deactivate` function to revert (1)-(3) and clean up the shim dir.
+#
+# The container itself keeps running until you call `./docker/run.sh down`.
+# `deactivate` only tears down the shim PATH; multiple shells can be activated
+# against the same container concurrently.
+
+# Detect the directory containing this script. Works under bash (BASH_SOURCE)
+# and zsh (use ${(%):-%N} fallback — sourced filename).
+if [ -n "${BASH_SOURCE:-}" ]; then
+ _compass_activate_path="${BASH_SOURCE[0]}"
+elif [ -n "${ZSH_VERSION:-}" ]; then
+ # shellcheck disable=SC2296
+ _compass_activate_path="${(%):-%N}"
+else
+ echo "[activate] Unsupported shell: source from bash or zsh" >&2
+ return 1 2>/dev/null || exit 1
+fi
+_COMPASS_REPO_ROOT="$(cd "$(dirname "${_compass_activate_path}")/.." && pwd)"
+unset _compass_activate_path
+
+# Path the host repo is bind-mounted to inside the container — must match
+# CONT_REPO_DIR in docker/run.sh.
+_COMPASS_CONT_REPO_DIR="/workspace/COMPASS"
+
+# Pull container name + image tag from run.sh so the two stay in sync.
+_COMPASS_CONTAINER="$(
+ REPO_ROOT="${_COMPASS_REPO_ROOT}" bash -c '
+ cd "${REPO_ROOT}"
+ repo_hash=$(printf "%s" "${REPO_ROOT}" | sha1sum | cut -c1-8)
+ echo "compass-$(id -un)-${repo_hash}"
+ '
+)"
+
+# Bring the container up if it isn't already.
+if ! "${_COMPASS_REPO_ROOT}/docker/run.sh" up; then
+ echo "[activate] Failed to bring up container; aborting." >&2
+ unset _COMPASS_REPO_ROOT _COMPASS_CONTAINER
+ return 1 2>/dev/null || exit 1
+fi
+
+# Tmp shim dir, removed by `deactivate`.
+_COMPASS_SHIM_DIR="$(mktemp -d "${TMPDIR:-/tmp}/compass-shims.XXXXXX")"
+
+# Shimmed commands. To add another tool, append it here — no other wiring needed.
+_compass_shim_cmds=(
+ python python3
+ pip pip3
+ isaaclab.sh
+ tensorboard
+ pytest
+ yapf pylint
+ pre-commit
+)
+
+# Generate one shim script per command. Each is a tiny bash wrapper that
+# translates the host CWD into the container path before exec'ing.
+for _cmd in "${_compass_shim_cmds[@]}"; do
+ cat > "${_COMPASS_SHIM_DIR}/${_cmd}" <&2; }
+step() { echo -e "${BLUE}[STEP]${NC} $*"; }
+
+# ──────────────────────────────────────────────────────────────────────────────
+# Defaults.
+# ──────────────────────────────────────────────────────────────────────────────
+REPO_ROOT="$(cd "$(dirname "${BASH_SOURCE[0]}")/.." && pwd)"
+CACHE_DIR="${REPO_ROOT}/assets"
+HF_TOKEN_ARG=""
+FORCE=false
+
+USDS_URL="https://huggingface.co/nvidia/COMPASS/resolve/main/compass_usds.zip"
+USDS_ZIP="${CACHE_DIR}/compass_usds.zip"
+USDS_DIR="${CACHE_DIR}/usd"
+
+CKPT_URL="https://huggingface.co/nvidia/X-Mobility/resolve/main/x_mobility-nav2-semantic_action_path.ckpt"
+CKPT_FILE="${CACHE_DIR}/x_mobility.ckpt"
+
+# ──────────────────────────────────────────────────────────────────────────────
+# Argument parsing.
+# ──────────────────────────────────────────────────────────────────────────────
+usage() {
+ sed -n '5,15p' "${BASH_SOURCE[0]}" | sed 's/^# \?//'
+ exit "${1:-0}"
+}
+while [ "$#" -gt 0 ]; do
+ case "$1" in
+ --hf-token) HF_TOKEN_ARG="$2"; shift 2 ;;
+ --cache-dir)
+ CACHE_DIR="$2"
+ USDS_ZIP="${CACHE_DIR}/compass_usds.zip"
+ USDS_DIR="${CACHE_DIR}/usd"
+ CKPT_FILE="${CACHE_DIR}/x_mobility.ckpt"
+ shift 2
+ ;;
+ --force) FORCE=true; shift ;;
+ -h|--help) usage 0 ;;
+ *) error "Unknown flag: $1"; usage 2 ;;
+ esac
+done
+
+HF_TOKEN_EFFECTIVE="${HF_TOKEN_ARG:-${HF_TOKEN:-}}"
+
+# ──────────────────────────────────────────────────────────────────────────────
+# Steps.
+# ──────────────────────────────────────────────────────────────────────────────
+check_hf_token() {
+ if [ -z "${HF_TOKEN_EFFECTIVE}" ]; then
+ error "HF_TOKEN not set. The COMPASS HuggingFace repo is gated."
+ error ""
+ error "To fix:"
+ error " 1. Request access at https://huggingface.co/nvidia/COMPASS"
+ error " 2. Get a token at https://huggingface.co/settings/tokens"
+ error " 3. export HF_TOKEN=hf_xxx (or pass --hf-token hf_xxx)"
+ exit 1
+ fi
+ info "HuggingFace token found."
+}
+
+check_downloader() {
+ if command -v curl >/dev/null 2>&1; then
+ DOWNLOADER=curl
+ elif command -v wget >/dev/null 2>&1; then
+ DOWNLOADER=wget
+ else
+ error "Neither curl nor wget is installed. Install one of them and re-run."
+ exit 1
+ fi
+}
+
+# Args: $1=URL $2=destination path
+hf_download() {
+ local url="$1" dst="$2"
+ case "${DOWNLOADER}" in
+ curl)
+ curl -L --fail --progress-bar \
+ -H "Authorization: Bearer ${HF_TOKEN_EFFECTIVE}" \
+ -o "${dst}" "${url}"
+ ;;
+ wget)
+ wget --progress=bar:force \
+ --header="Authorization: Bearer ${HF_TOKEN_EFFECTIVE}" \
+ -O "${dst}" "${url}"
+ ;;
+ esac
+}
+
+prepare_dirs() {
+ step "Creating ${CACHE_DIR}"
+ mkdir -p "${CACHE_DIR}"
+}
+
+download_usds() {
+ if [ "${FORCE}" = true ]; then
+ rm -rf "${USDS_DIR}" "${USDS_ZIP}"
+ fi
+ if [ -d "${USDS_DIR}" ] && [ -n "$(ls -A "${USDS_DIR}" 2>/dev/null)" ]; then
+ info "USDs already extracted at ${USDS_DIR} — skipping."
+ return 0
+ fi
+
+ step "Downloading compass_usds.zip → ${USDS_ZIP}"
+ check_hf_token
+ hf_download "${USDS_URL}" "${USDS_ZIP}"
+ if [ ! -s "${USDS_ZIP}" ]; then
+ error "Downloaded compass_usds.zip is empty. Check your HF_TOKEN and access."
+ rm -f "${USDS_ZIP}"
+ exit 1
+ fi
+
+ step "Unzipping → ${USDS_DIR}"
+ if ! command -v unzip >/dev/null 2>&1; then
+ error "unzip is not installed. Install it (e.g. apt-get install unzip)."
+ exit 1
+ fi
+ mkdir -p "${USDS_DIR}"
+ unzip -q -o "${USDS_ZIP}" -d "${USDS_DIR}"
+ info "USDs extracted to ${USDS_DIR}"
+}
+
+download_ckpt() {
+ if [ "${FORCE}" = true ]; then rm -f "${CKPT_FILE}"; fi
+ if [ -s "${CKPT_FILE}" ]; then
+ info "X-Mobility checkpoint already present at ${CKPT_FILE} — skipping."
+ return 0
+ fi
+
+ step "Downloading X-Mobility ckpt → ${CKPT_FILE}"
+ # X-Mobility ckpt isn't always gated, but pass the token anyway — works in both cases.
+ if [ -z "${HF_TOKEN_EFFECTIVE}" ]; then
+ warn "HF_TOKEN not set; trying anonymous download (may fail if gated)."
+ fi
+ if [ -n "${HF_TOKEN_EFFECTIVE}" ]; then
+ hf_download "${CKPT_URL}" "${CKPT_FILE}"
+ else
+ case "${DOWNLOADER}" in
+ curl) curl -L --fail --progress-bar -o "${CKPT_FILE}" "${CKPT_URL}" ;;
+ wget) wget --progress=bar:force -O "${CKPT_FILE}" "${CKPT_URL}" ;;
+ esac
+ fi
+ if [ ! -s "${CKPT_FILE}" ]; then
+ error "Downloaded ckpt is empty. Check your HF_TOKEN and network."
+ rm -f "${CKPT_FILE}"
+ exit 1
+ fi
+ info "Downloaded $(du -h "${CKPT_FILE}" | cut -f1) → ${CKPT_FILE}"
+}
+
+show_summary() {
+ step "Asset summary"
+ echo "Cache dir: ${CACHE_DIR}"
+ if [ -d "${USDS_DIR}" ] && [ -n "$(ls -A "${USDS_DIR}" 2>/dev/null)" ]; then
+ echo " ✓ USDs: ${USDS_DIR} ($(du -sh "${USDS_DIR}" | cut -f1))"
+ else
+ echo " ✗ USDs: ${USDS_DIR} (missing)"
+ fi
+ if [ -s "${CKPT_FILE}" ]; then
+ echo " ✓ X-Mobility ckpt: ${CKPT_FILE} ($(du -h "${CKPT_FILE}" | cut -f1))"
+ else
+ echo " ✗ X-Mobility ckpt: ${CKPT_FILE} (missing)"
+ fi
+ echo ""
+ echo "These paths are bind-mounted into the container at:"
+ echo " /workspace/assets/usd"
+ echo " /workspace/assets/x_mobility.ckpt"
+}
+
+main() {
+ info "COMPASS asset preparation"
+ info "========================="
+ check_downloader
+ prepare_dirs
+ download_usds
+ download_ckpt
+ show_summary
+ info "Done."
+}
+
+main "$@"
diff --git a/docker/run.sh b/docker/run.sh
new file mode 100755
index 0000000..a82472a
--- /dev/null
+++ b/docker/run.sh
@@ -0,0 +1,224 @@
+#!/usr/bin/env bash
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Manage the COMPASS docker dev container.
+#
+# Usage:
+# ./docker/run.sh build [tag] # build the image (default tag: latest)
+# ./docker/run.sh assets [--hf-token TOK] # download USDs + X-Mobility ckpt to ./assets
+# ./docker/run.sh up # idempotent: start daemon container if not running
+# ./docker/run.sh down # docker rm -f the container
+# ./docker/run.sh exec [...] # one-shot exec inside the running container
+# ./docker/run.sh shell # escape hatch: drop into bash inside the container
+# ./docker/run.sh status # show container + image state
+#
+# Companion: `source ./docker/activate` for a Python-venv-like dev experience.
+
+set -eu
+
+# Repo root: the dir containing this script's parent (docker/run.sh → COMPASS/).
+REPO_ROOT="$(cd "$(dirname "${BASH_SOURCE[0]}")/.." && pwd)"
+
+# Image tag. Override via `./docker/run.sh build mytag` then `COMPASS_IMAGE_TAG=mytag ./docker/run.sh up`.
+IMAGE_TAG="${COMPASS_IMAGE_TAG:-latest}"
+IMAGE_NAME="compass-rl:${IMAGE_TAG}"
+
+# Container name = "compass--<8-hex of repo path>". Hashing the absolute repo
+# path means multiple checkouts of COMPASS coexist without colliding, and the same
+# checkout always lands on the same container across shells / reboots.
+_REPO_HASH="$(printf '%s' "${REPO_ROOT}" | sha1sum | cut -c1-8)"
+CONTAINER_NAME="compass-$(id -un)-${_REPO_HASH}"
+
+# Writable shader cache lives outside the repo so a `git clean` doesn't nuke it.
+KIT_CACHE_DIR="${HOME}/.cache/compass/kit"
+
+# ──────────────────────────────────────────────────────────────────────────────
+# Output helpers (lifted from ros2_deployment/prepare_assets.sh).
+# ──────────────────────────────────────────────────────────────────────────────
+GREEN='\033[0;32m'; YELLOW='\033[1;33m'; RED='\033[0;31m'; BLUE='\033[0;34m'; NC='\033[0m'
+info() { echo -e "${GREEN}[INFO]${NC} $*"; }
+warn() { echo -e "${YELLOW}[WARNING]${NC} $*"; }
+error() { echo -e "${RED}[ERROR]${NC} $*" >&2; }
+step() { echo -e "${BLUE}[STEP]${NC} $*"; }
+
+# ──────────────────────────────────────────────────────────────────────────────
+# Single source of truth for `docker run` flags. Used by `up`.
+# Keep the mount list minimal — the repo bind-mount covers code + configs +
+# assets, so we only add X11 socket forwarding and the kit shader cache.
+# ──────────────────────────────────────────────────────────────────────────────
+CONT_REPO_DIR="/workspace/COMPASS"
+
+_compass_run_args() {
+ mkdir -p "${KIT_CACHE_DIR}"
+ local args=(
+ --name "${CONTAINER_NAME}"
+ --gpus all
+ --net=host
+ --user "$(id -u):$(id -g)"
+ # Isaac Sim's install at /isaac-sim is mode drwxr-x--- with group
+ # `isaac-sim` (GID 1234 in the base image). Adding our host user to
+ # that group at runtime is the minimal way to grant access without
+ # modifying the base image.
+ --group-add 1234
+ # Repo bind-mount overrides the COPY in Dockerfile.rl so host edits hot-reload.
+ # Path is /workspace/COMPASS to leave /workspace/isaaclab (Isaac Lab installation,
+ # from the base image) intact and accessible.
+ -v "${REPO_ROOT}:${CONT_REPO_DIR}"
+ -v "/tmp/.X11-unix:/tmp/.X11-unix:rw"
+ -v "${KIT_CACHE_DIR}:/isaac-sim/kit/cache"
+ # HOME=/workspace/COMPASS puts pip / pre-commit / huggingface caches under
+ # the bind-mount so they survive `down` + `up`. Caches land in ./.cache/
+ # which is gitignored.
+ -e "HOME=${CONT_REPO_DIR}"
+ -e "DISPLAY=${DISPLAY:-}"
+ -e "WANDB_API_KEY=${WANDB_API_KEY:-}"
+ -e "HF_TOKEN=${HF_TOKEN:-}"
+ # Already ENV in Dockerfile.rl; redundant flags are harmless and explicit.
+ -e "ACCEPT_EULA=Y"
+ -e "OMNI_KIT_ALLOW_ROOT=1"
+ # Bind-mount host /etc/passwd + /etc/group read-only so the container
+ # resolves $(id -u)/$(id -g) to a real username. Without this, NSS
+ # lookups inside the container (huggingface_hub, getpass.getuser, …)
+ # fall over with "no passwd entry for uid …".
+ -v "/etc/passwd:/etc/passwd:ro"
+ -v "/etc/group:/etc/group:ro"
+ --workdir "${CONT_REPO_DIR}"
+ --detach
+ )
+ printf '%s\n' "${args[@]}"
+}
+
+# ──────────────────────────────────────────────────────────────────────────────
+# Subcommands.
+# ──────────────────────────────────────────────────────────────────────────────
+cmd_build() {
+ local tag="${1:-${IMAGE_TAG}}"
+ step "Building ${IMAGE_NAME/:*/:${tag}} from docker/Dockerfile.rl"
+ cd "${REPO_ROOT}"
+ docker build --network=host -f docker/Dockerfile.rl -t "compass-rl:${tag}" .
+ info "Build complete: compass-rl:${tag}"
+}
+
+cmd_assets() {
+ "${REPO_ROOT}/docker/prepare_assets.sh" "$@"
+}
+
+cmd_up() {
+ if docker ps --format '{{.Names}}' | grep -qx "${CONTAINER_NAME}"; then
+ info "Container already running: ${CONTAINER_NAME}"
+ return 0
+ fi
+ if docker ps -a --format '{{.Names}}' | grep -qx "${CONTAINER_NAME}"; then
+ # Stopped container with the same name — start it back up.
+ step "Restarting existing container: ${CONTAINER_NAME}"
+ docker start "${CONTAINER_NAME}" >/dev/null
+ info "Container running: ${CONTAINER_NAME}"
+ return 0
+ fi
+
+ if ! docker image inspect "${IMAGE_NAME}" >/dev/null 2>&1; then
+ error "Image ${IMAGE_NAME} not found. Run: ./docker/run.sh build"
+ exit 1
+ fi
+
+ step "Starting container: ${CONTAINER_NAME} (image: ${IMAGE_NAME})"
+ # Allow X11 connections from the docker user (no-op if no X server / xhost).
+ xhost +SI:localuser:"$(id -un)" >/dev/null 2>&1 || true
+
+ # Override the image's entrypoint (Isaac Sim's runheadless.sh) with `sleep
+ # infinity` so the container stays alive as a passive shell host. We exec
+ # actual commands via `docker exec`. `--entrypoint` accepts only the
+ # executable; the image arg becomes the first positional argument.
+ local args=()
+ while IFS= read -r line; do args+=("$line"); done < <(_compass_run_args)
+ args+=(--entrypoint /bin/sleep)
+ docker run "${args[@]}" "${IMAGE_NAME}" infinity >/dev/null
+ info "Container running: ${CONTAINER_NAME}"
+}
+
+cmd_down() {
+ if ! docker ps -a --format '{{.Names}}' | grep -qx "${CONTAINER_NAME}"; then
+ info "No container to stop: ${CONTAINER_NAME}"
+ return 0
+ fi
+ step "Removing container: ${CONTAINER_NAME}"
+ docker rm -f "${CONTAINER_NAME}" >/dev/null
+ info "Container removed."
+}
+
+cmd_exec() {
+ if [ "$#" -eq 0 ]; then
+ error "Usage: ./docker/run.sh exec [args...]"
+ exit 2
+ fi
+ cmd_up >/dev/null # Lazy up: don't make the user remember.
+ # CWD translation: if the host CWD is inside the repo, mirror the same
+ # subdirectory inside the container so relative paths work.
+ local host_pwd cont_pwd
+ host_pwd="$(pwd)"
+ case "${host_pwd}" in
+ "${REPO_ROOT}"|"${REPO_ROOT}"/*)
+ cont_pwd="${CONT_REPO_DIR}${host_pwd#${REPO_ROOT}}"
+ ;;
+ *)
+ cont_pwd="${CONT_REPO_DIR}"
+ ;;
+ esac
+ # Add -t only when stdin AND stdout are a terminal — `docker exec -t`
+ # against a non-tty stdin errors with "cannot attach stdin to a TTY-enabled".
+ local exec_flags="-i"
+ if [ -t 0 ] && [ -t 1 ]; then exec_flags="-it"; fi
+ exec docker exec ${exec_flags} -w "${cont_pwd}" "${CONTAINER_NAME}" "$@"
+}
+
+cmd_shell() {
+ cmd_up >/dev/null
+ local exec_flags="-i"
+ if [ -t 0 ] && [ -t 1 ]; then exec_flags="-it"; fi
+ exec docker exec ${exec_flags} -w "${CONT_REPO_DIR}" "${CONTAINER_NAME}" bash
+}
+
+cmd_status() {
+ echo "Image: ${IMAGE_NAME}"
+ if docker image inspect "${IMAGE_NAME}" >/dev/null 2>&1; then
+ echo "Image OK: $(docker image inspect "${IMAGE_NAME}" --format '{{.Id}} ({{.Created}})')"
+ else
+ echo "Image OK: (not built — run ./docker/run.sh build)"
+ fi
+ echo "Container: ${CONTAINER_NAME}"
+ if docker ps --format '{{.Names}}' | grep -qx "${CONTAINER_NAME}"; then
+ echo "State: running"
+ elif docker ps -a --format '{{.Names}}' | grep -qx "${CONTAINER_NAME}"; then
+ echo "State: stopped"
+ else
+ echo "State: absent"
+ fi
+ echo "Repo root: ${REPO_ROOT}"
+ echo "Kit cache: ${KIT_CACHE_DIR}"
+}
+
+usage() {
+ sed -n '5,16p' "${BASH_SOURCE[0]}" | sed 's/^# \?//'
+ exit "${1:-0}"
+}
+
+# ──────────────────────────────────────────────────────────────────────────────
+# Dispatch.
+# ──────────────────────────────────────────────────────────────────────────────
+if [ "$#" -eq 0 ]; then usage 2; fi
+SUB="$1"; shift
+case "${SUB}" in
+ build) cmd_build "$@" ;;
+ assets) cmd_assets "$@" ;;
+ up) cmd_up "$@" ;;
+ down) cmd_down "$@" ;;
+ exec) cmd_exec "$@" ;;
+ shell) cmd_shell "$@" ;;
+ status) cmd_status "$@" ;;
+ -h|--help|help) usage 0 ;;
+ *)
+ error "Unknown subcommand: ${SUB}"
+ usage 2
+ ;;
+esac
diff --git a/docs/README.md b/docs/README.md
new file mode 100644
index 0000000..6320093
--- /dev/null
+++ b/docs/README.md
@@ -0,0 +1,61 @@
+# COMPASS docs
+
+Source for everything published at **https://nvlabs.github.io/COMPASS/**.
+
+```
+docs/
+├── project_page/ # academic landing page (Bulma; served at /)
+└── handbook/ # Sphinx + nvidia-sphinx-theme handbook (served at /docs/)
+```
+
+## Local preview
+
+From the repo root, build the handbook and serve it together with the
+academic landing — same layout as production:
+
+```bash
+pip install -r docs/handbook/requirements.txt
+make -C docs/handbook html
+
+mkdir -p /tmp/_site
+cp -r docs/project_page/. /tmp/_site/
+cp -r docs/handbook/_build/html /tmp/_site/docs
+
+python -m http.server -d /tmp/_site 8765
+# / → academic landing
+# /docs/ → handbook
+```
+
+For live-reload while editing handbook pages (handbook only; no academic
+landing):
+
+```bash
+sphinx-autobuild docs/handbook docs/handbook/_build/html --port 8000
+```
+
+## Deploy
+
+Automatic on every push to `main` that touches `docs/**` or
+`.github/workflows/docs.yml`. The workflow at
+[`.github/workflows/docs.yml`](../.github/workflows/docs.yml) installs
+`docs/handbook/requirements.txt`, runs `make html` (which uses
+`sphinx-build -W` so any warning fails the build), stages the academic
+landing at site root, copies the handbook under `/docs/`, and deploys via
+`actions/deploy-pages@v4` — no intermediate `gh-pages` branch.
+
+The legacy `gh_page` branch is a frozen archive only; not built, not deployed.
+
+## Editing tips
+
+- The handbook is **self-contained** — every page owns its content directly.
+ No `{include}` transclusions today, so editing a topic means editing one
+ file under `docs/handbook/`.
+- Each handbook page has an "Edit on GitHub" link in the right-hand sidebar
+ that deep-links to the corresponding markdown source. The `edit_uri` in
+ [`handbook/conf.py`](handbook/conf.py) makes this work.
+- `-W` strict builds catch broken internal links and unresolved
+ cross-references. Preview locally before pushing if you're touching nav
+ structure or relative links.
+- New pages must be referenced from a `{toctree}` directive in
+ [`handbook/index.md`](handbook/index.md), otherwise Sphinx warns about
+ orphan pages.
diff --git a/docs/handbook/Makefile b/docs/handbook/Makefile
new file mode 100644
index 0000000..a2dadc6
--- /dev/null
+++ b/docs/handbook/Makefile
@@ -0,0 +1,15 @@
+SPHINXOPTS ?=
+SPHINXBUILD ?= sphinx-build
+SOURCEDIR = .
+BUILDDIR = _build
+
+.PHONY: help html clean
+
+help:
+ @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS)
+
+html:
+ $(SPHINXBUILD) -W -b html "$(SOURCEDIR)" "$(BUILDDIR)/html" $(SPHINXOPTS)
+
+clean:
+ rm -rf $(BUILDDIR)
diff --git a/docs/handbook/_static/custom.css b/docs/handbook/_static/custom.css
new file mode 100644
index 0000000..3faae32
--- /dev/null
+++ b/docs/handbook/_static/custom.css
@@ -0,0 +1,49 @@
+/* SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. */
+/* SPDX-License-Identifier: Apache-2.0 */
+/* Light brand polish on top of nvidia-sphinx-theme. */
+
+:root {
+ --compass-card-radius: 0.9rem;
+ --compass-card-shadow: 0 12px 32px rgba(0, 0, 0, 0.08);
+ --compass-card-border: rgba(127, 127, 127, 0.2);
+}
+
+/* sphinx-design grid cards on the landing page */
+.sd-card {
+ border-radius: var(--compass-card-radius);
+ border: 1px solid var(--compass-card-border);
+ box-shadow: var(--compass-card-shadow);
+ height: 100%;
+}
+
+.sd-card .sd-card-body {
+ padding: 1.15rem 1.2rem;
+}
+
+.sd-card .sd-card-title {
+ margin-bottom: 0.45rem;
+}
+
+/* Hero lead under the H1 on the landing */
+.hero-lead {
+ font-size: 1.1rem;
+ line-height: 1.6;
+ max-width: 66rem;
+ margin-bottom: 1.25rem;
+}
+
+/* Inline pill chips for "Quick start", "Training", etc. */
+.workflow-pills {
+ margin: 1rem 0 1.4rem;
+}
+
+.workflow-pill {
+ display: inline-block;
+ margin: 0 0.5rem 0.5rem 0;
+ padding: 0.35rem 0.7rem;
+ border-radius: 999px;
+ background: rgba(118, 185, 0, 0.12); /* NVIDIA green tint */
+ color: inherit;
+ font-size: 0.95rem;
+ font-weight: 600;
+}
diff --git a/docs/handbook/agentic.md b/docs/handbook/agentic.md
new file mode 100644
index 0000000..c23bac9
--- /dev/null
+++ b/docs/handbook/agentic.md
@@ -0,0 +1,51 @@
+# Agentic skills
+
+COMPASS ships a Claude Code skill that orchestrates the end-to-end
+training pipeline from natural-language prompts: scene search / download
+(SAGE-10k), USD conversion, scene registration, training launch, and
+optional OSMO submission.
+
+The skill itself lives at
+[`.claude/skills/compass/SKILL.md`](https://github.com/NVlabs/COMPASS/blob/main/.claude/skills/compass/SKILL.md).
+Helper scripts live at
+[`.claude/skills/compass/scripts/`](https://github.com/NVlabs/COMPASS/tree/main/.claude/skills/compass/scripts).
+
+## How it gets invoked
+
+Inside a [Claude Code](https://claude.com/claude-code) session at the COMPASS
+repo root:
+
+```
+/skill compass
+```
+
+…or just describe the task in plain English; Claude Code auto-routes when the
+intent matches the skill's description.
+
+## Capabilities
+
+The skill encapsulates these concrete sub-flows; each is a pre-recorded
+recipe that the agent follows:
+
+- **Scene search** against the SAGE-10k catalogue.
+- **SAGE → USD conversion** via `scripts/sage10k_to_usd.py`.
+- **Scene registration** in
+ [`compass/rl_env/exts/mobility_es/mobility_es/config/environments.py`](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/config/environments.py)
+ and `EnvSceneAssetCfgMap` in `run.py`.
+- **OMap generation** for the new scene (see [Auto OMap from USDs](omap.md)).
+- **Training launch** via `run.py` (or [`osmo/run_osmo.py`](osmo.md) for cloud).
+
+## Auto OMap is the SAGE smoothness win
+
+SAGE-driven scenes don't ship with hand-authored occupancy maps. The
+[auto OMap from USDs](omap.md) generator closes that gap so every new scene
+the agent registers comes with a ready-to-use OMap for collision-free pose
+sampling, with no manual UI step.
+
+## Reading the skill source
+
+Skills are plain markdown with YAML frontmatter. The
+[full `SKILL.md`](https://github.com/NVlabs/COMPASS/blob/main/.claude/skills/compass/SKILL.md)
+documents every sub-flow, the prompts the agent uses, and the verification
+steps it runs. Treat it as the spec for what the agent will do on your
+behalf.
diff --git a/docs/handbook/conf.py b/docs/handbook/conf.py
new file mode 100644
index 0000000..1806767
--- /dev/null
+++ b/docs/handbook/conf.py
@@ -0,0 +1,103 @@
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+"""Sphinx configuration for the COMPASS documentation site."""
+
+from __future__ import annotations
+
+import os
+import sys
+
+# Make the repo root importable so future autodoc / autosummary can find compass.*.
+ROOT = os.path.abspath("../..")
+sys.path.insert(0, ROOT)
+
+# ---------------------------------------------------------------------------
+# Project metadata
+# ---------------------------------------------------------------------------
+
+project = "COMPASS"
+copyright = "2025-2026, NVIDIA"
+author = "NVIDIA"
+
+# Bump alongside CHANGELOG.md / pyproject.toml when we cut a release.
+COMPASS_VERSION = "2.0.0"
+version = COMPASS_VERSION
+release = COMPASS_VERSION
+
+# ---------------------------------------------------------------------------
+# Extensions
+# ---------------------------------------------------------------------------
+
+extensions = [
+ "myst_parser",
+ "sphinx.ext.napoleon",
+ "sphinx.ext.viewcode",
+ "sphinx.ext.intersphinx",
+ "sphinx.ext.todo",
+ "sphinx.ext.githubpages",
+ "sphinx_design",
+ "sphinx_copybutton",
+ "sphinxcontrib.mermaid",
+]
+
+exclude_patterns = ["_build", "Thumbs.db", ".DS_Store", ".venv", "venv"]
+
+# ---------------------------------------------------------------------------
+# MyST (markdown) configuration
+# ---------------------------------------------------------------------------
+
+myst_enable_extensions = [
+ "colon_fence", # ::: directive blocks
+ "deflist", # definition lists
+ "fieldlist", # field lists
+ "tasklist", # GitHub-style task lists
+ "attrs_inline", # {.class} inline attribute syntax
+]
+myst_fence_as_directive = {"mermaid"}
+myst_heading_anchors = 3
+
+# The handbook is self-contained — every page owns its content directly.
+# We deliberately do NOT suppress `myst.xref_missing` or `image.not_readable`
+# so `-W` catches broken intra-handbook links and missing images. If a future
+# {include} of an external README needs those suppressions back, scope them
+# to that page rather than globally.
+
+# ---------------------------------------------------------------------------
+# Intersphinx
+# ---------------------------------------------------------------------------
+
+intersphinx_mapping = {
+ "python": ("https://docs.python.org/3", None),
+}
+
+# ---------------------------------------------------------------------------
+# Theme: nvidia-sphinx-theme
+# https://github.com/NVIDIA/nvidia-sphinx-theme
+# ---------------------------------------------------------------------------
+
+html_theme = "nvidia_sphinx_theme"
+html_title = f"COMPASS Handbook"
+html_show_sphinx = False
+html_theme_options = {
+ "github_url": "https://github.com/NVlabs/COMPASS",
+ "copyright_override": {
+ "start": 2025
+ },
+ "pygments_light_style": "tango",
+ "pygments_dark_style": "monokai",
+}
+
+html_static_path = ["_static"]
+html_css_files = ["custom.css"]
+
+# ---------------------------------------------------------------------------
+# Mermaid (sequence/flow diagrams in markdown)
+# ---------------------------------------------------------------------------
+
+mermaid_version = "11"
+
+# ---------------------------------------------------------------------------
+# Misc
+# ---------------------------------------------------------------------------
+
+todo_include_todos = False
diff --git a/docs/handbook/contributing.md b/docs/handbook/contributing.md
new file mode 100644
index 0000000..4111b13
--- /dev/null
+++ b/docs/handbook/contributing.md
@@ -0,0 +1,31 @@
+# Contributing
+
+The contribution rules — sign-off, commit policy, pre-commit, code style —
+live in
+[`CONTRIBUTING.md`](https://github.com/NVlabs/COMPASS/blob/main/CONTRIBUTING.md):
+
+```{include} ../../CONTRIBUTING.md
+```
+
+## Editing this handbook
+
+Each page in this site has an "Edit on GitHub" button (top right) that
+deep-links to the corresponding markdown source under
+`docs/handbook/`. Edit, push, and the GitHub Actions workflow at
+[`.github/workflows/docs.yml`](https://github.com/NVlabs/COMPASS/blob/main/.github/workflows/docs.yml)
+will re-build and re-deploy automatically on push to `main`.
+
+To preview locally:
+
+```bash
+pip install -r docs/handbook/requirements.txt
+cd docs/handbook && make html
+# Built to _build/html/ — open with any static server:
+python -m http.server -d _build/html 8000
+
+# Or use sphinx-autobuild for live reload while editing:
+sphinx-autobuild . _build/html --port 8000
+```
+
+The handbook builds with `-W` (warnings → errors), so any broken internal
+link or unresolved reference fails CI.
diff --git a/docs/handbook/deployment/isaac_sim.md b/docs/handbook/deployment/isaac_sim.md
new file mode 100644
index 0000000..564aec3
--- /dev/null
+++ b/docs/handbook/deployment/isaac_sim.md
@@ -0,0 +1,264 @@
+# Isaac Sim setup
+
+The deeper-dive companion to the [ROS2 Deployment](ros2.md) overview —
+container build, ROS2 bridge configuration, and the Isaac Sim launch
+recipe.
+
+## Overview
+
+Standalone ROS2 deployment for the COMPASS navigator with Isaac Sim
+integration.
+
+### What's included
+
+[`ros2_deployment/compass_container.py`](https://github.com/NVlabs/COMPASS/blob/main/ros2_deployment/compass_container.py)
+is the container management script. It:
+
+- Manages **two separate Docker containers** — COMPASS Navigator and Isaac Sim
+- Controls container lifecycle: start, stop, enter, monitor both containers
+- Handles TensorRT model conversion automatically
+- Launches the Isaac Sim container with the ROS2 bridge
+- Provides easy container entry and debugging
+
+[`ros2_deployment/docker/Dockerfile.deploy`](https://github.com/NVlabs/COMPASS/tree/main/ros2_deployment/docker)
+creates a container with:
+
+- ROS2 Humble + CUDA 11.8 + TensorRT
+- the COMPASS Navigator package and its dependencies
+- a non-root user setup for development
+- proper FastDDS configuration for inter-container communication
+
+## Quick setup & run
+
+### 1. Build the container
+
+```bash
+export COMPASS_PATH=/path/to/compass
+export HUGGINGFACE_TOKEN=hf_your_token_here
+cd $COMPASS_PATH/ros2_deployment
+./build_compass_docker.sh
+```
+
+### 2. Launch Isaac Sim (terminal 1)
+
+```bash
+./compass_container.py launch_isaac_sim
+```
+
+- **In Isaac Sim GUI:** Go to `Windows` → `Examples` → `Robotics Examples` → `ROS2` → `Navigation`.
+- **Load a robot scene** (e.g., Carter).
+- **Press Play (▶️)** to start simulation.
+
+### 3. Launch COMPASS Navigator with GUI (terminal 2)
+
+```bash
+./compass_container.py --rviz launch_nav
+```
+
+- Automatically converts ONNX → TensorRT (first time only)
+- Builds the ROS2 workspace and launches the navigator
+- Opens RViz2 with robot visualization
+
+### 3.b Navigate the robot
+
+- **In RViz2:** use the **2D Nav Goal** tool in the toolbar.
+- **Click anywhere on the map** to set navigation targets.
+- **Robot navigates autonomously** using AI-powered path planning.
+
+## 4. Alternative: headless mode (no GUI)
+
+### 4.a Launch COMPASS Navigator
+
+```bash
+./compass_container.py launch_nav
+```
+
+- Runs the navigator without RViz2 GUI (saves resources).
+- All ROS2 topics still available for external tools.
+
+### 4.b Send navigation goals
+
+```bash
+# Enter the compass container
+./compass_container.py enter
+
+# Inside container, publish a goal pose
+ros2 topic pub --once /goal_pose geometry_msgs/msg/PoseStamped "
+header:
+ frame_id: 'odom'
+pose:
+ position:
+ x: 2.0
+ y: 0.0
+ z: 0.0
+ orientation:
+ x: 0.0
+ y: 0.0
+ z: 0.0
+ w: 1.0
+"
+
+# Monitor navigation progress
+ros2 topic echo /cmd_vel --once # robot commands
+ros2 topic echo /chassis/odom --once # robot position
+# (or visualize in Isaac Sim)
+```
+
+## Container commands
+
+```bash
+# COMPASS Navigator container lifecycle
+./compass_container.py start # start headless (background)
+./compass_container.py --rviz start # start with RViz GUI
+./compass_container.py enter # enter running container
+./compass_container.py stop # stop container
+./compass_container.py logs # view logs
+./compass_container.py status # status
+
+# Isaac Sim container (separate)
+./compass_container.py launch_isaac_sim # interactive
+
+# Combined launch options
+./compass_container.py launch_nav # quick headless launch
+./compass_container.py --rviz launch_nav # quick launch with RViz GUI
+./compass_container.py launch_nav --force-trt-conversion # rebuild TRT engine (headless)
+./compass_container.py --rviz launch_nav --force-trt-conversion
+
+# Development
+./compass_container.py enter # enter headless container
+./compass_container.py --rviz enter # enter with RViz support
+
+# Troubleshooting
+./compass_container.py debug_network_setup # debug ROS2 network setup
+```
+
+## Container lifecycle
+
+### COMPASS Navigator container
+
+- **Starts in detached mode** (runs in background).
+- **Persists after `launch_nav` exits** — the container keeps running.
+- **Runs ROS2 nodes and RViz2** inside the container.
+- **Must be manually stopped** with `./compass_container.py stop`.
+
+```bash
+./compass_container.py launch_nav
+# Command exits, but the container + ROS2 nodes continue running.
+
+./compass_container.py status # check if still running
+./compass_container.py enter # access running container
+./compass_container.py stop # stop container
+```
+
+### Isaac Sim container
+
+- **Starts in interactive mode** (blocks the terminal).
+- **Container exits when the Isaac Sim GUI closes**.
+- **Auto-removes itself** when terminated.
+- **Command blocks** until you close Isaac Sim.
+
+```bash
+./compass_container.py launch_isaac_sim
+# Command blocks, shows the Isaac Sim GUI.
+# Close Isaac Sim → container exits → command exits.
+# The container is automatically removed.
+```
+
+### Typical workflow
+
+```bash
+# Terminal 1: start Isaac Sim (interactive, blocks)
+./compass_container.py launch_isaac_sim
+
+# Terminal 2: start COMPASS (detached, returns immediately)
+./compass_container.py launch_nav
+
+# Use both systems...
+
+# Terminal 1: close the Isaac Sim GUI (container auto-exits)
+# Terminal 2: stop the COMPASS container
+./compass_container.py stop
+```
+
+## Troubleshooting
+
+**No GUI / black screen**
+
+```bash
+# X11 permissions are checked automatically when launching Isaac Sim.
+# If launch fails with X11 errors, fix permissions:
+xhost +local:docker
+export DISPLAY=:0
+```
+
+**Topics not visible between containers**
+
+```bash
+# Verify ROS2 domain consistency
+echo $ROS_DOMAIN_ID # Should be the same in both containers (0 by default)
+```
+
+**Package not found errors**
+
+```bash
+# Force a workspace rebuild
+./compass_container.py enter
+# Inside the container:
+rm -rf build install log && colcon build --symlink-install
+```
+
+**Model updated (need TensorRT conversion)**
+
+```bash
+# If you manually changed the ONNX model in assets/models/
+./compass_container.py launch_nav --force-trt-conversion
+```
+
+**Manual workspace build (inside container)**
+
+```bash
+cd /home/compassuser/compass_ws
+source /opt/ros/humble/setup.bash
+colcon build --symlink-install
+```
+
+**Build issues — `HUGGINGFACE_TOKEN` not set**
+
+```bash
+# Get a token from https://huggingface.co/settings/tokens after requesting
+# access to nvidia/COMPASS.
+export HUGGINGFACE_TOKEN=hf_your_token_here
+./build_compass_docker.sh
+```
+
+**TensorRT conversion fails**
+
+```bash
+# Check GPU memory usage
+nvidia-smi
+# Stop other GPU processes if needed
+./compass_container.py stop
+./compass_container.py launch_nav --force-trt-conversion
+```
+
+**ROS2 communication issues — robot doesn't respond to navigation commands**
+
+```bash
+# Verify Isaac Sim is running and the scene is playing (Play ▶️ pressed).
+# Inside the COMPASS Navigator container:
+./compass_container.py enter
+# Inside the container:
+ros2 topic list | grep -E "(cmd_vel|odom|image)"
+ros2 topic echo /cmd_vel --once # should show navigation commands when goals are set
+```
+
+**Network troubleshooting**
+
+```bash
+# Automated diagnostics (recommended)
+./compass_container.py debug_network_setup
+# This checks env vars, network mode, and ROS2 topic discovery in both containers.
+
+# Manual checks (if needed):
+docker inspect compass-ros2-navigator | grep NetworkMode # Should show: "NetworkMode": "host"
+```
diff --git a/docs/handbook/deployment/ros2.md b/docs/handbook/deployment/ros2.md
new file mode 100644
index 0000000..a627ef6
--- /dev/null
+++ b/docs/handbook/deployment/ros2.md
@@ -0,0 +1,57 @@
+# ROS2 Deployment
+
+COMPASS ships ROS2 nodes that consume a TensorRT engine and emit velocity
+commands. The same nodes cover three integration paths:
+
+- **Isaac Sim** — driving a simulated robot end-to-end via the ROS2 bridge.
+ The detailed setup is on the [Isaac Sim setup](isaac_sim.md) sub-page.
+- **Sim2Real** — deploying the same `compass_inference` node directly on a
+ real robot, optionally pairing with visual SLAM (e.g. cuVSLAM) for state
+ estimation.
+- **Object navigation** — wiring an object-localization module (e.g.
+ Locate3D) into the bundled `obj_target_generator` node so the robot can
+ approach named objects.
+
+The packages live under
+[`ros2_deployment/`](https://github.com/NVlabs/COMPASS/tree/main/ros2_deployment).
+
+## Provided ROS2 nodes
+
+- **`compass_inference`** — consumes camera images, target poses, and robot
+ speed inputs, then outputs velocity commands by running TensorRT inference
+ with COMPASS engines.
+- **`obj_target_generator`** — receives object localization bounding boxes
+ and generates navigation target poses for the COMPASS navigator.
+
+These nodes enable a variety of integration workflows; the three below are
+the bundled examples.
+
+## 1. Isaac Sim integration
+
+The [`compass_navigator`](https://github.com/NVlabs/COMPASS/tree/main/ros2_deployment/compass_navigator)
+package is fully compatible with [NVIDIA Isaac Sim](https://developer.nvidia.com/isaac-sim),
+leveraging its robotics environments and ROS2 bridge for seamless simulation.
+
+For detailed setup instructions and a step-by-step Isaac Sim integration guide,
+see the [Isaac Sim setup](isaac_sim.md) sub-page.
+
+## 2. Zero-shot sim2real transfer
+
+The `compass_inference` node can also be deployed directly on real robots,
+enabling a seamless transition from simulation to real-world operation. By
+integrating visual SLAM solutions such as
+[cuVSLAM](https://nvidia-isaac-ros.github.io/concepts/visual_slam/cuvslam/index.html)
+for robot state estimation, the COMPASS model can support zero-shot sim2real
+transfer.
+
+
+
+## 3. Object navigation integration
+
+By integrating an object localization module (e.g.,
+[Locate3D](https://locate3d.atmeta.com/)), we can also enable object navigation
+with COMPASS. The `obj_target_generator` node can convert localized object
+bounding boxes into navigation goals, allowing the robot to autonomously
+approach specified objects.
+
+
diff --git a/docs/handbook/extending.md b/docs/handbook/extending.md
new file mode 100644
index 0000000..b410ade
--- /dev/null
+++ b/docs/handbook/extending.md
@@ -0,0 +1,103 @@
+# Adding a new embodiment or scene
+
+The Isaac-Lab extension at
+[`compass/rl_env/exts/mobility_es/`](https://github.com/NVlabs/COMPASS/tree/main/compass/rl_env/exts/mobility_es)
+defines the embodiments (H1, Carter, Spot, G1, Digit, …) and scenes COMPASS
+trains on. Adding your own is a registration exercise — the gin configs and
+`run.py` driver pick it up once the entry exists.
+
+## Adding new embodiments
+
+To add a new robot embodiment, follow these steps:
+
+### 1. Create robot configuration
+
+- Follow the Isaac Lab [instructions](https://isaac-sim.github.io/IsaacLab/main/source/how-to/write_articulation_cfg.html)
+ to add a new robot articulation configuration in
+ [`compass/rl_env/exts/mobility_es/mobility_es/config/robots.py`](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/config/robots.py).
+- Ensure proper joint configurations, collision properties, and physics
+ parameters are set.
+
+### 2. Create environment configuration
+
+- Create a new RL environment class that inherits from `GoalReachingEnvCfg`
+ in
+ [`compass/rl_env/exts/mobility_es/mobility_es/config/env_cfg.py`](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/config/env_cfg.py).
+- Override the following components as needed:
+
+ | Component | Description |
+ |-----------|-------------|
+ | `scene.robot` | Set robot articulation configuration |
+ | `scene.camera` | Configure camera settings |
+ | `actions` | Define action item for the embodiment |
+ | `observations` | Configure RL observations |
+ | `events` | Configure RL events |
+ | `rewards` | Configure RL rewards |
+ | `terminations` | Configure RL terminations |
+
+:::{note}
+Each embodiment should define its own action term as a low-level controller
+that maps velocity commands to joint positions. We have pre-defined action
+terms for different robot embodiments under
+[`compass/rl_env/exts/mobility_es/mobility_es/mdp/action`](https://github.com/NVlabs/COMPASS/tree/main/compass/rl_env/exts/mobility_es/mobility_es/mdp/action)
+that can be re-configured for new embodiments.
+:::
+
+### 3. Register and verify the environment
+
+- Import your new environment in [`run.py`](https://github.com/NVlabs/COMPASS/blob/main/run.py).
+- Verify it is functional by running `run.py` with the new environment.
+
+### Examples of existing embodiments
+
+- [H1 humanoid robot](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/config/h1_env_cfg.py)
+- [Carter mobile robot](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/config/carter_env_cfg.py)
+- [Spot quadruped robot](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/config/spot_env_cfg.py)
+- [G1 humanoid robot](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/config/g1_env_cfg.py)
+- [Digit humanoid robot](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/config/digit_env_cfg.py)
+
+## Adding new scenes
+
+### 1. Create scene configuration
+
+- Follow the Isaac Lab
+ [scene tutorial](https://isaac-sim.github.io/IsaacLab/main/source/tutorials/02_scene/create_scene.html)
+ to add a new scene configuration in
+ [`compass/rl_env/exts/mobility_es/mobility_es/config/environments.py`](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/config/environments.py).
+ Inherit from `EnvSceneAssetCfg` with proper parameters like
+ `pose_sample_range`, `env_spacing`, `replicate_physics`, etc.
+
+### 2. Add an occupancy map (optional)
+
+We use an occupancy map for collision-free pose sampling. It's optional but
+recommended for improving sampling efficiency, especially in tight scenes.
+
+Generate the map directly from the scene USD with the bundled CLI:
+
+```bash
+${ISAACLAB_PATH}/isaaclab.sh -p scripts/generate_omap_from_usd.py path/to/scene.usd
+```
+
+By default this writes `.png` and `occupancy_map.yaml` to
+`/omap/`. Use `--cell-size`, `--z-min` / `--z-max`, `--bounds`, or
+`--out-dir` to override the defaults; see `--help` for the full flag list.
+
+You can register the YAML path explicitly in `OMAP_PATHS` in
+[`compass/rl_env/exts/mobility_es/mobility_es/config/environments.py`](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/config/environments.py),
+but it's not required: when the scene has no entry, the collision checker
+falls back to looking for an `omap/occupancy_map.yaml` next to the scene's
+USD — which is exactly where the generator drops it.
+
+The legacy interactive flow via Isaac Sim's
+[occupancy-map UI](https://docs.omniverse.nvidia.com/isaacsim/latest/features/ext_omni_isaac_occupancy_map.html)
+still works if you prefer authoring a map by hand. Save the YAML/PNG into
+the same `/omap/` location and the loader will pick it up.
+
+See the [Auto OMap from USDs](omap.md) handbook page for the deeper
+generator + verifier reference.
+
+### 3. Register and verify the scene
+
+- Import your new scene in [`run.py`](https://github.com/NVlabs/COMPASS/blob/main/run.py).
+- Verify the scene is functional by running `run.py` with the new scene
+ by setting `env_cfg.scene.environment = MyNewSceneCfg()`.
diff --git a/docs/handbook/index.md b/docs/handbook/index.md
new file mode 100644
index 0000000..763b014
--- /dev/null
+++ b/docs/handbook/index.md
@@ -0,0 +1,157 @@
+# COMPASS Handbook
+
+```{raw} html
+
+COMPASS is a cross-embodiment mobility policy framework that
+combines imitation learning, residual reinforcement learning, and policy
+distillation to ship one generalist navigation policy across humanoids,
+quadrupeds, and wheeled robots. This handbook is the live reference for
+installing, training, deploying, and extending it.
+
+
+ Residual RL
+ Policy Distillation
+ Isaac Lab 3.0
+ ROS2 deployment
+ OSMO cloud
+ VLA fine-tuning
+
+```
+
+[**↗ Project page**](https://nvlabs.github.io/COMPASS/) ·
+[arXiv](https://arxiv.org/abs/2502.16372) ·
+[Source on GitHub](https://github.com/NVlabs/COMPASS)
+
+---
+
+## End-to-end pipeline
+
+Each stage has a top-level entry-point script in the repo:
+
+| # | Stage | Script |
+|---|------|--------|
+| 1 | Train residual RL specialist (or evaluate any policy) | [`run.py`](https://github.com/NVlabs/COMPASS/blob/main/run.py) |
+| 2 | Roll out specialists to collect HDF5 distillation data | [`record.py`](https://github.com/NVlabs/COMPASS/blob/main/record.py) |
+| 3 | Distil specialists into one generalist | [`distillation_train.py`](https://github.com/NVlabs/COMPASS/blob/main/distillation_train.py) |
+| 4 | Export to ONNX / JIT | [`onnx_conversion.py`](https://github.com/NVlabs/COMPASS/blob/main/onnx_conversion.py) |
+| 5 | Convert ONNX → TensorRT engine | [`trt_conversion.py`](https://github.com/NVlabs/COMPASS/blob/main/trt_conversion.py) |
+| 6 | Deploy via ROS2 in Isaac Sim or on real robots | [`ros2_deployment/`](https://github.com/NVlabs/COMPASS/tree/main/ros2_deployment) |
+
+Built on Isaac Lab 3.0 / Isaac Sim 4.5 and on top of NVIDIA's
+[X-Mobility](https://github.com/NVlabs/X-MOBILITY) base policy.
+
+---
+
+## Where to start
+
+::::{grid} 1 1 2 3
+:gutter: 3
+
+:::{grid-item-card} 🚀 Quick start
+:link: quickstart
+:link-type: doc
+
+Three commands to a training shell.
+:::
+
+:::{grid-item-card} 📦 Installation
+:link: installation/docker
+:link-type: doc
+
+Docker-as-venv: three commands and you're in a training shell.
+:::
+
+:::{grid-item-card} 🎓 Training a specialist
+:link: workflows/training
+:link-type: doc
+
+How the residual RL loop works, how to override embodiment / scene.
+:::
+
+:::{grid-item-card} 🛰️ ROS2 Deployment
+:link: deployment/ros2
+:link-type: doc
+
+ROS2 nodes consuming a TensorRT engine — Isaac Sim, sim2real, or
+object navigation.
+:::
+
+:::{grid-item-card} ☁️ OSMO cloud submission
+:link: osmo
+:link-type: doc
+
+Submit training and evaluation runs to NVIDIA's OSMO cluster.
+:::
+
+:::{grid-item-card} 🤖 GR00T post-training
+:link: workflows/gr00t_finetuning
+:link-type: doc
+
+Use COMPASS distillation datasets to fine-tune NVIDIA's
+[Isaac-GR00T](https://github.com/NVIDIA/Isaac-GR00T) VLA model.
+:::
+
+::::
+
+---
+
+## What's where in the repo
+
+```text
+COMPASS/
+├── compass/
+│ ├── residual_rl/ # Actor-critic that adds a residual on top of X-Mobility
+│ ├── distillation/ # Generalist distillation (PyTorch Lightning trainer)
+│ ├── rl_env/ # Isaac Lab `mobility_es` extension (embodiments + scenes)
+│ └── utils/ # Shared helpers
+├── configs/ # Gin configs (train / eval / record / distillation / shared)
+├── docker/ # Docker-as-venv dev environment + Dockerfiles
+├── osmo/ # OSMO workflow YAMLs + Python launcher
+├── ros2_deployment/ # ROS2 packages for Isaac Sim / real-robot deployment
+├── scripts/ # Standalone tools (HDF5→LeRobot, omap generator, …)
+└── x_mobility/ # Vendored X-Mobility wheel
+```
+
+For deeper layout details, see [CLAUDE.md](https://github.com/NVlabs/COMPASS/blob/main/CLAUDE.md).
+
+```{toctree}
+:caption: Installation
+:maxdepth: 1
+:hidden:
+
+quickstart
+installation/docker
+agentic
+extending
+```
+
+```{toctree}
+:caption: Workflows
+:maxdepth: 1
+:hidden:
+
+workflows/training
+workflows/recording
+workflows/distillation
+workflows/export
+workflows/gr00t_finetuning
+```
+
+```{toctree}
+:caption: ROS2 Deployment
+:maxdepth: 1
+:hidden:
+
+deployment/ros2
+deployment/isaac_sim
+```
+
+```{toctree}
+:caption: Reference
+:maxdepth: 1
+:hidden:
+
+osmo
+omap
+contributing
+```
diff --git a/docs/handbook/installation/docker.md b/docs/handbook/installation/docker.md
new file mode 100644
index 0000000..7690cbd
--- /dev/null
+++ b/docs/handbook/installation/docker.md
@@ -0,0 +1,166 @@
+# Docker-as-venv install
+
+`./docker/run.sh` + `source ./docker/activate` give you a Python-venv-like dev
+loop that runs commands inside the COMPASS container while keeping your editor,
+terminal, and prompt on the host. Edit code with whatever editor you like; the
+bind-mount means changes hot-reload.
+
+:::{note}
+Docker is the recommended path because the image bakes Isaac Lab, the
+X-Mobility wheel, and the `mobility_es` extension at build time — no host
+Python / Vulkan SDK to manage. Bare-metal install is possible but not
+documented end-to-end in the handbook; see the
+[Isaac Lab installation guide](https://isaac-sim.github.io/IsaacLab/v3.0.0-beta1/source/setup/installation/index.html)
+and `${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -e compass/rl_env/exts/mobility_es`.
+:::
+
+## How it works
+
+```
+Host shell → shim PATH → docker exec → daemon container
+(editor, (set by (translates (compass-rl image,
+ terminal, `source host CWD repo bind-mounted
+ prompt) docker/ to container at /workspace/COMPASS)
+ activate`) path)
+```
+
+`source ./docker/activate` brings up the container if it isn't already running,
+prepends a tmp shim dir to `PATH`, and rewrites your prompt to `(compass-rl)`.
+The shims (`python`, `pip`, `tensorboard`, `pytest`, `yapf`, `pylint`,
+`pre-commit`, …) each `docker exec` the same-named binary inside the container,
+with the host CWD translated to the container path. `deactivate` reverts.
+
+## Prerequisites
+
+- Docker (Engine 24+ recommended)
+- [NVIDIA Container Toolkit](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html) so `--gpus all` works
+- An NVIDIA GPU
+- A HuggingFace account with access to [nvidia/COMPASS](https://huggingface.co/nvidia/COMPASS) and a [token](https://huggingface.co/settings/tokens)
+- An X server (only if you want `--viz kit` to render — headless training works fine without)
+
+For the three-command quick-start path, see [Quick start](../quickstart.md).
+The rest of this page is the subcommand reference, multi-checkout / multi-GPU
+notes, the git workflow, and troubleshooting.
+
+## Subcommand reference
+
+```
+./docker/run.sh build [tag] # docker build -f docker/Dockerfile.rl
+./docker/run.sh assets [--hf-token TOK] # download USDs + ckpt to ./assets
+./docker/run.sh up # idempotent: start daemon container
+./docker/run.sh down # docker rm -f the container
+./docker/run.sh exec [...] # one-shot exec inside the container
+./docker/run.sh shell # escape hatch: drop into bash
+./docker/run.sh status # show container + image state
+```
+
+### `build`
+
+Builds `compass-rl:latest` (override the tag with `./docker/run.sh build mytag`).
+Re-running is fast because Docker layer-caches.
+
+### `assets`
+
+Downloads:
+
+| File | URL | Lands at |
+|------|-----|---------|
+| `compass_usds.zip` (extracted) | `huggingface.co/nvidia/COMPASS/...` | `./assets/usd/` |
+| `x_mobility-nav2-semantic_action_path.ckpt` | `huggingface.co/nvidia/X-Mobility/...` | `./assets/x_mobility.ckpt` |
+
+Cache-aware: skips files that already exist. `--force` to redownload everything.
+`--cache-dir DIR` to put assets somewhere other than `./assets/`.
+
+`./assets/` is part of the repo bind-mount, so inside the container it's at
+`/workspace/COMPASS/assets/` — relative paths from the repo root work in both
+host and container shells.
+
+### `up` / `down`
+
+`up` is idempotent: starts the container if not running, or no-op if already up.
+`down` stops and removes it. The container's name is
+`compass--<8-hex-of-repo-path>`, so multiple checkouts of COMPASS on
+the same machine coexist without colliding.
+
+### `exec` / `shell`
+
+`exec` runs one command inside the container (`./docker/run.sh exec python --version`).
+`shell` drops you into a bash inside the container — escape hatch for poking at
+the image, not for daily dev (use `source ./docker/activate` for that).
+
+### `status`
+
+Shows whether the image is built, whether the container is running, and the
+relevant paths. Run this first when something feels off.
+
+## Multiple checkouts of COMPASS
+
+The container name hashes the absolute repo path:
+
+```bash
+# ~/COMPASS/dev → container compass-liuw-a7f3b2c8
+# ~/COMPASS/main → container compass-liuw-9d1e44f0
+```
+
+Both can run concurrently and never confuse each other. Each gets its own
+bind-mount, its own pre-commit cache, its own kit shader cache.
+
+## Multi-GPU
+
+The container starts with `--gpus all` by default. To pin to specific GPUs,
+export `NVIDIA_VISIBLE_DEVICES` before bringing the container up:
+
+```bash
+NVIDIA_VISIBLE_DEVICES=0 ./docker/run.sh up # only GPU 0 visible inside the container
+```
+
+(Note: this currently requires editing `_compass_run_args` in
+[`docker/run.sh`](https://github.com/NVlabs/COMPASS/blob/main/docker/run.sh)
+to honor the env var — track via `release_tracker.md` if you need it; not
+implemented in v1.)
+
+## VSCode / Cursor
+
+Editor + container are decoupled: VSCode runs natively on the host, opens the
+repo at `~/Projects/COMPASS`, and you run `python run.py …` from VSCode's
+integrated terminal **after** sourcing `./docker/activate` in that terminal. No
+"Reopen in Container" needed.
+
+## Git workflow
+
+`git status / add / commit -s / push` run on the host as normal — no shim. SSH
+keys, GPG signing, DCO sign-off all work without extra plumbing.
+
+The only wrinkle is **pre-commit hooks** (yapf, pylint, clang-format). The
+hooks live in the container, not on the host. So:
+
+- **Activate before committing.** `source ./docker/activate` adds `pre-commit`
+ to `PATH`, and the shim routes the hook invocation into the container.
+- **Hook env cache** lives at `./.cache/pre-commit/` (inside the bind-mount), so
+ `down` + `up` doesn't force a 30s rebuild. `.cache/` is gitignored.
+
+## Troubleshooting
+
+| Symptom | Likely cause | Fix |
+|--------|--------------|-----|
+| `Image compass-rl:latest not found` | Haven't built yet | `./docker/run.sh build` |
+| `permission denied while trying to connect to the Docker daemon` | User not in `docker` group | `sudo usermod -aG docker $USER` then re-login |
+| `Vulkan/X11: cannot open display` from inside container | X server not forwarded | `xhost +SI:localuser:$(id -un)` (run.sh tries this automatically; may need manual on systems where it fails silently) |
+| Isaac Sim shader cold-compile every run | Shader cache wiped | Check `~/.cache/compass/kit/` is writable; reuses across runs |
+| `pre-commit: command not found` on `git commit` | Forgot to activate | `source ./docker/activate` |
+| Container won't `up`: "another container with the same name" | Stale container from a crash | `./docker/run.sh down` then `./docker/run.sh up` |
+
+## What lives where
+
+```
+docker/
+├── Dockerfile.rl # Image: Isaac Lab 3.0-beta1 + COMPASS deps + python wrapper
+├── Dockerfile.distillation # Used by docker-only distillation runs (unrelated to dev env)
+├── run.sh # build / assets / up / down / exec / shell / status
+├── activate # source me: shim PATH + (compass-rl) prompt prefix
+└── prepare_assets.sh # invoked by `run.sh assets`
+
+~/.cache/compass/kit/ # writable Isaac Sim shader cache (survives container teardown)
+./assets/ # USDs + X-Mobility ckpt (gitignored; populated by `run.sh assets`)
+./.cache/ # pip / pre-commit / huggingface caches (gitignored)
+```
diff --git a/docs/handbook/omap.md b/docs/handbook/omap.md
new file mode 100644
index 0000000..8c49686
--- /dev/null
+++ b/docs/handbook/omap.md
@@ -0,0 +1,64 @@
+# Auto OMap from USDs
+
+Occupancy maps gate collision-free pose sampling during training. Historically
+they were hand-authored in the Isaac Sim editor — slow, error-prone, and a
+blocker for [SAGE-driven](agentic.md) scene generation. The
+[`scripts/generate_omap_from_usd.py`](https://github.com/NVlabs/COMPASS/blob/main/scripts/generate_omap_from_usd.py)
+CLI generates an OMap directly from a USD scene in one shot.
+
+## Generate an OMap
+
+```bash
+python scripts/generate_omap_from_usd.py \
+ compass/rl_env/exts/mobility_es/mobility_es/usd//.usd
+```
+
+(Inside an [activated dev shell](installation/docker.md), `python` already
+points at Isaac Sim's bundled Python; on bare-metal install, prefix with
+`${ISAACLAB_PATH}/isaaclab.sh -p`.)
+
+By default the script writes the PNG + ROS YAML pair to `/omap/`
+next to the input USD — exactly where
+[`OccupancyMapCollisionChecker`](https://github.com/NVlabs/COMPASS/blob/main/compass/rl_env/exts/mobility_es/mobility_es/utils/occupancy_map.py)
+auto-discovers it when no explicit `OMAP_PATHS` entry exists.
+
+## Common flags
+
+| Flag | Default | Meaning |
+|------|--------|---------|
+| `-o, --out-dir` | `/omap/` | Where the PNG + YAML land |
+| `--cell-size` | `0.05` | meters / pixel |
+| `--z-min` / `--z-max` | `0.1` / `0.62` | Height slab the rasterizer projects |
+| `--bounds` | derived from USD bbox + 1 m padding | World-space `xmin xmax ymin ymax` |
+| `--padding` | `1.0` | Padding (m) around the auto-derived bbox |
+| `--map-name` | `` | PNG stem |
+
+Run `python scripts/generate_omap_from_usd.py --help` for the complete list.
+
+## Loader auto-discovery
+
+`OccupancyMapCollisionChecker` (`compass/rl_env/exts/.../utils/occupancy_map.py`)
+checks `OMAP_PATHS` first; if it has no entry for the scene, it falls back to
+`/omap/occupancy_map.yaml` — the same path the
+generator writes to. **No `OMAP_PATHS` registration is needed for new
+scenes.**
+
+## Verifying a generated OMap
+
+A small standalone verifier in `/tmp/verify_omap.py` (used during PR-5
+development) loads the generated YAML, samples a uniform grid of poses,
+runs `is_in_collision`, and writes annotated PNGs:
+
+- All 300 samples — green = free, red = collision (or out-of-bounds).
+- Free-only — every dot lands on an unoccupied (white) cell.
+
+The verification checked three representative scenes (`office`,
+`combined_simple_warehouse`, `sample_small_footprint_one_rack_obst_sdg`);
+all passed with free-pose samples cleanly avoiding obstacles.
+
+## Slab tuning for taller embodiments
+
+The default `[0.1, 0.62]` height slab works for Carter, Spot, G1. Tall
+humanoids (H1) clear about 1.3 m; bump `--z-max 1.4` so the rasterizer
+captures higher obstacles. The slab is the only embodiment-specific knob
+and is exposed at the CLI rather than baked into per-embodiment maps.
diff --git a/docs/handbook/osmo.md b/docs/handbook/osmo.md
new file mode 100644
index 0000000..17ee32a
--- /dev/null
+++ b/docs/handbook/osmo.md
@@ -0,0 +1,109 @@
+# OSMO cloud submission
+
+Submit COMPASS training, evaluation, recording, or distillation jobs to
+NVIDIA's [OSMO](https://docs.nvidia.com/osmo/) cluster via the bundled
+Python launcher [`osmo/run_osmo.py`](https://github.com/NVlabs/COMPASS/blob/main/osmo/run_osmo.py).
+
+## Prerequisites
+
+- An OSMO account with a logged-in CLI: `osmo login`
+- Write access to a docker registry that OSMO workers can pull from (set as `--registry-prefix` or via the `COMPASS_OSMO_REGISTRY` env var, e.g. `nvcr.io//`)
+- A wandb account; export `WANDB_API_KEY` (or pass `--prompt`)
+- A HuggingFace token with read access to [`nvidia/COMPASS`](https://huggingface.co/nvidia/COMPASS) (gated) and [`nvidia/X-Mobility`](https://huggingface.co/nvidia/X-Mobility); export `HF_TOKEN` (or pass `--prompt`). Distillation does not need this.
+- Any resume / residual / distillation checkpoints you reference uploaded as wandb artifacts that the workflow can `wandb artifact get`.
+
+The COMPASS USDs (`compass_usds.zip`) and the X-Mobility base-policy
+checkpoint are downloaded inside the workflow directly from HuggingFace
+on every run — no OSMO-dataset or wandb-artifact mirroring required.
+
+## Quick start
+
+```bash
+# One-time, in your shell
+export WANDB_API_KEY=
+export HF_TOKEN=
+export COMPASS_OSMO_REGISTRY=nvcr.io//
+
+# Submit residual RL training; build+push the image automatically.
+python osmo/run_osmo.py train \
+ --experiment-name pilot \
+ --wandb-project compass-rl
+```
+
+To inspect the would-be `osmo workflow submit` invocation without actually
+submitting, add `--dry-run`.
+
+## Subcommands
+
+| Subcommand | Workflow YAML | Purpose |
+|------------|---------------|---------|
+| `train` | [`osmo/workflows/rl_es_train_workflow.yaml`](https://github.com/NVlabs/COMPASS/blob/main/osmo/workflows/rl_es_train_workflow.yaml) | Residual RL specialist training (auto-runs an eval at the end) |
+| `eval` | [`osmo/workflows/rl_es_eval_workflow.yaml`](https://github.com/NVlabs/COMPASS/blob/main/osmo/workflows/rl_es_eval_workflow.yaml) | Residual RL specialist or generalist evaluation |
+| `record` | [`osmo/workflows/rl_es_record_workflow.yaml`](https://github.com/NVlabs/COMPASS/blob/main/osmo/workflows/rl_es_record_workflow.yaml) | Roll out a specialist policy to collect HDF5 data for distillation |
+| `distill` | [`osmo/workflows/distillation_train_workflow.yaml`](https://github.com/NVlabs/COMPASS/blob/main/osmo/workflows/distillation_train_workflow.yaml) | Train the generalist distillation policy |
+
+### `train`
+
+```bash
+python osmo/run_osmo.py train \
+ --experiment-name \
+ --wandb-project \
+ [--resume-ckpt ] \
+ [--no-residual] \
+ [--image ]
+```
+
+### `eval`
+
+```bash
+python osmo/run_osmo.py eval \
+ --experiment-name \
+ --wandb-project \
+ --checkpoint \
+ [--distillation-ckpt ] \
+ [--no-residual] \
+ [--embodiment h1|spot|carter|g1|digit] \
+ [--environment ] \
+ [--image ]
+```
+
+### `record`
+
+```bash
+python osmo/run_osmo.py record \
+ --experiment-name \
+ --dataset-name \
+ [--image ]
+```
+
+### `distill`
+
+```bash
+python osmo/run_osmo.py distill \
+ --experiment-name \
+ --wandb-project \
+ --dataset-name \
+ [--checkpoint ] \
+ [--train-config distillation_config] \
+ [--image ]
+```
+
+## Image build behavior
+
+If you do not pass `--image`, `run_osmo.py` will:
+
+1. Build the appropriate Dockerfile ([`docker/Dockerfile.rl`](https://github.com/NVlabs/COMPASS/blob/main/docker/Dockerfile.rl) for `train` / `eval` / `record`, [`docker/Dockerfile.distillation`](https://github.com/NVlabs/COMPASS/blob/main/docker/Dockerfile.distillation) for `distill`) tagged as `/compass_:`.
+2. `docker push` that tag.
+3. Pass the resulting image into the `osmo workflow submit` command.
+
+For repeated runs against the same code, build the image once and pass it via
+`--image` to skip the build/push.
+
+## Troubleshooting
+
+- **`ERROR: $WANDB_API_KEY is not set`** — export it, or pass `--prompt` to be asked interactively.
+- **`ERROR: --image not given and --registry-prefix is empty`** — either supply `--image ` or set `--registry-prefix` / `$COMPASS_OSMO_REGISTRY`.
+- **`manifest unknown` from `osmo workflow submit`** — the image hasn't pushed yet (or you don't have read access). Re-run `docker push ` and retry.
+- **Workflow logs** — visit your OSMO console; the workflow ID printed by `osmo workflow submit` is the lookup key.
+- **HuggingFace download fails inside the workflow** — verify `HF_TOKEN` was exported and that your account has access to [`nvidia/COMPASS`](https://huggingface.co/nvidia/COMPASS) and [`nvidia/X-Mobility`](https://huggingface.co/nvidia/X-Mobility).
+- **Dataset not found** (distillation only) — confirm your distillation input dataset is uploaded and visible to the workflow's run-as account.
diff --git a/docs/handbook/quickstart.md b/docs/handbook/quickstart.md
new file mode 100644
index 0000000..f117de3
--- /dev/null
+++ b/docs/handbook/quickstart.md
@@ -0,0 +1,78 @@
+# Quick start
+
+The fastest path to a training shell, using the [Docker-as-venv dev environment](installation/docker.md).
+
+## Prerequisites
+
+- Docker (Engine 24+) with the
+ [NVIDIA Container Toolkit](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html)
+- An NVIDIA GPU
+- A HuggingFace account with [token](https://huggingface.co/settings/tokens)
+ and access to [nvidia/COMPASS](https://huggingface.co/nvidia/COMPASS)
+
+## Three commands
+
+```bash
+git clone https://github.com/NVlabs/COMPASS.git && cd COMPASS
+
+export HF_TOKEN=hf_xxx
+./docker/run.sh assets # USDs + X-Mobility ckpt → ./assets/ (~5 min, one-time)
+./docker/run.sh build # build the dev image (~10 min, first run)
+source ./docker/activate # venv-like activation (prompt: (compass-rl))
+```
+
+:::{admonition} What `./docker/run.sh assets` downloads
+:class: tip
+
+The build step doesn't pull these — training does. The downloader is gated
+by your HF token.
+
+- **`./assets/usd/`** — `compass_usds.zip` from
+ [`nvidia/COMPASS`](https://huggingface.co/nvidia/COMPASS). The training
+ scenes (warehouse, office, hospital, …) and embodiment USDs.
+- **`./assets/x_mobility.ckpt`** — `x_mobility-nav2-semantic_action_path.ckpt`
+ from [`nvidia/X-Mobility`](https://huggingface.co/nvidia/X-Mobility). The
+ base policy that the residual head is trained on top of.
+
+`./assets/` is part of the repo bind-mount, so inside the container these
+paths are visible at the same `./assets/...` (under `/workspace/COMPASS/`).
+Re-running `assets` is idempotent — it's a no-op once the files exist.
+:::
+
+## First training step
+
+From the activated shell, kick off a 1-env smoke run to confirm everything wires:
+
+```bash
+python run.py \
+ -c configs/train_config.gin \
+ -o /tmp/out \
+ -b ./assets/x_mobility.ckpt \
+ --num_envs 1 \
+ --enable_cameras
+```
+
+You should see Isaac Sim boot, the scene load, and PPO step into iteration 0.
+
+## Next steps
+
+- **Scale up**: drop `--num_envs 1`. The default scales with available VRAM (~1 GB / env).
+- **Other embodiments**: pass `--embodiment {h1,carter,spot,g1,digit}`. See
+ [Adding a new embodiment / scene](extending.md) to add your own.
+- **Submit to OSMO**: see [OSMO cloud submission](osmo.md).
+- **Distil a generalist**: collect rollouts ([recording](workflows/recording.md))
+ then [distil](workflows/distillation.md).
+
+## Leaving the dev environment
+
+```bash
+deactivate # remove the shim PATH; keep the container alive
+./docker/run.sh down # stop the container entirely
+```
+
+If you can't run Docker, you'll need to install Isaac Lab v3.0.0-beta1 and
+the `mobility_es` extension on the host directly — follow the
+[Isaac Lab installation guide](https://isaac-sim.github.io/IsaacLab/v3.0.0-beta1/source/setup/installation/index.html)
+and then `${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -e compass/rl_env/exts/mobility_es`.
+Docker is the supported / tested path; bare-metal works but isn't documented
+end-to-end in the handbook.
diff --git a/docs/handbook/requirements.txt b/docs/handbook/requirements.txt
new file mode 100644
index 0000000..e4ecce4
--- /dev/null
+++ b/docs/handbook/requirements.txt
@@ -0,0 +1,8 @@
+myst-parser>=3.0.1
+nvidia-sphinx-theme>=0.0.8
+setuptools>=69
+sphinx>=7.0,<8.3
+sphinx-autobuild>=2024.0.0
+sphinx_copybutton>=0.5.2
+sphinx_design>=0.6.1
+sphinxcontrib-mermaid>=1.0.0
diff --git a/docs/handbook/workflows/distillation.md b/docs/handbook/workflows/distillation.md
new file mode 100644
index 0000000..0194efc
--- /dev/null
+++ b/docs/handbook/workflows/distillation.md
@@ -0,0 +1,54 @@
+# Distilling the generalist
+
+Once you have an HDF5 distillation dataset (see [Recording distillation data](recording.md)),
+`distillation_train.py` trains a single generalist policy that imitates the
+per-embodiment specialists. PyTorch Lightning under the hood; pure-PyTorch
+script (no Isaac-Lab Python wrapper required).
+
+## Train a generalist
+
+```bash
+python3 distillation_train.py \
+ --config-files configs/distillation_config.gin \
+ --dataset-path \
+ --output-dir
+```
+
+Hyperparameters live in
+[`configs/distillation_config.gin`](https://github.com/NVlabs/COMPASS/blob/main/configs/distillation_config.gin).
+Override on the CLI by repeating `--config-files` or via gin
+`--gin_bindings` overrides if you need to tweak a single value.
+
+## Evaluate the generalist
+
+The same `run.py` driver evaluates a generalist checkpoint when given via `-d`:
+
+```bash
+python run.py \
+ -c configs/eval_config.gin \
+ -o \
+ -b \
+ -d \
+ --enable_cameras \
+ --video \
+ --video_interval
+```
+
+(Inside an [activated dev shell](../installation/docker.md), `python` is
+already wired; on bare-metal install, prefix with `${ISAACLAB_PATH}/isaaclab.sh -p`.)
+
+## Submitting to OSMO
+
+```bash
+python osmo/run_osmo.py distill \
+ --experiment-name \
+ --dataset-name
+```
+
+Full reference: [OSMO cloud submission](../osmo.md).
+
+## Where to go next
+
+- [Export](export.md) the generalist to ONNX / TensorRT for inference.
+- [GR00T post-training](gr00t_finetuning.md) — use the same dataset to
+ fine-tune the Isaac-GR00T VLA model.
diff --git a/docs/handbook/workflows/export.md b/docs/handbook/workflows/export.md
new file mode 100644
index 0000000..2f47b93
--- /dev/null
+++ b/docs/handbook/workflows/export.md
@@ -0,0 +1,50 @@
+# Exporting to ONNX / TensorRT
+
+Two scripts cover the export path. Both are pure-PyTorch (no Isaac Lab
+required).
+
+## ONNX / JIT
+
+### Specialist (residual + base)
+
+```bash
+python3 onnx_conversion.py \
+ -b \
+ -r \
+ -o \
+ -j
+```
+
+### Generalist
+
+```bash
+python3 onnx_conversion.py \
+ -b \
+ -g \
+ -e \
+ -o \
+ -j
+```
+
+`-e` selects which embodiment-specific head to export. Pass one of
+`{h1, carter, spot, g1, digit}` — must match an entry in `EmbodimentEnvCfgMap`
+in [`run.py`](https://github.com/NVlabs/COMPASS/blob/main/run.py).
+
+## TensorRT
+
+```bash
+python3 trt_conversion.py \
+ -o \
+ -t
+```
+
+Generates a TensorRT engine specialised for your GPU. The engine is then
+consumed by the [ROS2 deployment node](../deployment/ros2.md).
+
+:::{note} Engine portability
+TensorRT engines are GPU-specific. An engine built on an L40 won't run
+optimally (or at all) on a Jetson Orin. Build the engine on the same GPU
+family as the deployment target, or use the
+[ROS2 deployment](../deployment/ros2.md) container's runtime conversion
+flow.
+:::
diff --git a/docs/handbook/workflows/gr00t_finetuning.md b/docs/handbook/workflows/gr00t_finetuning.md
new file mode 100644
index 0000000..def16fa
--- /dev/null
+++ b/docs/handbook/workflows/gr00t_finetuning.md
@@ -0,0 +1,50 @@
+# GR00T post-training (VLA fine-tuning)
+
+COMPASS distillation datasets can fine-tune VLA models like
+[NVIDIA Isaac-GR00T](https://github.com/NVIDIA/Isaac-GR00T) to bolt on
+navigation capabilities. Three steps: convert, fine-tune, evaluate.
+
+## Step 1 — Convert HDF5 → GR00T LeRobot format
+
+You need an HDF5 distillation dataset first; see
+[Recording distillation data](recording.md). Then convert with the bundled
+script:
+
+```bash
+python scripts/hdf5_to_lerobot_episodic.py \
+ --hdf5-dir \
+ --output-path
+```
+
+The script is pure-Python (no Isaac Lab) — runs anywhere with the standard
+COMPASS Python environment. It walks the HDF5 dataset, repacks per-episode
+into LeRobot's parquet format, and emits the chunk + metadata layout that
+GR00T's training pipeline expects.
+
+## Step 2 — Post-train GR00T
+
+Follow the post-training instructions in the
+[Isaac-GR00T getting-started guide](https://github.com/NVIDIA/Isaac-GR00T/tree/main/getting_started).
+
+A ready-to-use navigation data configuration lives on this branch:
+[`liuw/nav_fine_tune`](https://github.com/NVIDIA/Isaac-GR00T/compare/main...liuw/nav_fine_tune).
+
+## Step 3 — Evaluate the post-trained GR00T model in COMPASS
+
+Launch the GR00T inference server (see the Isaac-GR00T repo) on
+**port 8888**, with the same data configuration you used during training.
+Then evaluate from COMPASS:
+
+```bash
+python run.py \
+ -c configs/eval_config.gin \
+ -o \
+ -b \
+ --enable_cameras \
+ --gr00t-policy
+```
+
+`--gr00t-policy` tells `run.py` to dispatch action queries to the inference
+server instead of loading a local checkpoint. Eval parameters (scene,
+embodiment, episode count) live in
+[`configs/eval_config.gin`](https://github.com/NVlabs/COMPASS/blob/main/configs/eval_config.gin).
diff --git a/docs/handbook/workflows/recording.md b/docs/handbook/workflows/recording.md
new file mode 100644
index 0000000..1023ce5
--- /dev/null
+++ b/docs/handbook/workflows/recording.md
@@ -0,0 +1,45 @@
+# Recording distillation data
+
+`record.py` rolls out trained specialists across embodiments / scenes and
+writes the trajectories as HDF5 files. The resulting dataset feeds the
+[generalist distillation step](distillation.md).
+
+## Run a recording
+
+1. **Configure which specialists to record from**: edit
+ [`configs/distillation_dataset_config_template.yaml`](https://github.com/NVlabs/COMPASS/blob/main/configs/distillation_dataset_config_template.yaml)
+ to point at your per-embodiment specialist checkpoints and split ratios.
+ Save it as `configs/distillation_dataset_config.yaml` (or anywhere; pass
+ the path on the command line).
+
+2. **Roll out**:
+
+ ```bash
+ python record.py \
+ -c configs/distillation_dataset_config.yaml \
+ -o \
+ -b \
+ --dataset-name
+ ```
+
+The dataset name appears in OSMO references and in the HDF5 file metadata. It
+is the same identifier used by [`scripts/hdf5_to_lerobot_episodic.py`](https://github.com/NVlabs/COMPASS/blob/main/scripts/hdf5_to_lerobot_episodic.py)
+for [GR00T post-training](gr00t_finetuning.md).
+
+## Output layout
+
+`record.py` writes one HDF5 file per shard, plus a manifest, under
+`/`. Each HDF5 file contains episodic data with the standard
+COMPASS observation keys (camera, lidar, proprio, …) and the action emitted
+by the specialist. The shape convention is `[T, S, ...]` (timesteps × shards).
+
+## On OSMO
+
+```bash
+python osmo/run_osmo.py record \
+ --experiment-name \
+ --dataset-name \
+ --base-policy-ckpt
+```
+
+Full reference: [OSMO cloud submission](../osmo.md).
diff --git a/docs/handbook/workflows/training.md b/docs/handbook/workflows/training.md
new file mode 100644
index 0000000..ee74b66
--- /dev/null
+++ b/docs/handbook/workflows/training.md
@@ -0,0 +1,78 @@
+# Training residual RL specialists
+
+`run.py` trains a residual RL policy on top of the X-Mobility base policy for a
+given embodiment + scene. The residual head adapts X-Mobility's
+language-conditioned navigation behaviour to embodiment-specific dynamics.
+
+## Default training run
+
+```bash
+python run.py \
+ -c configs/train_config.gin \
+ -o \
+ -b \
+ --enable_cameras
+```
+
+(Inside an [activated dev shell](../installation/docker.md), `python` already
+points at Isaac Sim's bundled Python; on a bare-metal install, prefix with
+`${ISAACLAB_PATH}/isaaclab.sh -p`.)
+
+## Evaluating a trained specialist
+
+```bash
+python run.py \
+ -c configs/eval_config.gin \
+ -o \
+ -b \
+ -p \
+ --enable_cameras \
+ --video \
+ --video_interval
+```
+
+## GPU memory and `--num_envs`
+
+GPU memory scales linearly with the parallel-env count: **32 envs ≈ 30 GB**.
+Drop `--num_envs` to fit the host. `--num_envs 1` is the canonical smoke-test
+setting and reaches PPO iteration 0 in a few minutes.
+
+## Picking embodiment / scene
+
+Override the gin defaults via CLI:
+
+```bash
+python run.py -c configs/train_config.gin \
+ --embodiment {h1,carter,spot,g1,digit} \
+ --environment \
+ -o -b
+```
+
+The current set lives in `EmbodimentEnvCfgMap` and `EnvSceneAssetCfgMap` in
+[`run.py`](https://github.com/NVlabs/COMPASS/blob/main/run.py). To register a
+new one, see [Adding a new embodiment / scene](../extending.md).
+
+## Logging
+
+TensorBoard at `/tensorboard/` by default. For Weights & Biases
+add:
+
+```bash
+--logger wandb \
+--wandb-project-name \
+--wandb-run-name \
+--wandb-entity-name
+```
+
+## Submitting to OSMO
+
+Train on the OSMO cluster instead of locally:
+
+```bash
+python osmo/run_osmo.py train \
+ --experiment-name \
+ --image \
+ --base-policy-ckpt
+```
+
+Full reference: [OSMO cloud submission](../osmo.md).
diff --git a/docs/project_page/LICENSE b/docs/project_page/LICENSE
new file mode 100644
index 0000000..261eeb9
--- /dev/null
+++ b/docs/project_page/LICENSE
@@ -0,0 +1,201 @@
+ Apache License
+ Version 2.0, January 2004
+ http://www.apache.org/licenses/
+
+ TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
+
+ 1. Definitions.
+
+ "License" shall mean the terms and conditions for use, reproduction,
+ and distribution as defined by Sections 1 through 9 of this document.
+
+ "Licensor" shall mean the copyright owner or entity authorized by
+ the copyright owner that is granting the License.
+
+ "Legal Entity" shall mean the union of the acting entity and all
+ other entities that control, are controlled by, or are under common
+ control with that entity. For the purposes of this definition,
+ "control" means (i) the power, direct or indirect, to cause the
+ direction or management of such entity, whether by contract or
+ otherwise, or (ii) ownership of fifty percent (50%) or more of the
+ outstanding shares, or (iii) beneficial ownership of such entity.
+
+ "You" (or "Your") shall mean an individual or Legal Entity
+ exercising permissions granted by this License.
+
+ "Source" form shall mean the preferred form for making modifications,
+ including but not limited to software source code, documentation
+ source, and configuration files.
+
+ "Object" form shall mean any form resulting from mechanical
+ transformation or translation of a Source form, including but
+ not limited to compiled object code, generated documentation,
+ and conversions to other media types.
+
+ "Work" shall mean the work of authorship, whether in Source or
+ Object form, made available under the License, as indicated by a
+ copyright notice that is included in or attached to the work
+ (an example is provided in the Appendix below).
+
+ "Derivative Works" shall mean any work, whether in Source or Object
+ form, that is based on (or derived from) the Work and for which the
+ editorial revisions, annotations, elaborations, or other modifications
+ represent, as a whole, an original work of authorship. For the purposes
+ of this License, Derivative Works shall not include works that remain
+ separable from, or merely link (or bind by name) to the interfaces of,
+ the Work and Derivative Works thereof.
+
+ "Contribution" shall mean any work of authorship, including
+ the original version of the Work and any modifications or additions
+ to that Work or Derivative Works thereof, that is intentionally
+ submitted to Licensor for inclusion in the Work by the copyright owner
+ or by an individual or Legal Entity authorized to submit on behalf of
+ the copyright owner. For the purposes of this definition, "submitted"
+ means any form of electronic, verbal, or written communication sent
+ to the Licensor or its representatives, including but not limited to
+ communication on electronic mailing lists, source code control systems,
+ and issue tracking systems that are managed by, or on behalf of, the
+ Licensor for the purpose of discussing and improving the Work, but
+ excluding communication that is conspicuously marked or otherwise
+ designated in writing by the copyright owner as "Not a Contribution."
+
+ "Contributor" shall mean Licensor and any individual or Legal Entity
+ on behalf of whom a Contribution has been received by Licensor and
+ subsequently incorporated within the Work.
+
+ 2. Grant of Copyright License. Subject to the terms and conditions of
+ this License, each Contributor hereby grants to You a perpetual,
+ worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+ copyright license to reproduce, prepare Derivative Works of,
+ publicly display, publicly perform, sublicense, and distribute the
+ Work and such Derivative Works in Source or Object form.
+
+ 3. Grant of Patent License. Subject to the terms and conditions of
+ this License, each Contributor hereby grants to You a perpetual,
+ worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+ (except as stated in this section) patent license to make, have made,
+ use, offer to sell, sell, import, and otherwise transfer the Work,
+ where such license applies only to those patent claims licensable
+ by such Contributor that are necessarily infringed by their
+ Contribution(s) alone or by combination of their Contribution(s)
+ with the Work to which such Contribution(s) was submitted. If You
+ institute patent litigation against any entity (including a
+ cross-claim or counterclaim in a lawsuit) alleging that the Work
+ or a Contribution incorporated within the Work constitutes direct
+ or contributory patent infringement, then any patent licenses
+ granted to You under this License for that Work shall terminate
+ as of the date such litigation is filed.
+
+ 4. Redistribution. You may reproduce and distribute copies of the
+ Work or Derivative Works thereof in any medium, with or without
+ modifications, and in Source or Object form, provided that You
+ meet the following conditions:
+
+ (a) You must give any other recipients of the Work or
+ Derivative Works a copy of this License; and
+
+ (b) You must cause any modified files to carry prominent notices
+ stating that You changed the files; and
+
+ (c) You must retain, in the Source form of any Derivative Works
+ that You distribute, all copyright, patent, trademark, and
+ attribution notices from the Source form of the Work,
+ excluding those notices that do not pertain to any part of
+ the Derivative Works; and
+
+ (d) If the Work includes a "NOTICE" text file as part of its
+ distribution, then any Derivative Works that You distribute must
+ include a readable copy of the attribution notices contained
+ within such NOTICE file, excluding those notices that do not
+ pertain to any part of the Derivative Works, in at least one
+ of the following places: within a NOTICE text file distributed
+ as part of the Derivative Works; within the Source form or
+ documentation, if provided along with the Derivative Works; or,
+ within a display generated by the Derivative Works, if and
+ wherever such third-party notices normally appear. The contents
+ of the NOTICE file are for informational purposes only and
+ do not modify the License. You may add Your own attribution
+ notices within Derivative Works that You distribute, alongside
+ or as an addendum to the NOTICE text from the Work, provided
+ that such additional attribution notices cannot be construed
+ as modifying the License.
+
+ You may add Your own copyright statement to Your modifications and
+ may provide additional or different license terms and conditions
+ for use, reproduction, or distribution of Your modifications, or
+ for any such Derivative Works as a whole, provided Your use,
+ reproduction, and distribution of the Work otherwise complies with
+ the conditions stated in this License.
+
+ 5. Submission of Contributions. Unless You explicitly state otherwise,
+ any Contribution intentionally submitted for inclusion in the Work
+ by You to the Licensor shall be under the terms and conditions of
+ this License, without any additional terms or conditions.
+ Notwithstanding the above, nothing herein shall supersede or modify
+ the terms of any separate license agreement you may have executed
+ with Licensor regarding such Contributions.
+
+ 6. Trademarks. This License does not grant permission to use the trade
+ names, trademarks, service marks, or product names of the Licensor,
+ except as required for reasonable and customary use in describing the
+ origin of the Work and reproducing the content of the NOTICE file.
+
+ 7. Disclaimer of Warranty. Unless required by applicable law or
+ agreed to in writing, Licensor provides the Work (and each
+ Contributor provides its Contributions) on an "AS IS" BASIS,
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
+ implied, including, without limitation, any warranties or conditions
+ of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
+ PARTICULAR PURPOSE. You are solely responsible for determining the
+ appropriateness of using or redistributing the Work and assume any
+ risks associated with Your exercise of permissions under this License.
+
+ 8. Limitation of Liability. In no event and under no legal theory,
+ whether in tort (including negligence), contract, or otherwise,
+ unless required by applicable law (such as deliberate and grossly
+ negligent acts) or agreed to in writing, shall any Contributor be
+ liable to You for damages, including any direct, indirect, special,
+ incidental, or consequential damages of any character arising as a
+ result of this License or out of the use or inability to use the
+ Work (including but not limited to damages for loss of goodwill,
+ work stoppage, computer failure or malfunction, or any and all
+ other commercial damages or losses), even if such Contributor
+ has been advised of the possibility of such damages.
+
+ 9. Accepting Warranty or Additional Liability. While redistributing
+ the Work or Derivative Works thereof, You may choose to offer,
+ and charge a fee for, acceptance of support, warranty, indemnity,
+ or other liability obligations and/or rights consistent with this
+ License. However, in accepting such obligations, You may act only
+ on Your own behalf and on Your sole responsibility, not on behalf
+ of any other Contributor, and only if You agree to indemnify,
+ defend, and hold each Contributor harmless for any liability
+ incurred by, or claims asserted against, such Contributor by reason
+ of your accepting any such warranty or additional liability.
+
+ END OF TERMS AND CONDITIONS
+
+ APPENDIX: How to apply the Apache License to your work.
+
+ To apply the Apache License to your work, attach the following
+ boilerplate notice, with the fields enclosed by brackets "[]"
+ replaced with your own identifying information. (Don't include
+ the brackets!) The text should be enclosed in the appropriate
+ comment syntax for the file format. We also recommend that a
+ file or class name and description of purpose be included on the
+ same "printed page" as the copyright notice for easier
+ identification within third-party archives.
+
+ Copyright [yyyy] [name of copyright owner]
+
+ Licensed under the Apache License, Version 2.0 (the "License");
+ you may not use this file except in compliance with the License.
+ You may obtain a copy of the License at
+
+ http://www.apache.org/licenses/LICENSE-2.0
+
+ Unless required by applicable law or agreed to in writing, software
+ distributed under the License is distributed on an "AS IS" BASIS,
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ See the License for the specific language governing permissions and
+ limitations under the License.
diff --git a/docs/project_page/README.md b/docs/project_page/README.md
new file mode 100644
index 0000000..f441ba4
--- /dev/null
+++ b/docs/project_page/README.md
@@ -0,0 +1,2 @@
+# COMPASS
+Cross-embOdiment Mobility Policy via ResiduAl RL and Skill Synthesis
diff --git a/docs/project_page/index.html b/docs/project_page/index.html
new file mode 100644
index 0000000..27f69c9
--- /dev/null
+++ b/docs/project_page/index.html
@@ -0,0 +1,347 @@
+
+
+
+
+
+
+
+ COMPASS: Cross-embodiment Mobility Policy via Residual RL and Skill Synthesis
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ COMPASS : C ross-embO diment M obility P olicy
+ via ResiduA l RL and S kill S ynthesis
+
+
+
+ Wei Liu1 ,
+
+ Huihua Zhao1 ,
+
+ Chenran Li1,2 ,
+
+
+ Yuchen Deng1 ,
+
+
+ Joydeep Biswas1,3 ,
+
+
+ Soha Pouya1 ,
+
+
+ Yan Chang1
+
+
+
+
+ 1 NVIDIA,
+ 2 UC Berkeley
+ 3 UT Austin
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
Abstract
+
+
+ As robots are increasingly deployed in diverse application domains, enabling robust mobility across different embodiments has become a critical challenge. Classical mobility stacks, though effective on specific platforms, require extensive per-robot tuning and do not scale easily to new embodiments. Learning-based approaches, such as imitation learning (IL), offer alternatives, but face significant limitations on the need for high-quality demonstrations for each embodiment.
+
+
+ To address these challenges, we introduce COMPASS, a unified framework that enables scalable cross-embodiment mobility using expert demonstrations from only a single embodiment. We first pre-train a mobility policy on a single robot using IL, combining a world model with a policy model. We then apply residual reinforcement learning (RL) to efficiently adapt this policy to diverse embodiments through corrective refinements. Finally, we distill specialist policies into a single generalist policy conditioned on an embodiment embedding vector. This design significantly reduces the burden of collecting data while enabling robust generalization across a wide range of robot designs. Our experiments demonstrate that COMPASS scales effectively across diverse robot platforms while maintaining adaptability to various environment configurations, achieving a generalist policy with a success rate approximately 5X higher than the pre-trained IL policy, and further demonstrates zero-shot sim-to-real transfer.
+
+
+
+
+
+
+
+
+
+
+
+
+
+
Method
+
+
+
+
+
+
+
+
+
+
+
+
+
+ COMPASS introduces a novel three-stage learning workflow for developing cross-embodiment mobility policies:
+
+
+ Imitation Learning: We first train a foundational model that combines a world model with a mobility policy using easily accessible teacher policies.
+ Residual RL: Building on the base policy, we employ residual reinforcement learning to fine-tune embodiment-specific policies, handling various physical constraints and sensor modalities.
+ Policy Distillation: Finally, we merge these embodiment-specialist policies into a single robust cross-embodiment policy through policy distillation.
+
+
+ This approach enables efficient transfer of mobility skills across diverse robot platforms while maintaining adaptability to various environment configurations.
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
Results
+
+
+ Extensive experiments demonstrate that COMPASS can achieve robust generalization across diverse robot platforms while preserving the adaptability needed to succeed in varied environments. Quantitatively, the RL specialists and the distilled generalist policy can achieve a 5X higher success rate and 3X lower travel time on average than the pre-trained IL policy (X-Mobility).
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
Zero-shot Sim2Real Transfer
+
+
+ COMPASS policies trained in simulation can be directly deployed on real robots, demonstrating strong sim2real transfer capabilities without additional fine-tuning.
+
+
+
+
+
+
+
+
+
+
Real-world deployment of COMPASS policy on real robots: Carter and G1.
+
+
+
+
+
+
+
+
+
+
+
Open Vocabulary Object Navigation
+
+
+ Open Vocabulary Object Navigation by integrating Locate3D with COMPASS.
+
+
+
+
+
+
COMPASS policy performing open vocabulary object navigation by integrating Locate3D.
+
+
+
+
+
+
+
+
GR00T Post-training with COMPASS Datasets
+
+
+ GR00T Post-training with COMPASS distillation datasets, enabling navigation capabilities.
+
+
+
+
+
+
GR00T post-training with COMPASS datasets for navigation.
+
+
+
+
+
+
+
+
BibTeX
+
+ @article{liu2025compass,
+ title={COMPASS: Cross-embodiment Mobility Policy via Residual RL and Skill Synthesis},
+ author={Liu, Wei and Zhao, Huihua and Li, Chenran and Deng, Yuchen and Biswas, Joydeep and Pouya, Soha and Chang, Yan},
+ journal={arXiv preprint arXiv:2502.16372},
+ year={2025}
+ }
+
+
+
+
+
+
+
+
+
+
diff --git a/docs/project_page/static/css/bulma-carousel.min.css b/docs/project_page/static/css/bulma-carousel.min.css
new file mode 100644
index 0000000..46c20eb
--- /dev/null
+++ b/docs/project_page/static/css/bulma-carousel.min.css
@@ -0,0 +1 @@
+@-webkit-keyframes spinAround{from{-webkit-transform:rotate(0);transform:rotate(0)}to{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}@keyframes spinAround{from{-webkit-transform:rotate(0);transform:rotate(0)}to{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}.slider{position:relative;width:100%}.slider-container{display:flex;flex-wrap:nowrap;flex-direction:row;overflow:hidden;-webkit-transform:translate3d(0,0,0);transform:translate3d(0,0,0);min-height:100%}.slider-container.is-vertical{flex-direction:column}.slider-container .slider-item{flex:none}.slider-container .slider-item .image.is-covered img{-o-object-fit:cover;object-fit:cover;-o-object-position:center center;object-position:center center;height:100%;width:100%}.slider-container .slider-item .video-container{height:0;padding-bottom:0;padding-top:56.25%;margin:0;position:relative}.slider-container .slider-item .video-container.is-1by1,.slider-container .slider-item .video-container.is-square{padding-top:100%}.slider-container .slider-item .video-container.is-4by3{padding-top:75%}.slider-container .slider-item .video-container.is-21by9{padding-top:42.857143%}.slider-container .slider-item .video-container embed,.slider-container .slider-item .video-container iframe,.slider-container .slider-item .video-container object{position:absolute;top:0;left:0;width:100%!important;height:100%!important}.slider-navigation-next,.slider-navigation-previous{display:flex;justify-content:center;align-items:center;position:absolute;width:42px;height:42px;background:#fff center center no-repeat;background-size:20px 20px;border:1px solid #fff;border-radius:25091983px;box-shadow:0 2px 5px #3232321a;top:50%;margin-top:-20px;left:0;cursor:pointer;transition:opacity .3s,-webkit-transform .3s;transition:transform .3s,opacity .3s;transition:transform .3s,opacity .3s,-webkit-transform .3s}.slider-navigation-next:hover,.slider-navigation-previous:hover{-webkit-transform:scale(1.2);transform:scale(1.2)}.slider-navigation-next.is-hidden,.slider-navigation-previous.is-hidden{display:none;opacity:0}.slider-navigation-next svg,.slider-navigation-previous svg{width:25%}.slider-navigation-next{left:auto;right:0;background:#fff center center no-repeat;background-size:20px 20px}.slider-pagination{display:none;justify-content:center;align-items:center;position:absolute;bottom:0;left:0;right:0;padding:.5rem 1rem;text-align:center}.slider-pagination .slider-page{background:#fff;width:10px;height:10px;border-radius:25091983px;display:inline-block;margin:0 3px;box-shadow:0 2px 5px #3232321a;transition:-webkit-transform .3s;transition:transform .3s;transition:transform .3s,-webkit-transform .3s;cursor:pointer}.slider-pagination .slider-page.is-active,.slider-pagination .slider-page:hover{-webkit-transform:scale(1.4);transform:scale(1.4)}@media screen and (min-width:800px){.slider-pagination{display:flex}}.hero.has-carousel{position:relative}.hero.has-carousel+.hero-body,.hero.has-carousel+.hero-footer,.hero.has-carousel+.hero-head{z-index:10;overflow:hidden}.hero.has-carousel .hero-carousel{position:absolute;top:0;left:0;bottom:0;right:0;height:auto;border:none;margin:auto;padding:0;z-index:0}.hero.has-carousel .hero-carousel .slider{width:100%;max-width:100%;overflow:hidden;height:100%!important;max-height:100%;z-index:0}.hero.has-carousel .hero-carousel .slider .has-background{max-height:100%}.hero.has-carousel .hero-carousel .slider .has-background .is-background{-o-object-fit:cover;object-fit:cover;-o-object-position:center center;object-position:center center;height:100%;width:100%}.hero.has-carousel .hero-body{margin:0 3rem;z-index:10}
diff --git a/docs/project_page/static/css/bulma-slider.min.css b/docs/project_page/static/css/bulma-slider.min.css
new file mode 100644
index 0000000..83c6d28
--- /dev/null
+++ b/docs/project_page/static/css/bulma-slider.min.css
@@ -0,0 +1 @@
+@-webkit-keyframes spinAround{from{-webkit-transform:rotate(0);transform:rotate(0)}to{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}@keyframes spinAround{from{-webkit-transform:rotate(0);transform:rotate(0)}to{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}input[type=range].slider{-webkit-appearance:none;-moz-appearance:none;appearance:none;margin:1rem 0;background:0 0;touch-action:none}input[type=range].slider.is-fullwidth{display:block;width:100%}input[type=range].slider:focus{outline:0}input[type=range].slider:not([orient=vertical])::-webkit-slider-runnable-track{width:100%}input[type=range].slider:not([orient=vertical])::-moz-range-track{width:100%}input[type=range].slider:not([orient=vertical])::-ms-track{width:100%}input[type=range].slider:not([orient=vertical]).has-output+output,input[type=range].slider:not([orient=vertical]).has-output-tooltip+output{width:3rem;background:#4a4a4a;border-radius:4px;padding:.4rem .8rem;font-size:.75rem;line-height:.75rem;text-align:center;text-overflow:ellipsis;white-space:nowrap;color:#fff;overflow:hidden;pointer-events:none;z-index:200}input[type=range].slider:not([orient=vertical]).has-output-tooltip:disabled+output,input[type=range].slider:not([orient=vertical]).has-output:disabled+output{opacity:.5}input[type=range].slider:not([orient=vertical]).has-output{display:inline-block;vertical-align:middle;width:calc(100% - (4.2rem))}input[type=range].slider:not([orient=vertical]).has-output+output{display:inline-block;margin-left:.75rem;vertical-align:middle}input[type=range].slider:not([orient=vertical]).has-output-tooltip{display:block}input[type=range].slider:not([orient=vertical]).has-output-tooltip+output{position:absolute;left:0;top:-.1rem}input[type=range].slider[orient=vertical]{-webkit-appearance:slider-vertical;-moz-appearance:slider-vertical;appearance:slider-vertical;-webkit-writing-mode:bt-lr;-ms-writing-mode:bt-lr;writing-mode:bt-lr}input[type=range].slider[orient=vertical]::-webkit-slider-runnable-track{height:100%}input[type=range].slider[orient=vertical]::-moz-range-track{height:100%}input[type=range].slider[orient=vertical]::-ms-track{height:100%}input[type=range].slider::-webkit-slider-runnable-track{cursor:pointer;animate:.2s;box-shadow:0 0 0 #7a7a7a;background:#dbdbdb;border-radius:4px;border:0 solid #7a7a7a}input[type=range].slider::-moz-range-track{cursor:pointer;animate:.2s;box-shadow:0 0 0 #7a7a7a;background:#dbdbdb;border-radius:4px;border:0 solid #7a7a7a}input[type=range].slider::-ms-track{cursor:pointer;animate:.2s;box-shadow:0 0 0 #7a7a7a;background:#dbdbdb;border-radius:4px;border:0 solid #7a7a7a}input[type=range].slider::-ms-fill-lower{background:#dbdbdb;border-radius:4px}input[type=range].slider::-ms-fill-upper{background:#dbdbdb;border-radius:4px}input[type=range].slider::-webkit-slider-thumb{box-shadow:none;border:1px solid #b5b5b5;border-radius:4px;background:#fff;cursor:pointer}input[type=range].slider::-moz-range-thumb{box-shadow:none;border:1px solid #b5b5b5;border-radius:4px;background:#fff;cursor:pointer}input[type=range].slider::-ms-thumb{box-shadow:none;border:1px solid #b5b5b5;border-radius:4px;background:#fff;cursor:pointer}input[type=range].slider::-webkit-slider-thumb{-webkit-appearance:none;appearance:none}input[type=range].slider.is-circle::-webkit-slider-thumb{border-radius:290486px}input[type=range].slider.is-circle::-moz-range-thumb{border-radius:290486px}input[type=range].slider.is-circle::-ms-thumb{border-radius:290486px}input[type=range].slider:active::-webkit-slider-thumb{-webkit-transform:scale(1.25);transform:scale(1.25)}input[type=range].slider:active::-moz-range-thumb{transform:scale(1.25)}input[type=range].slider:active::-ms-thumb{transform:scale(1.25)}input[type=range].slider:disabled{opacity:.5;cursor:not-allowed}input[type=range].slider:disabled::-webkit-slider-thumb{cursor:not-allowed;-webkit-transform:scale(1);transform:scale(1)}input[type=range].slider:disabled::-moz-range-thumb{cursor:not-allowed;transform:scale(1)}input[type=range].slider:disabled::-ms-thumb{cursor:not-allowed;transform:scale(1)}input[type=range].slider:not([orient=vertical]){min-height:calc((1rem + 2px) * 1.25)}input[type=range].slider:not([orient=vertical])::-webkit-slider-runnable-track{height:.5rem}input[type=range].slider:not([orient=vertical])::-moz-range-track{height:.5rem}input[type=range].slider:not([orient=vertical])::-ms-track{height:.5rem}input[type=range].slider[orient=vertical]::-webkit-slider-runnable-track{width:.5rem}input[type=range].slider[orient=vertical]::-moz-range-track{width:.5rem}input[type=range].slider[orient=vertical]::-ms-track{width:.5rem}input[type=range].slider::-webkit-slider-thumb{height:1rem;width:1rem}input[type=range].slider::-moz-range-thumb{height:1rem;width:1rem}input[type=range].slider::-ms-thumb{height:1rem;width:1rem}input[type=range].slider::-ms-thumb{margin-top:0}input[type=range].slider::-webkit-slider-thumb{margin-top:-.25rem}input[type=range].slider[orient=vertical]::-webkit-slider-thumb{margin-top:auto;margin-left:-.25rem}input[type=range].slider.is-small:not([orient=vertical]){min-height:calc((.75rem + 2px) * 1.25)}input[type=range].slider.is-small:not([orient=vertical])::-webkit-slider-runnable-track{height:.375rem}input[type=range].slider.is-small:not([orient=vertical])::-moz-range-track{height:.375rem}input[type=range].slider.is-small:not([orient=vertical])::-ms-track{height:.375rem}input[type=range].slider.is-small[orient=vertical]::-webkit-slider-runnable-track{width:.375rem}input[type=range].slider.is-small[orient=vertical]::-moz-range-track{width:.375rem}input[type=range].slider.is-small[orient=vertical]::-ms-track{width:.375rem}input[type=range].slider.is-small::-webkit-slider-thumb{height:.75rem;width:.75rem}input[type=range].slider.is-small::-moz-range-thumb{height:.75rem;width:.75rem}input[type=range].slider.is-small::-ms-thumb{height:.75rem;width:.75rem}input[type=range].slider.is-small::-ms-thumb{margin-top:0}input[type=range].slider.is-small::-webkit-slider-thumb{margin-top:-.1875rem}input[type=range].slider.is-small[orient=vertical]::-webkit-slider-thumb{margin-top:auto;margin-left:-.1875rem}input[type=range].slider.is-medium:not([orient=vertical]){min-height:calc((1.25rem + 2px) * 1.25)}input[type=range].slider.is-medium:not([orient=vertical])::-webkit-slider-runnable-track{height:.625rem}input[type=range].slider.is-medium:not([orient=vertical])::-moz-range-track{height:.625rem}input[type=range].slider.is-medium:not([orient=vertical])::-ms-track{height:.625rem}input[type=range].slider.is-medium[orient=vertical]::-webkit-slider-runnable-track{width:.625rem}input[type=range].slider.is-medium[orient=vertical]::-moz-range-track{width:.625rem}input[type=range].slider.is-medium[orient=vertical]::-ms-track{width:.625rem}input[type=range].slider.is-medium::-webkit-slider-thumb{height:1.25rem;width:1.25rem}input[type=range].slider.is-medium::-moz-range-thumb{height:1.25rem;width:1.25rem}input[type=range].slider.is-medium::-ms-thumb{height:1.25rem;width:1.25rem}input[type=range].slider.is-medium::-ms-thumb{margin-top:0}input[type=range].slider.is-medium::-webkit-slider-thumb{margin-top:-.3125rem}input[type=range].slider.is-medium[orient=vertical]::-webkit-slider-thumb{margin-top:auto;margin-left:-.3125rem}input[type=range].slider.is-large:not([orient=vertical]){min-height:calc((1.5rem + 2px) * 1.25)}input[type=range].slider.is-large:not([orient=vertical])::-webkit-slider-runnable-track{height:.75rem}input[type=range].slider.is-large:not([orient=vertical])::-moz-range-track{height:.75rem}input[type=range].slider.is-large:not([orient=vertical])::-ms-track{height:.75rem}input[type=range].slider.is-large[orient=vertical]::-webkit-slider-runnable-track{width:.75rem}input[type=range].slider.is-large[orient=vertical]::-moz-range-track{width:.75rem}input[type=range].slider.is-large[orient=vertical]::-ms-track{width:.75rem}input[type=range].slider.is-large::-webkit-slider-thumb{height:1.5rem;width:1.5rem}input[type=range].slider.is-large::-moz-range-thumb{height:1.5rem;width:1.5rem}input[type=range].slider.is-large::-ms-thumb{height:1.5rem;width:1.5rem}input[type=range].slider.is-large::-ms-thumb{margin-top:0}input[type=range].slider.is-large::-webkit-slider-thumb{margin-top:-.375rem}input[type=range].slider.is-large[orient=vertical]::-webkit-slider-thumb{margin-top:auto;margin-left:-.375rem}input[type=range].slider.is-white::-moz-range-track{background:#fff!important}input[type=range].slider.is-white::-webkit-slider-runnable-track{background:#fff!important}input[type=range].slider.is-white::-ms-track{background:#fff!important}input[type=range].slider.is-white::-ms-fill-lower{background:#fff}input[type=range].slider.is-white::-ms-fill-upper{background:#fff}input[type=range].slider.is-white .has-output-tooltip+output,input[type=range].slider.is-white.has-output+output{background-color:#fff;color:#0a0a0a}input[type=range].slider.is-black::-moz-range-track{background:#0a0a0a!important}input[type=range].slider.is-black::-webkit-slider-runnable-track{background:#0a0a0a!important}input[type=range].slider.is-black::-ms-track{background:#0a0a0a!important}input[type=range].slider.is-black::-ms-fill-lower{background:#0a0a0a}input[type=range].slider.is-black::-ms-fill-upper{background:#0a0a0a}input[type=range].slider.is-black .has-output-tooltip+output,input[type=range].slider.is-black.has-output+output{background-color:#0a0a0a;color:#fff}input[type=range].slider.is-light::-moz-range-track{background:#f5f5f5!important}input[type=range].slider.is-light::-webkit-slider-runnable-track{background:#f5f5f5!important}input[type=range].slider.is-light::-ms-track{background:#f5f5f5!important}input[type=range].slider.is-light::-ms-fill-lower{background:#f5f5f5}input[type=range].slider.is-light::-ms-fill-upper{background:#f5f5f5}input[type=range].slider.is-light .has-output-tooltip+output,input[type=range].slider.is-light.has-output+output{background-color:#f5f5f5;color:#363636}input[type=range].slider.is-dark::-moz-range-track{background:#363636!important}input[type=range].slider.is-dark::-webkit-slider-runnable-track{background:#363636!important}input[type=range].slider.is-dark::-ms-track{background:#363636!important}input[type=range].slider.is-dark::-ms-fill-lower{background:#363636}input[type=range].slider.is-dark::-ms-fill-upper{background:#363636}input[type=range].slider.is-dark .has-output-tooltip+output,input[type=range].slider.is-dark.has-output+output{background-color:#363636;color:#f5f5f5}input[type=range].slider.is-primary::-moz-range-track{background:#00d1b2!important}input[type=range].slider.is-primary::-webkit-slider-runnable-track{background:#00d1b2!important}input[type=range].slider.is-primary::-ms-track{background:#00d1b2!important}input[type=range].slider.is-primary::-ms-fill-lower{background:#00d1b2}input[type=range].slider.is-primary::-ms-fill-upper{background:#00d1b2}input[type=range].slider.is-primary .has-output-tooltip+output,input[type=range].slider.is-primary.has-output+output{background-color:#00d1b2;color:#fff}input[type=range].slider.is-link::-moz-range-track{background:#3273dc!important}input[type=range].slider.is-link::-webkit-slider-runnable-track{background:#3273dc!important}input[type=range].slider.is-link::-ms-track{background:#3273dc!important}input[type=range].slider.is-link::-ms-fill-lower{background:#3273dc}input[type=range].slider.is-link::-ms-fill-upper{background:#3273dc}input[type=range].slider.is-link .has-output-tooltip+output,input[type=range].slider.is-link.has-output+output{background-color:#3273dc;color:#fff}input[type=range].slider.is-info::-moz-range-track{background:#209cee!important}input[type=range].slider.is-info::-webkit-slider-runnable-track{background:#209cee!important}input[type=range].slider.is-info::-ms-track{background:#209cee!important}input[type=range].slider.is-info::-ms-fill-lower{background:#209cee}input[type=range].slider.is-info::-ms-fill-upper{background:#209cee}input[type=range].slider.is-info .has-output-tooltip+output,input[type=range].slider.is-info.has-output+output{background-color:#209cee;color:#fff}input[type=range].slider.is-success::-moz-range-track{background:#23d160!important}input[type=range].slider.is-success::-webkit-slider-runnable-track{background:#23d160!important}input[type=range].slider.is-success::-ms-track{background:#23d160!important}input[type=range].slider.is-success::-ms-fill-lower{background:#23d160}input[type=range].slider.is-success::-ms-fill-upper{background:#23d160}input[type=range].slider.is-success .has-output-tooltip+output,input[type=range].slider.is-success.has-output+output{background-color:#23d160;color:#fff}input[type=range].slider.is-warning::-moz-range-track{background:#ffdd57!important}input[type=range].slider.is-warning::-webkit-slider-runnable-track{background:#ffdd57!important}input[type=range].slider.is-warning::-ms-track{background:#ffdd57!important}input[type=range].slider.is-warning::-ms-fill-lower{background:#ffdd57}input[type=range].slider.is-warning::-ms-fill-upper{background:#ffdd57}input[type=range].slider.is-warning .has-output-tooltip+output,input[type=range].slider.is-warning.has-output+output{background-color:#ffdd57;color:rgba(0,0,0,.7)}input[type=range].slider.is-danger::-moz-range-track{background:#ff3860!important}input[type=range].slider.is-danger::-webkit-slider-runnable-track{background:#ff3860!important}input[type=range].slider.is-danger::-ms-track{background:#ff3860!important}input[type=range].slider.is-danger::-ms-fill-lower{background:#ff3860}input[type=range].slider.is-danger::-ms-fill-upper{background:#ff3860}input[type=range].slider.is-danger .has-output-tooltip+output,input[type=range].slider.is-danger.has-output+output{background-color:#ff3860;color:#fff}
diff --git a/docs/project_page/static/css/bulma.css.map.txt b/docs/project_page/static/css/bulma.css.map.txt
new file mode 100644
index 0000000..cf91f8d
--- /dev/null
+++ b/docs/project_page/static/css/bulma.css.map.txt
@@ -0,0 +1 @@
+{"version":3,"sources":["../bulma.sass","../sass/utilities/_all.sass","../sass/utilities/animations.sass","bulma.css","../sass/utilities/mixins.sass","../sass/utilities/initial-variables.sass","../sass/utilities/controls.sass","../sass/base/_all.sass","../sass/base/minireset.sass","../sass/base/generic.sass","../sass/utilities/derived-variables.sass","../sass/elements/_all.sass","../sass/elements/box.sass","../sass/elements/button.sass","../sass/utilities/functions.sass","../sass/elements/container.sass","../sass/elements/content.sass","../sass/elements/icon.sass","../sass/elements/image.sass","../sass/elements/notification.sass","../sass/elements/progress.sass","../sass/elements/table.sass","../sass/elements/tag.sass","../sass/elements/title.sass","../sass/elements/other.sass","../sass/form/_all.sass","../sass/form/shared.sass","../sass/form/input-textarea.sass","../sass/form/checkbox-radio.sass","../sass/form/select.sass","../sass/form/file.sass","../sass/form/tools.sass","../sass/components/_all.sass","../sass/components/breadcrumb.sass","../sass/components/card.sass","../sass/components/dropdown.sass","../sass/components/level.sass","../sass/components/media.sass","../sass/components/menu.sass","../sass/components/message.sass","../sass/components/modal.sass","../sass/components/navbar.sass","../sass/components/pagination.sass","../sass/components/panel.sass","../sass/components/tabs.sass","../sass/grid/_all.sass","../sass/grid/columns.sass","../sass/grid/tiles.sass","../sass/helpers/_all.sass","../sass/helpers/color.sass","../sass/helpers/flexbox.sass","../sass/helpers/float.sass","../sass/helpers/other.sass","../sass/helpers/overflow.sass","../sass/helpers/position.sass","../sass/helpers/spacing.sass","../sass/helpers/typography.sass","../sass/helpers/visibility.sass","../sass/layout/_all.sass","../sass/layout/hero.sass","../sass/layout/section.sass","../sass/layout/footer.sass"],"names":[],"mappings":"AACA,6DAAA;ACDA,oBAAA;ACAA;EACE;IACE,uBAAuB;ECGzB;EDFA;IACE,yBAAyB;ECI3B;AACF;ADTA;EACE;IACE,uBAAuB;ECGzB;EDFA;IACE,yBAAyB;ECI3B;AACF;;AC0JA;;;;EANE,2BAA2B;EAC3B,yBAAyB;EACzB,sBAAsB;EACtB,qBAAqB;EACrB,iBAAiB;AD7InB;;ACkKA;EAfE,6BAD8B;EAE9B,kBAAkB;EAClB,eAAe;EACf,aAAa;EACb,YAAY;EACZ,cAAc;EACd,eAAe;EACf,qBAAqB;EACrB,oBAAoB;EACpB,kBAAkB;EAClB,QAAQ;EACR,yBAAyB;EACzB,wBAAwB;EACxB,cAAc;AD/IhB;;ACqJE;;EACE,qBC3IkB;AFNtB;;ACwNA;EAhEE,qBAAqB;EACrB,wBAAwB;EACxB,uCClM2B;EDmM3B,YAAY;EACZ,uBC/HuB;EDgIvB,eAAe;EACf,oBAAoB;EACpB,qBAAqB;EACrB,YAAY;EACZ,cAAc;EACd,YAAY;EACZ,YAAY;EACZ,gBAAgB;EAChB,eAAe;EACf,gBAAgB;EAChB,eAAe;EACf,aAAa;EACb,kBAAkB;EAClB,mBAAmB;EACnB,WAAW;ADpJb;;ACqJE;EAEE,uBCzM2B;ED0M3B,WAAW;EACX,cAAc;EACd,SAAS;EACT,kBAAkB;EAClB,QAAQ;EACR,0DAA0D;EAC1D,+BAA+B;ADnJnC;;ACoJE;EACE,WAAW;EACX,UAAU;ADjJd;;ACkJE;EACE,WAAW;EACX,UAAU;AD/Id;;ACgJE;EAEE,uCCtOyB;AFwF7B;;AC+IE;EACE,uCCxOyB;AF4F7B;;AC8IE;EACE,YAAY;EACZ,gBAAgB;EAChB,eAAe;EACf,gBAAgB;EAChB,eAAe;EACf,WAAW;AD3If;;AC4IE;EACE,YAAY;EACZ,gBAAgB;EAChB,eAAe;EACf,gBAAgB;EAChB,eAAe;EACf,WAAW;ADzIf;;AC0IE;EACE,YAAY;EACZ,gBAAgB;EAChB,eAAe;EACf,gBAAgB;EAChB,eAAe;EACf,WAAW;ADvIf;;ACwJA;EAXE,mDAA2C;UAA3C,2CAA2C;EAC3C,yBC7P4B;ED8P5B,uBCjMuB;EDkMvB,+BAA+B;EAC/B,6BAA6B;EAC7B,WAAW;EACX,cAAc;EACd,WAAW;EACX,kBAAkB;EAClB,UAAU;ADzIZ;;ACqJA;;;;;;;;;;;;;;;;;EANE,SADuB;EAEvB,OAFuB;EAGvB,kBAAkB;EAClB,QAJuB;EAKvB,MALuB;ADtHzB;;AGvHA;;;;;EA3BE,qBAAqB;EACrB,wBAAwB;EACxB,mBAAmB;EACnB,6BAA+C;EAC/C,kBDqDU;ECpDV,gBAAgB;EAChB,oBAAoB;EACpB,eDkBW;ECjBX,aAfoB;EAgBpB,2BAA2B;EAC3B,gBAhBuB;EAiBvB,iCAf+D;EAgB/D,gCAfkE;EAgBlE,iCAhBkE;EAiBlE,8BAlB+D;EAmB/D,kBAAkB;EAClB,mBAAmB;AH0JrB;;AGxJE;;;;;;;;;;;;;;;;;EAIE,aAAa;AHwKjB;;AGvKE;;;;;;;;;;;;;;;;EAEE,mBAAmB;AHwLvB;;AI7NA,eAAA;ACAA,0EAAA;AAEA;;;;;;;;;;;;;;;;;;;;;;;EAuBE,SAAS;EACT,UAAU;ALgOZ;;AK7NA;;;;;;EAME,eAAe;EACf,mBAAmB;ALgOrB;;AK7NA;EACE,gBAAgB;ALgOlB;;AK7NA;;;;EAIE,SAAS;ALgOX;;AK7NA;EACE,sBAAsB;ALgOxB;;AK9NA;EAII,mBAAmB;AL8NvB;;AK3NA;;EAEE,YAAY;EACZ,eAAe;AL8NjB;;AK3NA;EACE,SAAS;AL8NX;;AK3NA;EACE,yBAAyB;EACzB,iBAAiB;AL8NnB;;AK5NA;;EAEE,UAAU;AL+NZ;;AKjOA;;EAII,mBAAmB;ALkOvB;;AK9PA;EClBE,uBJjB6B;EIkB7B,eAhCc;EAiCd,kCAAkC;EAClC,mCAAmC;EACnC,gBAlCoB;EAmCpB,kBAhCsB;EAiCtB,kBAhCsB;EAiCtB,kCApCiC;EAqCjC,8BAAsB;KAAtB,2BAAsB;MAAtB,0BAAsB;UAAtB,sBAAsB;ANoRxB;;AMlRA;;;;;;;EAOE,cAAc;ANqRhB;;AMnRA;;;;;;EAME,oLJ7ByL;AFmT3L;;AMpRA;;EAEE,6BAA6B;EAC7B,4BAA4B;EAC5B,sBJlC0B;AFyT5B;;AMrRA;EACE,cJ3D4B;EI4D5B,cA1DkB;EA2DlB,gBJ3BiB;EI4BjB,gBA1DoB;ANkVtB;;AMpRA;EACE,cJpDgC;EIqDhC,eAAe;EACf,qBAAqB;ANuRvB;;AM1RA;EAKI,mBAAmB;ANyRvB;;AM9RA;EAOI,cJ1E0B;AFqW9B;;AMzRA;EACE,4BJtE4B;EIuE5B,cCpBsB;EDqBtB,kBArEiB;EAsEjB,mBAvEkB;EAwElB,4BAzEgC;ANqWlC;;AM1RA;EACE,4BJ7E4B;EI8E5B,YAAY;EACZ,cAAc;EACd,WAxEa;EAyEb,gBAxEkB;ANqWpB;;AM3RA;EACE,YAAY;EACZ,eAAe;AN8RjB;;AM5RA;;EAEE,wBAAwB;AN+R1B;;AM7RA;EACE,kBAvFuB;ANuXzB;;AM9RA;EACE,mBAAmB;EACnB,oBAAoB;ANiStB;;AM/RA;EACE,cJ1G4B;EI2G5B,gBJrEe;AFuWjB;;AM9RA;EACE,YAAY;ANiSd;;AM/RA;EL1DE,iCAAiC;EK4DjC,4BJ7G4B;EI8G5B,cJpH4B;EIqH5B,kBAjGqB;EAkGrB,gBAAgB;EAChB,uBAlG0B;EAmG1B,gBAAgB;EAChB,iBAAiB;ANkSnB;;AM1SA;EAUI,6BAA6B;EAC7B,mBAAmB;EACnB,cAvGoB;EAwGpB,UAAU;ANoSd;;AMlSA;;EAGI,mBAAmB;ANoSvB;;AMvSA;;EAKM,mBAAmB;ANuSzB;;AM5SA;EAOI,cJxI0B;AFib9B;;AQvbA,mBAAA;ACSA;EAEE,uBPI6B;EOH7B,kBP0DgB;EOzDhB,0FPX2B;EOY3B,cPP4B;EOQ5B,cAAc;EACd,gBAZmB;AT6brB;;AS/aA;EAGI,yEPC8B;AF+alC;;ASnbA;EAKI,oEPD8B;AFmblC;;AUzZA;EAGE,uBRpC6B;EQqC7B,qBR1C4B;EQ2C5B,iBPlDwB;EOmDxB,cRhD4B;EQiD5B,eAAe;EAGf,uBAAuB;EACvB,iCApD6D;EAqD7D,iBApD6B;EAqD7B,kBArD6B;EAsD7B,8BAvD6D;EAwD7D,kBAAkB;EAClB,mBAAmB;AVwZrB;;AUxaA;EAkBI,cAAc;AV0ZlB;;AU5aA;EAwBM,aAAa;EACb,YAAY;AVwZlB;;AUjbA;ETgGI,+BSrEwG;ETqExG,oBSpEgE;AV0ZpE;;AUtbA;ETgGI,mBSlEgE;ETkEhE,gCSjEwG;AV4Z5G;;AU3bA;EAiCM,+BAAmF;EACnF,gCAAoF;AV8Z1F;;AUhcA;EAsCI,qBR7E0B;EQ8E1B,cRjF0B;AF+e9B;;AUrcA;EA0CI,qBRpE8B;EQqE9B,cRrF0B;AFof9B;;AU1cA;EA6CM,kDRvE4B;AFwelC;;AU9cA;EAgDI,qBRzF0B;EQ0F1B,cR3F0B;AF6f9B;;AUndA;EAoDI,6BAA6B;EAC7B,yBAAyB;EACzB,cR/F0B;EQgG1B,0BAjF8B;AVoflC;;AU1dA;EA4DM,4BR/FwB;EQgGxB,cRvGwB;AFygB9B;;AU/dA;EAgEM,yBCH2B;EDI3B,cR3GwB;AF8gB9B;;AUpeA;;EAoEM,6BAA6B;EAC7B,yBAAyB;EACzB,gBAAgB;AVqatB;;AU3eA;EA2EM,uBR5GyB;EQ6GzB,yBAAyB;EACzB,cR3HuB;AF+hB7B;;AUjfA;EAgFQ,yBCnByB;EDoBzB,yBAAyB;EACzB,cRhIqB;AFqiB7B;;AUvfA;EAqFQ,yBAAyB;EACzB,cRpIqB;AF0iB7B;;AU5fA;EAwFU,mDRzHqB;AFiiB/B;;AUhgBA;EA2FQ,yBC9ByB;ED+BzB,yBAAyB;EACzB,cR3IqB;AFojB7B;;AUtgBA;;EAgGQ,uBRjIuB;EQkIvB,yBAAyB;EACzB,gBAAgB;AV2axB;;AU7gBA;EAoGQ,yBRlJqB;EQmJrB,YRtIuB;AFmjB/B;;AUlhBA;EAwGU,uBC3CuB;AXydjC;;AUthBA;;EA2GU,yBRzJmB;EQ0JnB,yBAAyB;EACzB,gBAAgB;EAChB,YR/IqB;AF+jB/B;;AU9hBA;EAiHU,gEAA4E;AVibtF;;AUliBA;EAmHQ,6BAA6B;EAC7B,mBRrJuB;EQsJvB,YRtJuB;AFykB/B;;AUxiBA;EA0HU,uBR3JqB;EQ4JrB,mBR5JqB;EQ6JrB,cR1KmB;AF4lB7B;;AU9iBA;EA+HY,4DAA8D;AVmb1E;;AUljBA;EAqIc,gEAA4E;AVib1F;;AUtjBA;;EAwIU,6BAA6B;EAC7B,mBR1KqB;EQ2KrB,gBAAgB;EAChB,YR5KqB;AF+lB/B;;AU9jBA;EA6IQ,6BAA6B;EAC7B,qBR5LqB;EQ6LrB,cR7LqB;AFknB7B;;AUpkBA;EAoJU,yBRlMmB;EQmMnB,YRtLqB;AF0mB/B;;AUzkBA;EA4Jc,4DAA8D;AVib5E;;AU7kBA;;EA+JU,6BAA6B;EAC7B,qBR9MmB;EQ+MnB,gBAAgB;EAChB,cRhNmB;AFmoB7B;;AUrlBA;EA2EM,yBRzHuB;EQ0HvB,yBAAyB;EACzB,YR9GyB;AF4nB/B;;AU3lBA;EAgFQ,yBCnByB;EDoBzB,yBAAyB;EACzB,YRnHuB;AFkoB/B;;AUjmBA;EAqFQ,yBAAyB;EACzB,YRvHuB;AFuoB/B;;AUtmBA;EAwFU,gDRtImB;AFwpB7B;;AU1mBA;EA2FQ,uBC9ByB;ED+BzB,yBAAyB;EACzB,YR9HuB;AFipB/B;;AUhnBA;;EAgGQ,yBR9IqB;EQ+IrB,yBAAyB;EACzB,gBAAgB;AVqhBxB;;AUvnBA;EAoGQ,uBRrIuB;EQsIvB,cRnJqB;AF0qB7B;;AU5nBA;EAwGU,yBC3CuB;AXmkBjC;;AUhoBA;;EA2GU,uBR5IqB;EQ6IrB,yBAAyB;EACzB,gBAAgB;EAChB,cR5JmB;AFsrB7B;;AUxoBA;EAiHU,4DAA4E;AV2hBtF;;AU5oBA;EAmHQ,6BAA6B;EAC7B,qBRlKqB;EQmKrB,cRnKqB;AFgsB7B;;AUlpBA;EA0HU,yBRxKmB;EQyKnB,qBRzKmB;EQ0KnB,YR7JqB;AFyrB/B;;AUxpBA;EA+HY,gEAA8D;AV6hB1E;;AU5pBA;EAqIc,4DAA4E;AV2hB1F;;AUhqBA;;EAwIU,6BAA6B;EAC7B,qBRvLmB;EQwLnB,gBAAgB;EAChB,cRzLmB;AFstB7B;;AUxqBA;EA6IQ,6BAA6B;EAC7B,mBR/KuB;EQgLvB,YRhLuB;AF+sB/B;;AU9qBA;EAoJU,uBRrLqB;EQsLrB,cRnMmB;AFiuB7B;;AUnrBA;EA4Jc,gEAA8D;AV2hB5E;;AUvrBA;;EA+JU,6BAA6B;EAC7B,mBRjMqB;EQkMrB,gBAAgB;EAChB,YRnMqB;AFguB/B;;AU/rBA;EA2EM,4BR9GwB;EQ+GxB,yBAAyB;EACzB,yBC7Ce;AXqqBrB;;AUrsBA;EAgFQ,yBCnByB;EDoBzB,yBAAyB;EACzB,yBClDa;AX2qBrB;;AU3sBA;EAqFQ,yBAAyB;EACzB,yBCtDa;AXgrBrB;;AUhtBA;EAwFU,mDR3HoB;AFuvB9B;;AUptBA;EA2FQ,yBC9ByB;ED+BzB,yBAAyB;EACzB,yBC7Da;AX0rBrB;;AU1tBA;;EAgGQ,4BRnIsB;EQoItB,yBAAyB;EACzB,gBAAgB;AV+nBxB;;AUjuBA;EAoGQ,oCCpEa;EDqEb,iBRxIsB;AFywB9B;;AUtuBA;EAwGU,oCC3CuB;AX6qBjC;;AU1uBA;;EA2GU,oCC3EW;ED4EX,yBAAyB;EACzB,gBAAgB;EAChB,iBRjJoB;AFqxB9B;;AUlvBA;EAiHU,sFAA4E;AVqoBtF;;AUtvBA;EAmHQ,6BAA6B;EAC7B,wBRvJsB;EQwJtB,iBRxJsB;AF+xB9B;;AU5vBA;EA0HU,4BR7JoB;EQ8JpB,wBR9JoB;EQ+JpB,yBC5FW;AXkuBrB;;AUlwBA;EA+HY,sEAA8D;AVuoB1E;;AUtwBA;EAqIc,sFAA4E;AVqoB1F;;AU1wBA;;EAwIU,6BAA6B;EAC7B,wBR5KoB;EQ6KpB,gBAAgB;EAChB,iBR9KoB;AFqzB9B;;AUlxBA;EA6IQ,6BAA6B;EAC7B,gCC9Ga;ED+Gb,yBC/Ga;AXwvBrB;;AUxxBA;EAoJU,oCCpHW;EDqHX,iBRxLoB;AFg0B9B;;AU7xBA;EA4Jc,sEAA8D;AVqoB5E;;AUjyBA;;EA+JU,6BAA6B;EAC7B,gCChIW;EDiIX,gBAAgB;EAChB,yBClIW;AXywBrB;;AUzyBA;EA2EM,yBRrHwB;EQsHxB,yBAAyB;EACzB,WC3CU;AX6wBhB;;AU/yBA;EAgFQ,yBCnByB;EDoBzB,yBAAyB;EACzB,WChDQ;AXmxBhB;;AUrzBA;EAqFQ,yBAAyB;EACzB,WCpDQ;AXwxBhB;;AU1zBA;EAwFU,gDRlIoB;AFw2B9B;;AU9zBA;EA2FQ,yBC9ByB;ED+BzB,yBAAyB;EACzB,WC3DQ;AXkyBhB;;AUp0BA;;EAgGQ,yBR1IsB;EQ2ItB,yBAAyB;EACzB,gBAAgB;AVyuBxB;;AU30BA;EAoGQ,sBClEQ;EDmER,cR/IsB;AF03B9B;;AUh1BA;EAwGU,yBC3CuB;AXuxBjC;;AUp1BA;;EA2GU,sBCzEM;ED0EN,yBAAyB;EACzB,gBAAgB;EAChB,cRxJoB;AFs4B9B;;AU51BA;EAiHU,0DAA4E;AV+uBtF;;AUh2BA;EAmHQ,6BAA6B;EAC7B,qBR9JsB;EQ+JtB,cR/JsB;AFg5B9B;;AUt2BA;EA0HU,yBRpKoB;EQqKpB,qBRrKoB;EQsKpB,WC1FM;AX00BhB;;AU52BA;EA+HY,gEAA8D;AVivB1E;;AUh3BA;EAqIc,0DAA4E;AV+uB1F;;AUp3BA;;EAwIU,6BAA6B;EAC7B,qBRnLoB;EQoLpB,gBAAgB;EAChB,cRrLoB;AFs6B9B;;AU53BA;EA6IQ,6BAA6B;EAC7B,kBC5GQ;ED6GR,WC7GQ;AXg2BhB;;AUl4BA;EAoJU,sBClHM;EDmHN,cR/LoB;AFi7B9B;;AUv4BA;EA4Jc,gEAA8D;AV+uB5E;;AU34BA;;EA+JU,6BAA6B;EAC7B,kBC9HM;ED+HN,gBAAgB;EAChB,WChIM;AXi3BhB;;AUn5BA;EA2EM,yBRvG4B;EQwG5B,yBAAyB;EACzB,WC3CU;AXu3BhB;;AUz5BA;EAgFQ,yBCnByB;EDoBzB,yBAAyB;EACzB,WChDQ;AX63BhB;;AU/5BA;EAqFQ,yBAAyB;EACzB,WCpDQ;AXk4BhB;;AUp6BA;EAwFU,iDRpHwB;AFo8BlC;;AUx6BA;EA2FQ,yBC9ByB;ED+BzB,yBAAyB;EACzB,WC3DQ;AX44BhB;;AU96BA;;EAgGQ,yBR5H0B;EQ6H1B,yBAAyB;EACzB,gBAAgB;AVm1BxB;;AUr7BA;EAoGQ,sBClEQ;EDmER,cRjI0B;AFs9BlC;;AU17BA;EAwGU,yBC3CuB;AXi4BjC;;AU97BA;;EA2GU,sBCzEM;ED0EN,yBAAyB;EACzB,gBAAgB;EAChB,cR1IwB;AFk+BlC;;AUt8BA;EAiHU,0DAA4E;AVy1BtF;;AU18BA;EAmHQ,6BAA6B;EAC7B,qBRhJ0B;EQiJ1B,cRjJ0B;AF4+BlC;;AUh9BA;EA0HU,yBRtJwB;EQuJxB,qBRvJwB;EQwJxB,WC1FM;AXo7BhB;;AUt9BA;EA+HY,gEAA8D;AV21B1E;;AU19BA;EAqIc,0DAA4E;AVy1B1F;;AU99BA;;EAwIU,6BAA6B;EAC7B,qBRrKwB;EQsKxB,gBAAgB;EAChB,cRvKwB;AFkgClC;;AUt+BA;EA6IQ,6BAA6B;EAC7B,kBC5GQ;ED6GR,WC7GQ;AX08BhB;;AU5+BA;EAoJU,sBClHM;EDmHN,cRjLwB;AF6gClC;;AUj/BA;EA4Jc,gEAA8D;AVy1B5E;;AUr/BA;;EA+JU,6BAA6B;EAC7B,kBC9HM;ED+HN,gBAAgB;EAChB,WChIM;AX29BhB;;AU7/BA;EAwKU,yBC/HsC;EDgItC,cCvH2D;AXg9BrE;;AUlgCA;EA4KY,yBC/GqB;EDgHrB,yBAAyB;EACzB,cC5HyD;AXs9BrE;;AUxgCA;EAiLY,yBCpHqB;EDqHrB,yBAAyB;EACzB,cCjIyD;AX49BrE;;AU9gCA;EA2EM,yBRrG4B;EQsG5B,yBAAyB;EACzB,WC3CU;AXk/BhB;;AUphCA;EAgFQ,yBCnByB;EDoBzB,yBAAyB;EACzB,WChDQ;AXw/BhB;;AU1hCA;EAqFQ,yBAAyB;EACzB,WCpDQ;AX6/BhB;;AU/hCA;EAwFU,kDRlHwB;AF6jClC;;AUniCA;EA2FQ,yBC9ByB;ED+BzB,yBAAyB;EACzB,WC3DQ;AXugChB;;AUziCA;;EAgGQ,yBR1H0B;EQ2H1B,yBAAyB;EACzB,gBAAgB;AV88BxB;;AUhjCA;EAoGQ,sBClEQ;EDmER,cR/H0B;AF+kClC;;AUrjCA;EAwGU,yBC3CuB;AX4/BjC;;AUzjCA;;EA2GU,sBCzEM;ED0EN,yBAAyB;EACzB,gBAAgB;EAChB,cRxIwB;AF2lClC;;AUjkCA;EAiHU,0DAA4E;AVo9BtF;;AUrkCA;EAmHQ,6BAA6B;EAC7B,qBR9I0B;EQ+I1B,cR/I0B;AFqmClC;;AU3kCA;EA0HU,yBRpJwB;EQqJxB,qBRrJwB;EQsJxB,WC1FM;AX+iChB;;AUjlCA;EA+HY,gEAA8D;AVs9B1E;;AUrlCA;EAqIc,0DAA4E;AVo9B1F;;AUzlCA;;EAwIU,6BAA6B;EAC7B,qBRnKwB;EQoKxB,gBAAgB;EAChB,cRrKwB;AF2nClC;;AUjmCA;EA6IQ,6BAA6B;EAC7B,kBC5GQ;ED6GR,WC7GQ;AXqkChB;;AUvmCA;EAoJU,sBClHM;EDmHN,cR/KwB;AFsoClC;;AU5mCA;EA4Jc,gEAA8D;AVo9B5E;;AUhnCA;;EA+JU,6BAA6B;EAC7B,kBC9HM;ED+HN,gBAAgB;EAChB,WChIM;AXslChB;;AUxnCA;EAwKU,yBC/HsC;EDgItC,cCvH2D;AX2kCrE;;AU7nCA;EA4KY,yBC/GqB;EDgHrB,yBAAyB;EACzB,cC5HyD;AXilCrE;;AUnoCA;EAiLY,yBCpHqB;EDqHrB,yBAAyB;EACzB,cCjIyD;AXulCrE;;AUzoCA;EA2EM,yBRtG4B;EQuG5B,yBAAyB;EACzB,WC3CU;AX6mChB;;AU/oCA;EAgFQ,yBCnByB;EDoBzB,yBAAyB;EACzB,WChDQ;AXmnChB;;AUrpCA;EAqFQ,yBAAyB;EACzB,WCpDQ;AXwnChB;;AU1pCA;EAwFU,kDRnHwB;AFyrClC;;AU9pCA;EA2FQ,yBC9ByB;ED+BzB,yBAAyB;EACzB,WC3DQ;AXkoChB;;AUpqCA;;EAgGQ,yBR3H0B;EQ4H1B,yBAAyB;EACzB,gBAAgB;AVykCxB;;AU3qCA;EAoGQ,sBClEQ;EDmER,cRhI0B;AF2sClC;;AUhrCA;EAwGU,yBC3CuB;AXunCjC;;AUprCA;;EA2GU,sBCzEM;ED0EN,yBAAyB;EACzB,gBAAgB;EAChB,cRzIwB;AFutClC;;AU5rCA;EAiHU,0DAA4E;AV+kCtF;;AUhsCA;EAmHQ,6BAA6B;EAC7B,qBR/I0B;EQgJ1B,cRhJ0B;AFiuClC;;AUtsCA;EA0HU,yBRrJwB;EQsJxB,qBRtJwB;EQuJxB,WC1FM;AX0qChB;;AU5sCA;EA+HY,gEAA8D;AVilC1E;;AUhtCA;EAqIc,0DAA4E;AV+kC1F;;AUptCA;;EAwIU,6BAA6B;EAC7B,qBRpKwB;EQqKxB,gBAAgB;EAChB,cRtKwB;AFuvClC;;AU5tCA;EA6IQ,6BAA6B;EAC7B,kBC5GQ;ED6GR,WC7GQ;AXgsChB;;AUluCA;EAoJU,sBClHM;EDmHN,cRhLwB;AFkwClC;;AUvuCA;EA4Jc,gEAA8D;AV+kC5E;;AU3uCA;;EA+JU,6BAA6B;EAC7B,kBC9HM;ED+HN,gBAAgB;EAChB,WChIM;AXitChB;;AUnvCA;EAwKU,yBC/HsC;EDgItC,cCvH2D;AXssCrE;;AUxvCA;EA4KY,yBC/GqB;EDgHrB,yBAAyB;EACzB,cC5HyD;AX4sCrE;;AU9vCA;EAiLY,yBCpHqB;EDqHrB,yBAAyB;EACzB,cCjIyD;AXktCrE;;AUpwCA;EA2EM,yBRxG4B;EQyG5B,yBAAyB;EACzB,WC3CU;AXwuChB;;AU1wCA;EAgFQ,yBCnByB;EDoBzB,yBAAyB;EACzB,WChDQ;AX8uChB;;AUhxCA;EAqFQ,yBAAyB;EACzB,WCpDQ;AXmvChB;;AUrxCA;EAwFU,kDRrHwB;AFszClC;;AUzxCA;EA2FQ,yBC9ByB;ED+BzB,yBAAyB;EACzB,WC3DQ;AX6vChB;;AU/xCA;;EAgGQ,yBR7H0B;EQ8H1B,yBAAyB;EACzB,gBAAgB;AVosCxB;;AUtyCA;EAoGQ,sBClEQ;EDmER,cRlI0B;AFw0ClC;;AU3yCA;EAwGU,yBC3CuB;AXkvCjC;;AU/yCA;;EA2GU,sBCzEM;ED0EN,yBAAyB;EACzB,gBAAgB;EAChB,cR3IwB;AFo1ClC;;AUvzCA;EAiHU,0DAA4E;AV0sCtF;;AU3zCA;EAmHQ,6BAA6B;EAC7B,qBRjJ0B;EQkJ1B,cRlJ0B;AF81ClC;;AUj0CA;EA0HU,yBRvJwB;EQwJxB,qBRxJwB;EQyJxB,WC1FM;AXqyChB;;AUv0CA;EA+HY,gEAA8D;AV4sC1E;;AU30CA;EAqIc,0DAA4E;AV0sC1F;;AU/0CA;;EAwIU,6BAA6B;EAC7B,qBRtKwB;EQuKxB,gBAAgB;EAChB,cRxKwB;AFo3ClC;;AUv1CA;EA6IQ,6BAA6B;EAC7B,kBC5GQ;ED6GR,WC7GQ;AX2zChB;;AU71CA;EAoJU,sBClHM;EDmHN,cRlLwB;AF+3ClC;;AUl2CA;EA4Jc,gEAA8D;AV0sC5E;;AUt2CA;;EA+JU,6BAA6B;EAC7B,kBC9HM;ED+HN,gBAAgB;EAChB,WChIM;AX40ChB;;AU92CA;EAwKU,yBC/HsC;EDgItC,cCvH2D;AXi0CrE;;AUn3CA;EA4KY,yBC/GqB;EDgHrB,yBAAyB;EACzB,cC5HyD;AXu0CrE;;AUz3CA;EAiLY,yBCpHqB;EDqHrB,yBAAyB;EACzB,cCjIyD;AX60CrE;;AU/3CA;EA2EM,yBRzG4B;EQ0G5B,yBAAyB;EACzB,yBC7Ce;AXq2CrB;;AUr4CA;EAgFQ,yBCnByB;EDoBzB,yBAAyB;EACzB,yBClDa;AX22CrB;;AU34CA;EAqFQ,yBAAyB;EACzB,yBCtDa;AXg3CrB;;AUh5CA;EAwFU,kDRtHwB;AFk7ClC;;AUp5CA;EA2FQ,yBC9ByB;ED+BzB,yBAAyB;EACzB,yBC7Da;AX03CrB;;AU15CA;;EAgGQ,yBR9H0B;EQ+H1B,yBAAyB;EACzB,gBAAgB;AV+zCxB;;AUj6CA;EAoGQ,oCCpEa;EDqEb,cRnI0B;AFo8ClC;;AUt6CA;EAwGU,oCC3CuB;AX62CjC;;AU16CA;;EA2GU,oCC3EW;ED4EX,yBAAyB;EACzB,gBAAgB;EAChB,cR5IwB;AFg9ClC;;AUl7CA;EAiHU,sFAA4E;AVq0CtF;;AUt7CA;EAmHQ,6BAA6B;EAC7B,qBRlJ0B;EQmJ1B,cRnJ0B;AF09ClC;;AU57CA;EA0HU,yBRxJwB;EQyJxB,qBRzJwB;EQ0JxB,yBC5FW;AXk6CrB;;AUl8CA;EA+HY,gEAA8D;AVu0C1E;;AUt8CA;EAqIc,sFAA4E;AVq0C1F;;AU18CA;;EAwIU,6BAA6B;EAC7B,qBRvKwB;EQwKxB,gBAAgB;EAChB,cRzKwB;AFg/ClC;;AUl9CA;EA6IQ,6BAA6B;EAC7B,gCC9Ga;ED+Gb,yBC/Ga;AXw7CrB;;AUx9CA;EAoJU,oCCpHW;EDqHX,cRnLwB;AF2/ClC;;AU79CA;EA4Jc,gEAA8D;AVq0C5E;;AUj+CA;;EA+JU,6BAA6B;EAC7B,gCChIW;EDiIX,gBAAgB;EAChB,yBClIW;AXy8CrB;;AUz+CA;EAwKU,yBC/HsC;EDgItC,cCvH2D;AX47CrE;;AU9+CA;EA4KY,yBC/GqB;EDgHrB,yBAAyB;EACzB,cC5HyD;AXk8CrE;;AUp/CA;EAiLY,yBCpHqB;EDqHrB,yBAAyB;EACzB,cCjIyD;AXw8CrE;;AU1/CA;EA2EM,yBRnG2B;EQoG3B,yBAAyB;EACzB,WC3CU;AX89ChB;;AUhgDA;EAgFQ,yBCnByB;EDoBzB,yBAAyB;EACzB,WChDQ;AXo+ChB;;AUtgDA;EAqFQ,yBAAyB;EACzB,WCpDQ;AXy+ChB;;AU3gDA;EAwFU,kDRhHuB;AFuiDjC;;AU/gDA;EA2FQ,yBC9ByB;ED+BzB,yBAAyB;EACzB,WC3DQ;AXm/ChB;;AUrhDA;;EAgGQ,yBRxHyB;EQyHzB,yBAAyB;EACzB,gBAAgB;AV07CxB;;AU5hDA;EAoGQ,sBClEQ;EDmER,cR7HyB;AFyjDjC;;AUjiDA;EAwGU,yBC3CuB;AXw+CjC;;AUriDA;;EA2GU,sBCzEM;ED0EN,yBAAyB;EACzB,gBAAgB;EAChB,cRtIuB;AFqkDjC;;AU7iDA;EAiHU,0DAA4E;AVg8CtF;;AUjjDA;EAmHQ,6BAA6B;EAC7B,qBR5IyB;EQ6IzB,cR7IyB;AF+kDjC;;AUvjDA;EA0HU,yBRlJuB;EQmJvB,qBRnJuB;EQoJvB,WC1FM;AX2hDhB;;AU7jDA;EA+HY,gEAA8D;AVk8C1E;;AUjkDA;EAqIc,0DAA4E;AVg8C1F;;AUrkDA;;EAwIU,6BAA6B;EAC7B,qBRjKuB;EQkKvB,gBAAgB;EAChB,cRnKuB;AFqmDjC;;AU7kDA;EA6IQ,6BAA6B;EAC7B,kBC5GQ;ED6GR,WC7GQ;AXijDhB;;AUnlDA;EAoJU,sBClHM;EDmHN,cR7KuB;AFgnDjC;;AUxlDA;EA4Jc,gEAA8D;AVg8C5E;;AU5lDA;;EA+JU,6BAA6B;EAC7B,kBC9HM;ED+HN,gBAAgB;EAChB,WChIM;AXkkDhB;;AUpmDA;EAwKU,yBC/HsC;EDgItC,cCvH2D;AXujDrE;;AUzmDA;EA4KY,yBC/GqB;EDgHrB,yBAAyB;EACzB,cC5HyD;AX6jDrE;;AU/mDA;EAiLY,yBCpHqB;EDqHrB,yBAAyB;EACzB,cCjIyD;AXmkDrE;;AUrnDA;EATE,kBR6BgB;EQ5BhB,kBRFc;AFooDhB;;AU1nDA;EANE,eRLW;AFyoDb;;AU9nDA;EAJE,kBRRc;AF8oDhB;;AUloDA;EAFE,iBRXa;AFmpDf;;AUtoDA;;EAgMI,uBRjO2B;EQkO3B,qBRvO0B;EQwO1B,gBAtNyB;EAuNzB,YAtNyB;AViqD7B;;AU9oDA;EAqMI,aAAa;EACb,WAAW;AV68Cf;;AUnpDA;EAwMI,6BAA6B;EAC7B,oBAAoB;AV+8CxB;;AUxpDA;ETvCE,kBAAkB;EAKhB,2BAAiC;EACjC,0BAAgC;ES8O9B,6BAA6B;AVk9CnC;;AU/pDA;EA+MI,4BRlP0B;EQmP1B,qBRtP0B;EQuP1B,cRzP0B;EQ0P1B,gBAAgB;EAChB,oBAAoB;AVo9CxB;;AUvqDA;EAqNI,uBR9LqB;EQ+LrB,gCAA0D;EAC1D,iCAA2D;AVs9C/D;;AUp9CA;EACE,mBAAmB;EACnB,aAAa;EACb,eAAe;EACf,2BAA2B;AVu9C7B;;AU39CA;EAMI,qBAAqB;AVy9CzB;;AU/9CA;ETzHI,oBSiIwC;AV29C5C;;AUn+CA;EAUI,sBAAsB;AV69C1B;;AUv+CA;EAYI,mBAAmB;AV+9CvB;;AU3+CA;EAlOE,kBR6BgB;EQ5BhB,kBRFc;AFmtDhB;;AUh/CA;EA7NE,kBRRc;AFytDhB;;AUp/CA;EA3NE,iBRXa;AF8tDf;;AUx/CA;EA0BQ,4BAA4B;EAC5B,yBAAyB;AVk+CjC;;AU7/CA;EA6BQ,6BAA6B;EAC7B,0BAA0B;ETvJ9B,kBSwJwC;AVo+C5C;;AUngDA;ETzHI,eS0JqC;AVs+CzC;;AUvgDA;EAoCQ,UAAU;AVu+ClB;;AU3gDA;EA0CQ,UAAU;AVq+ClB;;AU/gDA;EA4CU,UAAU;AVu+CpB;;AUnhDA;EA8CQ,YAAY;EACZ,cAAc;AVy+CtB;;AUxhDA;EAiDI,uBAAuB;AV2+C3B;;AU5hDA;EAoDQ,oBAAoB;EACpB,qBAAqB;AV4+C7B;;AUjiDA;EAuDI,yBAAyB;AV8+C7B;;AUriDA;EA0DQ,oBAAoB;EACpB,qBAAqB;AV++C7B;;AYhzDA;EACE,YAAY;EACZ,cAAc;EACd,kBAAkB;EAClB,WAAW;AZmzDb;;AYvzDA;EAMI,0BAA0B;EAC1B,kBV2CM;EU1CN,mBV0CM;EUzCN,WAAW;AZqzDf;;AChuDE;EW9FF;IAWI,gBAAuC;EZwzDzC;AACF;;AC5tDI;EWxGJ;IAcM,iBAAqE;EZ2zDzE;AACF;;ACntDI;EWvHJ;IAiBM,iBAAiE;EZ8zDrE;AACF;;ACnuDI;EW7GJ;IAoBM,iBAAqE;EZi0DzE;AACF;;AC1tDI;EW5HJ;IAuBM,iBAAiE;EZo0DrE;AACF;;Aa50DA;EAII,kBAAkB;Ab40DtB;;Aah1DA;;;;;;;EAcM,kBAAkB;Ab40DxB;;Aa11DA;;;;;;EAqBI,cXlC0B;EWmC1B,gBXEiB;EWDjB,kBAxC+B;Abs3DnC;;Aar2DA;EAyBI,cAAc;EACd,oBAAoB;Abg1DxB;;Aa12DA;EA4BM,eAAe;Abk1DrB;;Aa92DA;EA8BI,iBAAiB;EACjB,uBAAuB;Abo1D3B;;Aan3DA;EAiCM,oBAAoB;Abs1D1B;;Aav3DA;EAmCI,gBAAgB;EAChB,uBAAuB;Abw1D3B;;Aa53DA;EAsCM,oBAAoB;Ab01D1B;;Aah4DA;EAwCI,iBAAiB;EACjB,oBAAoB;Ab41DxB;;Aar4DA;EA2CI,kBAAkB;EAClB,uBAAuB;Ab81D3B;;Aa14DA;EA8CI,cAAc;EACd,kBAAkB;Abg2DtB;;Aa/4DA;EAiDI,4BXvD0B;EDmI1B,8BCtI0B;EW4D1B,qBAhEqC;Abk6DzC;;Aar5DA;EAqDI,4BAA4B;EZwE5B,gBYvEmC;EACnC,eAAe;Abo2DnB;;Aa35DA;EAyDM,wBAAwB;Abs2D9B;;Aa/5DA;EA2DQ,4BAA4B;Abw2DpC;;Aan6DA;EA6DQ,4BAA4B;Ab02DpC;;Aav6DA;EA+DQ,4BAA4B;Ab42DpC;;Aa36DA;EAiEQ,4BAA4B;Ab82DpC;;Aa/6DA;EAmEI,wBAAwB;EZ0DxB,gBYzDmC;EACnC,eAAe;Abg3DnB;;Aar7DA;EAuEM,uBAAuB;EACvB,iBAAiB;Abk3DvB;;Aa17DA;EA0EQ,uBAAuB;Abo3D/B;;Aa97DA;EZ6HI,gBYjDmC;Abs3DvC;;Aal8DA;EA8EI,gBAAgB;EAChB,iBAAiB;EACjB,kBAAkB;Abw3DtB;;Aax8DA;EAkFM,eAAe;Ab03DrB;;Aa58DA;EAoFM,kBAAkB;Ab43DxB;;Aah9DA;EAsFM,qBAAqB;Ab83D3B;;Aap9DA;EAwFM,kBAAkB;Abg4DxB;;Aax9DA;EZ2CE,iCAAiC;EYgD/B,gBAAgB;EAChB,qBAvG8B;EAwG9B,gBAAgB;EAChB,iBAAiB;Abk4DrB;;Aah+DA;;EAiGI,cAAc;Abo4DlB;;Aar+DA;EAmGI,WAAW;Abs4Df;;Aaz+DA;;EAsGM,yBX/GwB;EWgHxB,qBA/GmC;EAgHnC,qBA/GmC;EAgHnC,mBAAmB;Abw4DzB;;Aaj/DA;EA2GM,cXxHwB;AFkgE9B;;Aar/DA;EA6GQ,mBAAmB;Ab44D3B;;Aaz/DA;;EAiHQ,qBAtHsC;EAuHtC,cX/HsB;AF4gE9B;;Aa//DA;;EAsHQ,qBAzHsC;EA0HtC,cXpIsB;AFkhE9B;;AargEA;;EA6HY,sBAAsB;Ab64DlC;;Aa1gEA;EAgIM,aAAa;Ab84DnB;;Aa9gEA;EAmII,kBXhHY;AF+/DhB;;AalhEA;EAqII,kBXpHY;AFqgEhB;;AathEA;EAuII,iBXvHW;AF0gEf;;AcxiEA;EACE,mBAAmB;EACnB,oBAAoB;EACpB,uBAAuB;EACvB,cATsB;EAUtB,aAVsB;AdqjExB;;AchjEA;EAQI,YAZwB;EAaxB,WAbwB;AdyjE5B;;AcrjEA;EAWI,YAdyB;EAezB,WAfyB;Ad6jE7B;;Ac1jEA;EAcI,YAhBwB;EAiBxB,WAjBwB;AdikE5B;;AelkEA;EACE,cAAc;EACd,kBAAkB;AfqkEpB;;AevkEA;EAII,cAAc;EACd,YAAY;EACZ,WAAW;AfukEf;;Ae7kEA;EAQM,uBb6DmB;AF4gEzB;;AejlEA;EAUI,WAAW;Af2kEf;;AerlEA;;;;;;;;;;;;;;;;;EA+BM,YAAY;EACZ,WAAW;Af0kEjB;;Ae1mEA;EAmCI,iBAAiB;Af2kErB;;Ae9mEA;EAqCI,gBAAgB;Af6kEpB;;AelnEA;EAuCI,gBAAgB;Af+kEpB;;AetnEA;EAyCI,qBAAqB;AfilEzB;;Ae1nEA;EA2CI,gBAAgB;AfmlEpB;;Ae9nEA;EA6CI,mBAAmB;AfqlEvB;;AeloEA;EA+CI,gBAAgB;AfulEpB;;AetoEA;EAiDI,qBAAqB;AfylEzB;;Ae1oEA;EAmDI,iBAAiB;Af2lErB;;Ae9oEA;EAqDI,sBAAsB;Af6lE1B;;AelpEA;EAuDI,iBAAiB;Af+lErB;;AetpEA;EAyDI,sBAAsB;AfimE1B;;Ae1pEA;EA2DI,sBAAsB;AfmmE1B;;Ae9pEA;EA6DI,iBAAiB;AfqmErB;;AelqEA;EA+DI,iBAAiB;AfumErB;;AetqEA;EAmEM,YAAwB;EACxB,WAAuB;AfumE7B;;Ae3qEA;EAmEM,YAAwB;EACxB,WAAuB;Af4mE7B;;AehrEA;EAmEM,YAAwB;EACxB,WAAuB;AfinE7B;;AerrEA;EAmEM,YAAwB;EACxB,WAAuB;AfsnE7B;;Ae1rEA;EAmEM,YAAwB;EACxB,WAAuB;Af2nE7B;;Ae/rEA;EAmEM,YAAwB;EACxB,WAAuB;AfgoE7B;;AepsEA;EAmEM,aAAwB;EACxB,YAAuB;AfqoE7B;;AgBlsEA;EAEE,4BdE4B;EcD5B,kBdyDU;EcxDV,kBAAkB;EAEhB,sCAXoD;AhB8sExD;;AgBzsEA;EAUI,mBAAmB;EACnB,0BAA0B;AhBmsE9B;;AgB9sEA;EAaI,mBAAmB;AhBqsEvB;;AgBltEA;;EAgBI,iBdV2B;AFitE/B;;AgBvtEA;EAkBI,uBAAuB;AhBysE3B;;AgB3tEA;Ef+II,ae3H4B;EAC5B,kBAAkB;EAClB,WAAW;AhB2sEf;;AgBjuEA;;;EA0BI,mBAAmB;AhB6sEvB;;AgBvuEA;EAgCM,uBd1ByB;Ec2BzB,cdxCuB;AFmvE7B;;AgB5uEA;EAgCM,yBdvCuB;EcwCvB,Yd3ByB;AF2uE/B;;AgBjvEA;EAgCM,4Bd5BwB;Ec6BxB,yBLsCe;AX+qErB;;AgBtvEA;EAgCM,yBdnCwB;EcoCxB,WLwCU;AXkrEhB;;AgB3vEA;EAgCM,yBdrB4B;EcsB5B,WLwCU;AXurEhB;;AgBhwEA;EAuCU,yBLyCsC;EKxCtC,cLiD2D;AX4qErE;;AgBrwEA;EAgCM,yBdnB4B;EcoB5B,WLwCU;AXisEhB;;AgB1wEA;EAuCU,yBLyCsC;EKxCtC,cLiD2D;AXsrErE;;AgB/wEA;EAgCM,yBdpB4B;EcqB5B,WLwCU;AX2sEhB;;AgBpxEA;EAuCU,yBLyCsC;EKxCtC,cLiD2D;AXgsErE;;AgBzxEA;EAgCM,yBdtB4B;EcuB5B,WLwCU;AXqtEhB;;AgB9xEA;EAuCU,yBLyCsC;EKxCtC,cLiD2D;AX0sErE;;AgBnyEA;EAgCM,yBdvB4B;EcwB5B,yBLsCe;AXiuErB;;AgBxyEA;EAuCU,yBLyCsC;EKxCtC,cLiD2D;AXotErE;;AgB7yEA;EAgCM,yBdjB2B;EckB3B,WLwCU;AXyuEhB;;AgBlzEA;EAuCU,yBLyCsC;EKxCtC,cLiD2D;AX8tErE;;AiBxzEA;EAEE,qBAAqB;EACrB,wBAAwB;EACxB,YAAY;EACZ,uBf0DuB;EezDvB,cAAc;EACd,YfsBW;EerBX,gBAAgB;EAChB,UAAU;EACV,WAAW;AjB0zEb;;AiBp0EA;EAYI,yBfT2B;AFq0E/B;;AiBx0EA;EAcI,yBff0B;AF60E9B;;AiB50EA;EAgBI,yBfjB0B;AFi1E9B;;AiBh1EA;EAkBI,yBfnB0B;EeoB1B,YAAY;AjBk0EhB;;AiBr1EA;EAyBQ,uBflBuB;AFk1E/B;;AiBz1EA;EA2BQ,uBfpBuB;AFs1E/B;;AiB71EA;EA6BQ,uBftBuB;AF01E/B;;AiBj2EA;EA+BQ,mEAA2F;AjBs0EnG;;AiBr2EA;EAyBQ,yBf/BqB;AF+2E7B;;AiBz2EA;EA2BQ,yBfjCqB;AFm3E7B;;AiB72EA;EA6BQ,yBfnCqB;AFu3E7B;;AiBj3EA;EA+BQ,qEAA2F;AjBs1EnG;;AiBr3EA;EAyBQ,4BfpBsB;AFo3E9B;;AiBz3EA;EA2BQ,4BftBsB;AFw3E9B;;AiB73EA;EA6BQ,4BfxBsB;AF43E9B;;AiBj4EA;EA+BQ,wEAA2F;AjBs2EnG;;AiBr4EA;EAyBQ,yBf3BsB;AF24E9B;;AiBz4EA;EA2BQ,yBf7BsB;AF+4E9B;;AiB74EA;EA6BQ,yBf/BsB;AFm5E9B;;AiBj5EA;EA+BQ,qEAA2F;AjBs3EnG;;AiBr5EA;EAyBQ,yBfb0B;AF64ElC;;AiBz5EA;EA2BQ,yBff0B;AFi5ElC;;AiB75EA;EA6BQ,yBfjB0B;AFq5ElC;;AiBj6EA;EA+BQ,qEAA2F;AjBs4EnG;;AiBr6EA;EAyBQ,yBfX0B;AF25ElC;;AiBz6EA;EA2BQ,yBfb0B;AF+5ElC;;AiB76EA;EA6BQ,yBff0B;AFm6ElC;;AiBj7EA;EA+BQ,qEAA2F;AjBs5EnG;;AiBr7EA;EAyBQ,yBfZ0B;AF46ElC;;AiBz7EA;EA2BQ,yBfd0B;AFg7ElC;;AiB77EA;EA6BQ,yBfhB0B;AFo7ElC;;AiBj8EA;EA+BQ,qEAA2F;AjBs6EnG;;AiBr8EA;EAyBQ,yBfd0B;AF87ElC;;AiBz8EA;EA2BQ,yBfhB0B;AFk8ElC;;AiB78EA;EA6BQ,yBflB0B;AFs8ElC;;AiBj9EA;EA+BQ,qEAA2F;AjBs7EnG;;AiBr9EA;EAyBQ,yBff0B;AF+8ElC;;AiBz9EA;EA2BQ,yBfjB0B;AFm9ElC;;AiB79EA;EA6BQ,yBfnB0B;AFu9ElC;;AiBj+EA;EA+BQ,qEAA2F;AjBs8EnG;;AiBr+EA;EAyBQ,yBfTyB;AFy9EjC;;AiBz+EA;EA2BQ,yBfXyB;AF69EjC;;AiB7+EA;EA6BQ,yBfbyB;AFi+EjC;;AiBj/EA;EA+BQ,qEAA2F;AjBs9EnG;;AiBr/EA;EAkCI,gCAtCkC;UAsClC,wBAtCkC;EAuClC,2CAAmC;UAAnC,mCAAmC;EACnC,yCAAiC;UAAjC,iCAAiC;EACjC,yCAAiC;UAAjC,iCAAiC;EACjC,yBfnC2B;EeoC3B,qEAA0F;EAC1F,6BAA6B;EAC7B,4BAA4B;EAC5B,0BAA0B;AjBu9E9B;;AiBjgFA;EA4CM,6BAA6B;AjBy9EnC;;AiBrgFA;EA8CM,6BAA6B;AjB29EnC;;AiBzgFA;EAgDM,oBAAoB;AjB69E1B;;AiB7gFA;EAoDI,eftBY;AFm/EhB;;AiBjhFA;EAsDI,ef1BY;AFy/EhB;;AiBrhFA;EAwDI,cf7BW;AF8/Ef;;AiB/9EA;EACE;IACE,2BAA2B;EjBk+E7B;EiBj+EA;IACE,4BAA4B;EjBm+E9B;AACF;;AiBx+EA;EACE;IACE,2BAA2B;EjBk+E7B;EiBj+EA;IACE,4BAA4B;EjBm+E9B;AACF;;AkB/gFA;EAEE,uBhBd6B;EgBe7B,chBxB4B;AFyiF9B;;AkBphFA;;EAMI,yBhBvB0B;EgBwB1B,qBA9B6B;EA+B7B,qBA9B6B;EA+B7B,mBAAmB;AlBmhFvB;;AkB5hFA;;EAeQ,uBhB3BuB;EgB4BvB,mBhB5BuB;EgB6BvB,chB1CqB;AF4jF7B;;AkBniFA;;EAeQ,yBhBxCqB;EgByCrB,qBhBzCqB;EgB0CrB,YhB7BuB;AFsjF/B;;AkB1iFA;;EAeQ,4BhB7BsB;EgB8BtB,wBhB9BsB;EgB+BtB,yBPoCa;AX4/ErB;;AkBjjFA;;EAeQ,yBhBpCsB;EgBqCtB,qBhBrCsB;EgBsCtB,WPsCQ;AXigFhB;;AkBxjFA;;EAeQ,yBhBtB0B;EgBuB1B,qBhBvB0B;EgBwB1B,WPsCQ;AXwgFhB;;AkB/jFA;;EAeQ,yBhBpB0B;EgBqB1B,qBhBrB0B;EgBsB1B,WPsCQ;AX+gFhB;;AkBtkFA;;EAeQ,yBhBrB0B;EgBsB1B,qBhBtB0B;EgBuB1B,WPsCQ;AXshFhB;;AkB7kFA;;EAeQ,yBhBvB0B;EgBwB1B,qBhBxB0B;EgByB1B,WPsCQ;AX6hFhB;;AkBplFA;;EAeQ,yBhBxB0B;EgByB1B,qBhBzB0B;EgB0B1B,yBPoCa;AXsiFrB;;AkB3lFA;;EAeQ,yBhBlByB;EgBmBzB,qBhBnByB;EgBoBzB,WPsCQ;AX2iFhB;;AkBlmFA;;EAoBM,mBAAmB;EACnB,SAAS;AlBmlFf;;AkBxmFA;;EAuBM,yBhB9B4B;EgB+B5B,WP+BU;AXujFhB;;AkB9mFA;;;;EA2BQ,mBAAmB;AlB0lF3B;;AkBrnFA;;EA6BM,sBAAsB;AlB6lF5B;;AkB1nFA;EA+BI,chBpD0B;AFmpF9B;;AkB9nFA;EAiCM,mBAAmB;AlBimFzB;;AkBloFA;EAoCM,yBhB3C4B;EgB4C5B,WPkBU;AXglFhB;;AkBvoFA;;EAwCQ,mBAAmB;AlBomF3B;;AkB5oFA;;EA2CQ,kBPYQ;EOXR,mBAAmB;AlBsmF3B;;AkBlpFA;EA8CI,6BA5DqC;AlBoqFzC;;AkBtpFA;;EAiDM,qBApEgC;EAqEhC,chBvEwB;AFirF9B;;AkB5pFA;EAoDI,6BAhEqC;AlB4qFzC;;AkBhqFA;;EAuDM,qBAxEgC;EAyEhC,chB7EwB;AF2rF9B;;AkBtqFA;EA0DI,6BAvEqC;AlBurFzC;;AkB1qFA;;EA+DU,sBAAsB;AlBgnFhC;;AkB/qFA;;EAoEM,iBAAiB;AlBgnFvB;;AkBprFA;;EAyEU,wBAAwB;AlBgnFlC;;AkBzrFA;EA2EI,WAAW;AlBknFf;;AkB7rFA;EAgFU,yBhB7FoB;AF8sF9B;;AkBjsFA;EAqFY,yBhBlGkB;AFktF9B;;AkBrsFA;EAuFc,4BhBrGgB;AFutF9B;;AkBzsFA;;EA2FM,qBAAqB;AlBmnF3B;;AkB9sFA;EAgGU,yBhB7GoB;AF+tF9B;;AkBhnFA;EjB/DE,iCAAiC;EiBkEjC,cAAc;EACd,kBAAkB;EAClB,eAAe;AlBknFjB;;AmB7uFA;EACE,mBAAmB;EACnB,aAAa;EACb,eAAe;EACf,2BAA2B;AnBgvF7B;;AmBpvFA;EAMI,qBAAqB;AnBkvFzB;;AmBxvFA;ElByII,oBkBjIwC;AnBovF5C;;AmB5vFA;EAUI,sBAAsB;AnBsvF1B;;AmBhwFA;EAYI,mBAAmB;AnBwvFvB;;AmBpwFA;EAgBM,ejBcO;AF0uFb;;AmBxwFA;EAmBM,kBjBUU;AF+uFhB;;AmB5wFA;EAqBI,uBAAuB;AnB2vF3B;;AmBhxFA;EAuBM,qBAAqB;EACrB,oBAAoB;AnB6vF1B;;AmBrxFA;EA0BI,yBAAyB;AnB+vF7B;;AmBzxFA;EA6BQ,mBAAmB;AnBgwF3B;;AmB7xFA;EA+BQ,eAAe;AnBkwFvB;;AmBjyFA;ElByII,ekBvGmC;AnBmwFvC;;AmBryFA;ElByII,ckBrGqC;EAE/B,yBAAyB;EACzB,4BAA4B;AnBowFtC;;AmB3yFA;EA6CU,0BAA0B;EAC1B,6BAA6B;AnBkwFvC;;AmB7vFA;EACE,mBAAmB;EACnB,4BjB/C4B;EiBgD5B,kBjBQU;EiBPV,cjBvD4B;EiBwD5B,oBAAoB;EACpB,kBjB1Bc;EiB2Bd,WAAW;EACX,uBAAuB;EACvB,gBAAgB;EAChB,oBAAoB;EACpB,qBAAqB;EACrB,mBAAmB;AnBgwFrB;;AmB5wFA;ElBsFI,oBkBxEuC;ElBwEvC,uBkBvEyC;AnBkwF7C;;AmBjxFA;EAqBM,uBjBhEyB;EiBiEzB,cjB9EuB;AF80F7B;;AmBtxFA;EAqBM,yBjB7EuB;EiB8EvB,YjBjEyB;AFs0F/B;;AmB3xFA;EAqBM,4BjBlEwB;EiBmExB,yBRAe;AX0wFrB;;AmBhyFA;EAqBM,yBjBzEwB;EiB0ExB,WREU;AX6wFhB;;AmBryFA;EAqBM,yBjB3D4B;EiB4D5B,WREU;AXkxFhB;;AmB1yFA;EA4BU,yBRGsC;EQFtC,cRW2D;AXuwFrE;;AmB/yFA;EAqBM,yBjBzD4B;EiB0D5B,WREU;AX4xFhB;;AmBpzFA;EA4BU,yBRGsC;EQFtC,cRW2D;AXixFrE;;AmBzzFA;EAqBM,yBjB1D4B;EiB2D5B,WREU;AXsyFhB;;AmB9zFA;EA4BU,yBRGsC;EQFtC,cRW2D;AX2xFrE;;AmBn0FA;EAqBM,yBjB5D4B;EiB6D5B,WREU;AXgzFhB;;AmBx0FA;EA4BU,yBRGsC;EQFtC,cRW2D;AXqyFrE;;AmB70FA;EAqBM,yBjB7D4B;EiB8D5B,yBRAe;AX4zFrB;;AmBl1FA;EA4BU,yBRGsC;EQFtC,cRW2D;AX+yFrE;;AmBv1FA;EAqBM,yBjBvD2B;EiBwD3B,WREU;AXo0FhB;;AmB51FA;EA4BU,yBRGsC;EQFtC,cRW2D;AXyzFrE;;AmBj2FA;EAgCI,kBjBpDY;AFy3FhB;;AmBr2FA;EAkCI,ejBvDS;AF83Fb;;AmBz2FA;EAoCI,kBjB1DY;AFm4FhB;;AmB72FA;ElBsFI,qBkB/C0C;ElB+C1C,sBkB9C0C;AnB00F9C;;AmBl3FA;ElBsFI,qBkB5C0C;ElB4C1C,sBkB3C0C;AnB40F9C;;AmBv3FA;ElBsFI,qBkBzC0C;ElByC1C,sBkBxC0C;AnB80F9C;;AmB53FA;ElBsFI,gBkB7ImB;EAyGnB,UAAU;EACV,kBAAkB;EAClB,UAAU;AnB+0Fd;;AmBn4FA;EAuDM,8BAA8B;EAC9B,WAAW;EACX,cAAc;EACd,SAAS;EACT,kBAAkB;EAClB,QAAQ;EACR,0DAA0D;EAC1D,+BAA+B;AnBg1FrC;;AmB94FA;EAgEM,WAAW;EACX,UAAU;AnBk1FhB;;AmBn5FA;EAmEM,WAAW;EACX,UAAU;AnBo1FhB;;AmBx5FA;EAuEM,yBAAmD;AnBq1FzD;;AmB55FA;EAyEM,yBAAoD;AnBu1F1D;;AmBh6FA;EA2EI,uBjB9DqB;AFu5FzB;;AmBv1FA;EAEI,0BAA0B;AnBy1F9B;;AoB/8FA;;EAGE,sBAAsB;ApBi9FxB;;AoBp9FA;;;;EAMI,oBAAoB;ApBq9FxB;;AoB39FA;;EAQI,iBApBmB;ApB4+FvB;;AoBh+FA;;EAUI,iBArBmB;ApBg/FvB;;AoBr+FA;;EAYI,sBAAsB;ApB89F1B;;AoB59FA;EACE,clB5B4B;EkB+B5B,elBHW;EkBIX,gBlBKmB;EkBJnB,kBAnCuB;ApBggGzB;;AoBn+FA;EAQI,cApCwB;EAqCxB,oBApCyB;ApBmgG7B;;AoBx+FA;EAWI,oBAAoB;ApBi+FxB;;AoB5+FA;EAaI,oBA7B+B;ApBggGnC;;AoBh/FA;EAkBM,elBnBO;AFq/Fb;;AoBp/FA;EAkBM,iBlBlBS;AFw/Ff;;AoBx/FA;EAkBM,elBjBO;AF2/Fb;;AoB5/FA;EAkBM,iBlBhBS;AF8/Ff;;AoBhgGA;EAkBM,kBlBfU;AFigGhB;;AoBpgGA;EAkBM,elBdO;AFogGb;;AoBxgGA;EAkBM,kBlBbU;AFugGhB;;AoBx/FA;EACE,clB/C4B;EkBkD5B,kBlBrBc;EkBsBd,gBlBjBiB;EkBkBjB,iBA7CyB;ApBsiG3B;;AoB//FA;EAQI,clBvD0B;EkBwD1B,gBlBnBiB;AF8gGrB;;AoBpgGA;EAWI,oBA/C+B;ApB4iGnC;;AoBxgGA;EAgBM,elBrCO;AFiiGb;;AoB5gGA;EAgBM,iBlBpCS;AFoiGf;;AoBhhGA;EAgBM,elBnCO;AFuiGb;;AoBphGA;EAgBM,iBlBlCS;AF0iGf;;AoBxhGA;EAgBM,kBlBjCU;AF6iGhB;;AoB5hGA;EAgBM,elBhCO;AFgjGb;;AoBhiGA;EAgBM,kBlB/BU;AFmjGhB;;AqBnlGA;EACE,cAAc;EACd,eAAe;EACf,mBAAmB;EACnB,kBAAkB;EAClB,yBAAyB;ArBslG3B;;AqBplGA;EAEE,gBnB0BiB;EmBzBjB,eAAe;EACf,gBAAgB;EAChB,UAAU;ArBslGZ;;AqB3lGA;EAOI,cAAc;EACd,eAAe;ArBwlGnB;;AqBnlGA;EACE,mBAAmB;EACnB,4BnBf4B;EmBgB5B,uBnB0CuB;EmBzCvB,oBAAoB;EACpB,kBnBKc;EmBJd,WAAW;EACX,uBAAuB;EACvB,oBAAoB;EACpB,gBAAgB;EAChB,uBAAuB;EACvB,kBAAkB;EAClB,mBAAmB;ArBslGrB;;AsB5nGA,eAAA;ACuDA;EAxBE,uBrBhB6B;EqBiB7B,qBrBtB4B;EqBuB5B,kBrBoCU;EqBnCV,crB5B4B;AF8nG9B;;ACjkGI;EsB/BA,4BrB9B0B;AFkoG9B;;ACrkGI;EsB/BA,4BrB9B0B;AFsoG9B;;ACzkGI;EsB/BA,4BrB9B0B;AF0oG9B;;AC7kGI;EsB/BA,4BrB9B0B;AF8oG9B;;AuB/mGE;EAEE,qBrB9B0B;AF+oG9B;;AuBhnGE;EAIE,qBrBtB8B;EqBuB9B,kDrBvB8B;AFuoGlC;;AuB/mGE;;;;;EAEE,4BrBnC0B;EqBoC1B,wBrBpC0B;EqBqC1B,gBAAgB;EAChB,crB3C0B;AFgqG9B;;ACrmGI;;;;;EsBdE,+BrB7CwB;AFwqG9B;;AC7mGI;;;;;EsBdE,+BrB7CwB;AFgrG9B;;ACrnGI;;;;;EsBdE,+BrB7CwB;AFwrG9B;;AC7nGI;;;;;EsBdE,+BrB7CwB;AFgsG9B;;AwBlsGA;EAEE,2DtBN2B;EsBO3B,eAAe;EACf,WAAW;AxBosGb;;AwBnsGE;EACE,gBAAgB;AxBssGpB;;AwBlsGI;EACE,mBtBFyB;AFusG/B;;AwBtsGK;EAMG,mDtBPuB;AF2sG/B;;AwB1sGI;EACE,qBtBfuB;AF4tG7B;;AwB9sGK;EAMG,gDtBpBqB;AFguG7B;;AwBltGI;EACE,wBtBJwB;AFytG9B;;AwBttGK;EAMG,mDtBTsB;AF6tG9B;;AwB1tGI;EACE,qBtBXwB;AFwuG9B;;AwB9tGK;EAMG,gDtBhBsB;AF4uG9B;;AwBluGI;EACE,qBtBG4B;AFkuGlC;;AwBtuGK;EAMG,iDtBF0B;AFsuGlC;;AwB1uGI;EACE,qBtBK4B;AFwuGlC;;AwB9uGK;EAMG,kDtBA0B;AF4uGlC;;AwBlvGI;EACE,qBtBI4B;AFivGlC;;AwBtvGK;EAMG,kDtBD0B;AFqvGlC;;AwB1vGI;EACE,qBtBE4B;AF2vGlC;;AwB9vGK;EAMG,kDtBH0B;AF+vGlC;;AwBlwGI;EACE,qBtBC4B;AFowGlC;;AwBtwGK;EAMG,kDtBJ0B;AFwwGlC;;AwB1wGI;EACE,qBtBO2B;AFswGjC;;AwB9wGK;EAMG,kDtBEyB;AF0wGjC;;AwB1wGE;ErBoBA,kBDwBgB;ECvBhB,kBDPc;AFiwGhB;;AwB7wGE;ErBqBA,kBDXc;AFuwGhB;;AwB/wGE;ErBqBA,iBDda;AF4wGf;;AwBhxGE;EACE,cAAc;EACd,WAAW;AxBmxGf;;AwBlxGE;EACE,eAAe;EACf,WAAW;AxBqxGf;;AwBnxGA;EAGI,uBtB8BqB;EsB7BrB,gDAA4D;EAC5D,iDAA6D;AxBoxGjE;;AwBzxGA;EAOI,6BAA6B;EAC7B,yBAAyB;EACzB,gBAAgB;EAChB,eAAe;EACf,gBAAgB;AxBsxGpB;;AwBpxGA;EAEE,cAAc;EACd,eAAe;EACf,eAAe;EACf,2BrB/CkE;EqBgDlE,gBAAgB;AxBsxGlB;;AwB5xGA;EAQI,gBA1DsB;EA2DtB,eA1DqB;AxBk1GzB;;AwBjyGA;EAWI,eAAe;AxB0xGnB;;AwBryGA;EAcI,YAAY;AxB2xGhB;;AyB51GA;EACE,eAAe;EACf,qBAAqB;EACrB,iBAAiB;EACjB,kBAAkB;AzB+1GpB;;AyB91GE;EACE,eAAe;AzBi2GnB;;AyBh2GE;EACE,cvBF0B;AFq2G9B;;AyBl2GE;;;;;EAGE,cvBJ0B;EuBK1B,mBAAmB;AzBu2GvB;;AyBl2GA;ExB8HI,kBwB3HqC;AzBm2GzC;;A0Bt3GA;EACE,qBAAqB;EACrB,eAAe;EACf,kBAAkB;EAClB,mBAAmB;A1By3GrB;;A0B73GA;EAMI,avBHkB;AH83GtB;;A0Bj4GA;EAUM,qBxBU4B;EDkI9B,cyB3I+B;EAC7B,UAAU;A1B23GhB;;A0Bv4GA;EAeM,uBxBsDmB;EDyErB,iByB9HsC;A1B43G1C;;A0B54GA;EAmBI,eAAe;EACf,cAAc;EACd,cAAc;EACd,eAAe;EACf,aAAa;A1B63GjB;;A0Bp5GA;EAyBM,aAAa;A1B+3GnB;;A0Bx5GA;;EA4BM,wBxBjBwB;AFk5G9B;;A0B75GA;EzB8II,oByBhHwC;A1Bm4G5C;;A0Bj6GA;EAgCM,YAAY;EACZ,UAAU;A1Bq4GhB;;A0Bt6GA;EAmCQ,kBAAkB;A1Bu4G1B;;A0B16GA;EAuCM,qBxBnCwB;AF06G9B;;A0B96GA;EA6CQ,mBxBhCuB;AFq6G/B;;A0Bl7GA;EA+CQ,mBxBlCuB;AFy6G/B;;A0Bt7GA;EAkDU,qBfyDuB;AX+0GjC;;A0B17GA;EAuDU,mDxB1CqB;AFi7G/B;;A0B97GA;EA6CQ,qBxB7CqB;AFk8G7B;;A0Bl8GA;EA+CQ,qBxB/CqB;AFs8G7B;;A0Bt8GA;EAkDU,mBfyDuB;AX+1GjC;;A0B18GA;EAuDU,gDxBvDmB;AF88G7B;;A0B98GA;EA6CQ,wBxBlCsB;AFu8G9B;;A0Bl9GA;EA+CQ,wBxBpCsB;AF28G9B;;A0Bt9GA;EAkDU,qBfyDuB;AX+2GjC;;A0B19GA;EAuDU,mDxB5CoB;AFm9G9B;;A0B99GA;EA6CQ,qBxBzCsB;AF89G9B;;A0Bl+GA;EA+CQ,qBxB3CsB;AFk+G9B;;A0Bt+GA;EAkDU,qBfyDuB;AX+3GjC;;A0B1+GA;EAuDU,gDxBnDoB;AF0+G9B;;A0B9+GA;EA6CQ,qBxB3B0B;AFg+GlC;;A0Bl/GA;EA+CQ,qBxB7B0B;AFo+GlC;;A0Bt/GA;EAkDU,qBfyDuB;AX+4GjC;;A0B1/GA;EAuDU,iDxBrCwB;AF4+GlC;;A0B9/GA;EA6CQ,qBxBzB0B;AF8+GlC;;A0BlgHA;EA+CQ,qBxB3B0B;AFk/GlC;;A0BtgHA;EAkDU,qBfyDuB;AX+5GjC;;A0B1gHA;EAuDU,kDxBnCwB;AF0/GlC;;A0B9gHA;EA6CQ,qBxB1B0B;AF+/GlC;;A0BlhHA;EA+CQ,qBxB5B0B;AFmgHlC;;A0BthHA;EAkDU,qBfyDuB;AX+6GjC;;A0B1hHA;EAuDU,kDxBpCwB;AF2gHlC;;A0B9hHA;EA6CQ,qBxB5B0B;AFihHlC;;A0BliHA;EA+CQ,qBxB9B0B;AFqhHlC;;A0BtiHA;EAkDU,qBfyDuB;AX+7GjC;;A0B1iHA;EAuDU,kDxBtCwB;AF6hHlC;;A0B9iHA;EA6CQ,qBxB7B0B;AFkiHlC;;A0BljHA;EA+CQ,qBxB/B0B;AFsiHlC;;A0BtjHA;EAkDU,qBfyDuB;AX+8GjC;;A0B1jHA;EAuDU,kDxBvCwB;AF8iHlC;;A0B9jHA;EA6CQ,qBxBvByB;AF4iHjC;;A0BlkHA;EA+CQ,qBxBzByB;AFgjHjC;;A0BtkHA;EAkDU,qBfyDuB;AX+9GjC;;A0B1kHA;EAuDU,kDxBjCuB;AFwjHjC;;A0B9kHA;EvB0CE,kBDwBgB;ECvBhB,kBDPc;AF+iHhB;;A0BnlHA;EvB6CE,kBDXc;AFqjHhB;;A0BvlHA;EvB+CE,iBDda;AF0jHf;;A0B3lHA;EAkEM,qBxB5DwB;AFylH9B;;A0B/lHA;EAoEI,WAAW;A1B+hHf;;A0BnmHA;EAsEM,WAAW;A1BiiHjB;;A0BvmHA;EA0EM,aAAa;EACb,kBAAkB;EzB2EpB,cyB1E+B;EAC7B,YAAY;EACZ,eAAe;A1BiiHrB;;A0B/mHA;EAgFM,kBxB5CU;AF+kHhB;;A0BnnHA;EAkFM,kBxBhDU;AFqlHhB;;A0BvnHA;EAoFM,iBxBnDS;AF0lHf;;A2B9mHA;EAEE,oBAAoB;EACpB,aAAa;EACb,2BAA2B;EAC3B,kBAAkB;A3BgnHpB;;A2BrnHA;EAYQ,uBzBZuB;EyBavB,yBAAyB;EACzB,czB3BqB;AFwoH7B;;A2B3nHA;EAkBU,yBhB4EuB;EgB3EvB,yBAAyB;EACzB,czBjCmB;AF8oH7B;;A2BjoHA;EAwBU,yBAAyB;EACzB,+CzBzBqB;EyB0BrB,czBvCmB;AFopH7B;;A2BvoHA;EA8BU,yBhBgEuB;EgB/DvB,yBAAyB;EACzB,czB7CmB;AF0pH7B;;A2B7oHA;EAYQ,yBzBzBqB;EyB0BrB,yBAAyB;EACzB,YzBduB;AFmpH/B;;A2BnpHA;EAkBU,yBhB4EuB;EgB3EvB,yBAAyB;EACzB,YzBpBqB;AFypH/B;;A2BzpHA;EAwBU,yBAAyB;EACzB,4CzBtCmB;EyBuCnB,YzB1BqB;AF+pH/B;;A2B/pHA;EA8BU,uBhBgEuB;EgB/DvB,yBAAyB;EACzB,YzBhCqB;AFqqH/B;;A2BrqHA;EAYQ,4BzBdsB;EyBetB,yBAAyB;EACzB,yBhBmDa;AX0mHrB;;A2B3qHA;EAkBU,yBhB4EuB;EgB3EvB,yBAAyB;EACzB,yBhB6CW;AXgnHrB;;A2BjrHA;EAwBU,yBAAyB;EACzB,+CzB3BoB;EyB4BpB,yBhBuCW;AXsnHrB;;A2BvrHA;EA8BU,yBhBgEuB;EgB/DvB,yBAAyB;EACzB,yBhBiCW;AX4nHrB;;A2B7rHA;EAYQ,yBzBrBsB;EyBsBtB,yBAAyB;EACzB,WhBqDQ;AXgoHhB;;A2BnsHA;EAkBU,yBhB4EuB;EgB3EvB,yBAAyB;EACzB,WhB+CM;AXsoHhB;;A2BzsHA;EAwBU,yBAAyB;EACzB,4CzBlCoB;EyBmCpB,WhByCM;AX4oHhB;;A2B/sHA;EA8BU,yBhBgEuB;EgB/DvB,yBAAyB;EACzB,WhBmCM;AXkpHhB;;A2BrtHA;EAYQ,yBzBP0B;EyBQ1B,yBAAyB;EACzB,WhBqDQ;AXwpHhB;;A2B3tHA;EAkBU,yBhB4EuB;EgB3EvB,yBAAyB;EACzB,WhB+CM;AX8pHhB;;A2BjuHA;EAwBU,yBAAyB;EACzB,6CzBpBwB;EyBqBxB,WhByCM;AXoqHhB;;A2BvuHA;EA8BU,yBhBgEuB;EgB/DvB,yBAAyB;EACzB,WhBmCM;AX0qHhB;;A2B7uHA;EAYQ,yBzBL0B;EyBM1B,yBAAyB;EACzB,WhBqDQ;AXgrHhB;;A2BnvHA;EAkBU,yBhB4EuB;EgB3EvB,yBAAyB;EACzB,WhB+CM;AXsrHhB;;A2BzvHA;EAwBU,yBAAyB;EACzB,8CzBlBwB;EyBmBxB,WhByCM;AX4rHhB;;A2B/vHA;EA8BU,yBhBgEuB;EgB/DvB,yBAAyB;EACzB,WhBmCM;AXksHhB;;A2BrwHA;EAYQ,yBzBN0B;EyBO1B,yBAAyB;EACzB,WhBqDQ;AXwsHhB;;A2B3wHA;EAkBU,yBhB4EuB;EgB3EvB,yBAAyB;EACzB,WhB+CM;AX8sHhB;;A2BjxHA;EAwBU,yBAAyB;EACzB,8CzBnBwB;EyBoBxB,WhByCM;AXotHhB;;A2BvxHA;EA8BU,yBhBgEuB;EgB/DvB,yBAAyB;EACzB,WhBmCM;AX0tHhB;;A2B7xHA;EAYQ,yBzBR0B;EyBS1B,yBAAyB;EACzB,WhBqDQ;AXguHhB;;A2BnyHA;EAkBU,yBhB4EuB;EgB3EvB,yBAAyB;EACzB,WhB+CM;AXsuHhB;;A2BzyHA;EAwBU,yBAAyB;EACzB,8CzBrBwB;EyBsBxB,WhByCM;AX4uHhB;;A2B/yHA;EA8BU,yBhBgEuB;EgB/DvB,yBAAyB;EACzB,WhBmCM;AXkvHhB;;A2BrzHA;EAYQ,yBzBT0B;EyBU1B,yBAAyB;EACzB,yBhBmDa;AX0vHrB;;A2B3zHA;EAkBU,yBhB4EuB;EgB3EvB,yBAAyB;EACzB,yBhB6CW;AXgwHrB;;A2Bj0HA;EAwBU,yBAAyB;EACzB,8CzBtBwB;EyBuBxB,yBhBuCW;AXswHrB;;A2Bv0HA;EA8BU,yBhBgEuB;EgB/DvB,yBAAyB;EACzB,yBhBiCW;AX4wHrB;;A2B70HA;EAYQ,yBzBHyB;EyBIzB,yBAAyB;EACzB,WhBqDQ;AXgxHhB;;A2Bn1HA;EAkBU,yBhB4EuB;EgB3EvB,yBAAyB;EACzB,WhB+CM;AXsxHhB;;A2Bz1HA;EAwBU,yBAAyB;EACzB,8CzBhBuB;EyBiBvB,WhByCM;AX4xHhB;;A2B/1HA;EA8BU,yBhBgEuB;EgB/DvB,yBAAyB;EACzB,WhBmCM;AXkyHhB;;A2Br2HA;EAmCI,kBzBZY;AFk1HhB;;A2Bz2HA;EAqCI,kBzBhBY;AFw1HhB;;A2B72HA;EAwCQ,eAAe;A3By0HvB;;A2Bj3HA;EA0CI,iBzBtBW;AFi2Hf;;A2Br3HA;EA6CQ,eAAe;A3B40HvB;;A2Bz3HA;EAiDM,6BAA6B;EAC7B,0BAA0B;A3B40HhC;;A2B93HA;EAoDM,4BAA4B;EAC5B,yBAAyB;A3B80H/B;;A2Bn4HA;EAwDQ,kBzBFI;AFi1HZ;;A2Bv4HA;EA0DQ,aAAa;A3Bi1HrB;;A2B34HA;EA6DM,sBAAsB;A3Bk1H5B;;A2B/4HA;EA+DM,sBAAsB;EACtB,YAAY;EACZ,gBAAgB;A3Bo1HtB;;A2Br5HA;EAmEM,uBAAuB;A3Bs1H7B;;A2Bz5HA;EAqEM,aAAa;EACb,YAAY;A3Bw1HlB;;A2B95HA;EAwEQ,eAAe;A3B01HvB;;A2Bl6HA;EA2EQ,eAAe;A3B21HvB;;A2Bt6HA;EA8EQ,eAAe;A3B41HvB;;A2B16HA;EAiFQ,eAAe;A3B61HvB;;A2B96HA;EAoFQ,0BAA4C;A3B81HpD;;A2Bl7HA;EAsFQ,0BzBhCI;EyBiCJ,uBAAuB;A3Bg2H/B;;A2Bv7HA;EAyFI,uBAAuB;A3Bk2H3B;;A2B37HA;EA4FM,WAAW;A3Bm2HjB;;A2B/7HA;EA8FM,YAAY;EACZ,eAAe;A3Bq2HrB;;A2Bp8HA;EAiGI,yBAAyB;A3Bu2H7B;;A2Bx8HA;EAmGM,0BAA4C;A3By2HlD;;A2B58HA;EAqGM,0BzB/CM;EyBgDN,2BAA2B;EAC3B,SAAS;A3B22Hf;;A2Bz2HA;EACE,oBAAoB;EACpB,aAAa;EACb,eAAe;EACf,2BAA2B;EAC3B,gBAAgB;EAChB,kBAAkB;A3B42HpB;;A2Bl3HA;EASM,yBhBpB2B;EgBqB3B,czB5HwB;AFy+H9B;;A2Bv3HA;EAYM,qBhBvB2B;AXs4HjC;;A2B33HA;EAeM,yBhB1B2B;EgB2B3B,czBlIwB;AFk/H9B;;A2Bh4HA;EAkBM,qBhB7B2B;AX+4HjC;;A2Bh3HA;EACE,YAAY;EACZ,OAAO;EACP,UAAU;EACV,aAAa;EACb,kBAAkB;EAClB,MAAM;EACN,WAAW;A3Bm3Hb;;A2Bj3HA;;EAGE,qBzB9I4B;EyB+I5B,kBzBpFU;EyBqFV,cAAc;EACd,iBAAiB;EACjB,kBAAkB;EAClB,mBAAmB;A3Bm3HrB;;A2Bj3HA;EACE,4BzBnJ4B;EyBoJ5B,czB1J4B;AF8gI9B;;A2Bl3HA;EACE,qBzB1J4B;EyB2J5B,mBA5J4B;EA6J5B,2BA5JoC;EA6JpC,cAAc;EACd,eA7JwB;EA8JxB,gBAAgB;EAChB,mBAAmB;EACnB,uBAAuB;A3Bq3HzB;;A2Bn3HA;EACE,mBAAmB;EACnB,aAAa;EACb,WAAW;EACX,uBAAuB;E1BjCrB,mB0BkCmC;EACrC,UAAU;A3Bs3HZ;;A2B53HA;EAQI,eAAe;A3Bw3HnB;;A4BtiIA;EACE,c1BF4B;E0BG5B,cAAc;EACd,e1B2BW;E0B1BX,gB1BiCe;AFwgIjB;;A4B7iIA;EAMI,oBAAoB;A5B2iIxB;;A4BjjIA;EASI,kB1BsBY;AFshIhB;;A4BrjIA;EAWI,kB1BkBY;AF4hIhB;;A4BzjIA;EAaI,iB1BeW;AFiiIf;;A4B9iIA;EACE,cAAc;EACd,kB1Bcc;E0Bbd,mBAAmB;A5BijIrB;;A4BpjIA;EAOM,Y1BdyB;AF+jI/B;;A4BxjIA;EAOM,c1B3BuB;AFglI7B;;A4B5jIA;EAOM,iB1BhBwB;AFykI9B;;A4BhkIA;EAOM,c1BvBwB;AFolI9B;;A4BpkIA;EAOM,c1BT4B;AF0kIlC;;A4BxkIA;EAOM,c1BP4B;AF4kIlC;;A4B5kIA;EAOM,c1BR4B;AFilIlC;;A4BhlIA;EAOM,c1BV4B;AFulIlC;;A4BplIA;EAOM,c1BX4B;AF4lIlC;;A4BxlIA;EAOM,c1BL2B;AF0lIjC;;A4BjlIA;EAEI,sBAAsB;A5BmlI1B;;A4BrlIA;EAKI,aAAa;EACb,2BAA2B;A5BolI/B;;A4B1lIA;E3B+GI,kB2BtGwC;A5BqlI5C;;A4B9lIA;;;EAcU,gBAAgB;A5BslI1B;;A4BpmIA;;;EAoBY,6BAA6B;EAC7B,0BAA0B;A5BslItC;;A4B3mIA;;;EA8BY,4BAA4B;EAC5B,yBAAyB;A5BmlIrC;;A4BlnIA;;;;;EAyCY,UAAU;A5BilItB;;A4B1nIA;;;;;;;;;EA8CY,UAAU;A5BwlItB;;A4BtoIA;;;;;;;;;EAgDc,UAAU;A5BkmIxB;;A4BlpIA;EAkDQ,YAAY;EACZ,cAAc;A5BomItB;;A4BvpIA;EAqDM,uBAAuB;A5BsmI7B;;A4B3pIA;EAuDM,yBAAyB;A5BwmI/B;;A4B/pIA;EA0DQ,YAAY;EACZ,cAAc;A5BymItB;;A4BpqIA;EA6DI,aAAa;EACb,2BAA2B;A5B2mI/B;;A4BzqIA;EAgEM,cAAc;A5B6mIpB;;A4B7qIA;EAkEQ,gBAAgB;E3B6CpB,qB2B5C2C;A5B+mI/C;;A4BlrIA;EAqEQ,YAAY;EACZ,cAAc;A5BinItB;;A4BvrIA;EAwEM,uBAAuB;A5BmnI7B;;A4B3rIA;EA0EM,yBAAyB;A5BqnI/B;;A4B/rIA;EA4EM,eAAe;A5BunIrB;;A4BnsIA;EAgFU,sBAAsB;A5BunIhC;;A4BvsIA;EAkFQ,uBAAuB;A5BynI/B;;A4B3sIA;EAoFQ,gBAAgB;A5B2nIxB;;AC3pIE;E2BpDF;IAuFM,aAAa;E5B6nIjB;AACF;;A4B5nIA;EAEI,kBAAkB;A5B8nItB;;ACzqIE;E2ByCF;IAII,qBAAqB;E5BioIvB;AACF;;AC3qIE;E2BqCF;IAMI,aAAa;IACb,YAAY;IACZ,cAAc;I3Bcd,oB2BbsC;IACtC,iBAAiB;E5BqoInB;E4B/oIF;IAYM,kB1BhGU;I0BiGV,oBAAoB;E5BsoIxB;E4BnpIF;IAeM,oBAAoB;E5BuoIxB;E4BtpIF;IAiBM,kB1BvGU;I0BwGV,oBAAoB;E5BwoIxB;E4B1pIF;IAoBM,iB1B3GS;I0B4GT,oBAAoB;E5ByoIxB;AACF;;A4BxoIA;EAEI,gBAAgB;A5B0oIpB;;ACxsIE;E2B4DF;IAII,aAAa;IACb,aAAa;IACb,YAAY;IACZ,cAAc;E5B6oIhB;E4BppIF;IASM,gBAAgB;E5B8oIpB;E4BvpIF;IAWM,cAAc;E5B+oIlB;E4B1pIF;IAaQ,YAAY;E5BgpIlB;E4B7pIF;I3BDI,qB2BgB2C;E5BipI7C;AACF;;A4BhpIA;EACE,sBAAsB;EACtB,WAAW;EACX,e1BhIW;E0BiIX,kBAAkB;EAClB,mBAAmB;A5BmpIrB;;A4BxpIA;;;EAaU,c1BxKoB;AFyzI9B;;A4B9pIA;;;EAeQ,kB1B3IQ;AFgyIhB;;A4BpqIA;;;EAiBQ,kB1B/IQ;AFwyIhB;;A4B1qIA;;;EAmBQ,iB1BlJO;AF+yIf;;A4BhrIA;EAqBM,c1B7KwB;E0B8KxB,azBnLgB;EyBoLhB,oBAAoB;EACpB,kBAAkB;EAClB,MAAM;EACN,YzBvLgB;EyBwLhB,UAAU;A5B+pIhB;;A4B1rIA;;EA+BM,mBzB5LgB;AH41ItB;;A4B/rIA;EAiCM,OAAO;A5BkqIb;;A4BnsIA;;EAqCM,oBzBlMgB;AHq2ItB;;A4BxsIA;EAuCM,QAAQ;A5BqqId;;A4B5sIA;EA2CM,6BAA6B;E3BrD/B,c2BsD+B;EAC7B,YAAY;EACZ,UAAU;A5BqqIhB;;A4BntIA;EAgDM,kB1B5KU;AFm1IhB;;A4BvtIA;EAkDM,kB1BhLU;AFy1IhB;;A4B3tIA;EAoDM,iB1BnLS;AF81If;;A6Bj4IA,qBAAA;ACSA;EAGE,e5ByBW;E4BxBX,mBAAmB;A9B03IrB;;A8B93IA;EAMI,mBAAmB;EACnB,c5BM8B;E4BL9B,aAAa;EACb,uBAAuB;EACvB,iBAduC;A9B04I3C;;A8Bt4IA;EAYM,c5BfwB;AF64I9B;;A8B14IA;EAcI,mBAAmB;EACnB,aAAa;A9Bg4IjB;;A8B/4IA;E7BuII,e6BtHoC;A9Bk4IxC;;A8Bn5IA;EAoBQ,c5BvBsB;E4BwBtB,eAAe;EACf,oBAAoB;A9Bm4I5B;;A8Bz5IA;EAwBM,c5BxBwB;E4ByBxB,iBAAiB;A9Bq4IvB;;A8B95IA;;EA4BI,uBAAuB;EACvB,aAAa;EACb,eAAe;EACf,2BAA2B;A9Bu4I/B;;A8Bt6IA;E7BuII,mB6BrGuC;A9Bw4I3C;;A8B16IA;E7BuII,kB6BnGuC;A9B04I3C;;A8B96IA;;EAyCM,uBAAuB;A9B04I7B;;A8Bn7IA;;EA6CM,yBAAyB;A9B24I/B;;A8Bx7IA;EAgDI,kB5BnBY;AF+5IhB;;A8B57IA;EAkDI,kB5BvBY;AFq6IhB;;A8Bh8IA;EAoDI,iB5B1BW;AF06If;;A8Bp8IA;EAwDM,iBAAiB;A9Bg5IvB;;A8Bx8IA;EA2DM,iBAAiB;A9Bi5IvB;;A8B58IA;EA8DM,iBAAiB;A9Bk5IvB;;A8Bh9IA;EAiEM,iBAAiB;A9Bm5IvB;;A+Bx8IA;EACE,uB7BP6B;E6BQ7B,sBApBmB;EAqBnB,0F7BtB2B;E6BuB3B,c7BlB4B;E6BmB5B,eAAe;EACf,gBAvBoB;EAwBpB,kBAAkB;A/B28IpB;;A+Bz8IA;EACE,6BAzBwC;EA0BxC,oBAAoB;EACpB,kD7B/B2B;E6BgC3B,aAAa;A/B48If;;A+B18IA;EACE,mBAAmB;EACnB,c7BhC4B;E6BiC5B,aAAa;EACb,YAAY;EACZ,gB7BGe;E6BFf,qBAlCgC;A/B++IlC;;A+Bn9IA;EAQI,uBAAuB;A/B+8I3B;;A+B78IA;EACE,mBAAmB;EACnB,eAAe;EACf,aAAa;EACb,uBAAuB;EACvB,qBA3CgC;A/B2/IlC;;A+B98IA;EACE,cAAc;EACd,kBAAkB;A/Bi9IpB;;A+B/8IA;EACE,6BA9CyC;EA+CzC,eA9C2B;A/BggJ7B;;A+Bh9IA;EACE,6BA/CwC;EAgDxC,6B7BpD6B;E6BqD7B,oBAAoB;EACpB,aAAa;A/Bm9If;;A+Bj9IA;EACE,mBAAmB;EACnB,aAAa;EACb,aAAa;EACb,YAAY;EACZ,cAAc;EACd,uBAAuB;EACvB,gBAzD2B;A/B6gJ7B;;A+B39IA;E9B6EI,+BCrI2B;AFuhJ/B;;A+Bl9IA;EAEI,qB7BlCkB;AFs/ItB;;AgCnhJA;EACE,oBAAoB;EACpB,kBAAkB;EAClB,mBAAmB;AhCshJrB;;AgCzhJA;EAOM,cAAc;AhCshJpB;;AgC7hJA;EAUM,UAAU;EACV,QAAQ;AhCuhJd;;AgCliJA;EAcM,YAAY;EACZ,mBA9BuB;EA+BvB,oBAAoB;EACpB,SAAS;AhCwhJf;;AgCthJA;EACE,aAAa;E/BiHX,O+BhHqB;EACvB,gBAzC6B;EA0C7B,gBAtC2B;EAuC3B,kBAAkB;EAClB,SAAS;EACT,WApCqB;AhC6jJvB;;AgCvhJA;EACE,uB9BjC6B;E8BkC7B,kB9BoBU;E8BnBV,0F9BhD2B;E8BiD3B,sBA9CsC;EA+CtC,mBA9CmC;AhCwkJrC;;AgB5jJgB;EgBqCd,c9BhD4B;E8BiD5B,cAAc;EACd,mBAAmB;EACnB,gBAAgB;EAChB,sBAAsB;EACtB,kBAAkB;AhC2hJpB;;AgCzhJA;;E/BkFI,mB+BhFmC;EACrC,mBAAmB;EACnB,mBAAmB;EACnB,WAAW;AhC4hJb;;AgCjiJA;;EAOI,4B9BxD0B;E8ByD1B,c9BpEyB;AFmmJ7B;;AgCviJA;;EAUI,yB9BlD8B;E8BmD9B,WrBSY;AXyhJhB;;AgChiJA;EACE,yB9BjE6B;E8BkE7B,YAAY;EACZ,cAAc;EACd,WAAW;EACX,gBAAgB;AhCmiJlB;;AiCjnJA;EAEE,mBAAmB;EACnB,8BAA8B;AjCmnJhC;;AiCtnJA;EAKI,kB/B8DQ;AFujJZ;;AiC1nJA;EAOI,qBAAqB;EACrB,mBAAmB;AjCunJvB;;AiC/nJA;EAWI,aAAa;AjCwnJjB;;AiCnoJA;;EAcM,aAAa;AjC0nJnB;;AiCxoJA;EAgBM,aAAa;AjC4nJnB;;AiC5oJA;EAmBQ,gBAAgB;EhC2HpB,qBgChJqC;AjCmpJzC;;AiCjpJA;EAsBQ,YAAY;AjC+nJpB;;AClkJE;EgCnFF;IAyBI,aAAa;EjCioJf;EiC1pJF;IA4BQ,YAAY;EjCioJlB;AACF;;AiChoJA;EACE,mBAAmB;EACnB,aAAa;EACb,gBAAgB;EAChB,YAAY;EACZ,cAAc;EACd,uBAAuB;AjCmoJzB;;AiCzoJA;;EASI,gBAAgB;AjCqoJpB;;AC7lJE;EgCjDF;IAaM,sBA7CmC;EjCmrJvC;AACF;;AiCroJA;;EAEE,gBAAgB;EAChB,YAAY;EACZ,cAAc;AjCwoJhB;;AiC5oJA;;EAQM,YAAY;AjCyoJlB;;AC3mJE;EgCtCF;;IhCiGI,qBgChJqC;EjCssJvC;AACF;;AiC1oJA;EACE,mBAAmB;EACnB,2BAA2B;AjC6oJ7B;;AC3nJE;EgCpBF;IAMM,kBAAkB;EjC8oJtB;AACF;;AC7nJE;EgCxBF;IAQI,aAAa;EjCkpJf;AACF;;AiCjpJA;EACE,mBAAmB;EACnB,yBAAyB;AjCopJ3B;;ACxoJE;EgCdF;IAKI,aAAa;EjCspJf;AACF;;AkC/tJA;EACE,uBAAuB;EACvB,aAAa;EACb,mBAAmB;AlCkuJrB;;AkCruJA;EAKI,sBAAsB;AlCouJ1B;;AkCzuJA;EAOI,8ChCD0B;EgCE1B,aAAa;EACb,oBAAoB;AlCsuJxB;;AkC/uJA;;EAYM,qBAAqB;AlCwuJ3B;;AkCpvJA;EAcM,mBAAmB;AlC0uJzB;;AkCxvJA;EAgBQ,kBAAkB;AlC4uJ1B;;AkC5vJA;EAkBI,8ChCZ0B;EgCa1B,gBAtBgB;EAuBhB,iBAvBgB;AlCqwJpB;;AkClwJA;EAwBM,kBA1BsB;EA2BtB,mBA3BsB;AlCywJ5B;;AkC5uJA;;EAEE,gBAAgB;EAChB,YAAY;EACZ,cAAc;AlC+uJhB;;AkC7uJA;EjC2GI,kBiC/IgB;AlCqxJpB;;AkC9uJA;EjCwGI,iBiC/IgB;AlCyxJpB;;AkC/uJA;EACE,gBAAgB;EAChB,YAAY;EACZ,cAAc;EACd,mBAAmB;AlCkvJrB;;AChtJE;EiCtCF;IAQI,gBAAgB;ElCmvJlB;AACF;;AmCrxJA;EACE,ejCkBW;AFswJb;;AmCzxJA;EAII,kBjCgBY;AFywJhB;;AmC7xJA;EAMI,kBjCYY;AF+wJhB;;AmCjyJA;EAQI,iBjCSW;AFoxJf;;AmC3xJA;EACE,iBArB0B;AnCmzJ5B;;AmC/xJA;EAGI,kBjCqCc;EiCpCd,cjCzB0B;EiC0B1B,cAAc;EACd,qBAzBiC;AnCyzJrC;;AmCtyJA;EAQM,4BjCvBwB;EiCwBxB,cjC/BwB;AFi0J9B;;AmC3yJA;EAYM,yBjClB4B;EiCmB5B,WxByCU;AX0vJhB;;AmChzJA;ElCoHI,8BCtI0B;EiCmCxB,cAnC0B;ElCsI5B,oBkCrIkC;AnCu0JtC;;AmClyJA;EACE,cjCzC4B;EiC0C5B,iBApC2B;EAqC3B,qBApC+B;EAqC/B,yBAAyB;AnCqyJ3B;;AmCzyJA;EAMI,eAtCoB;AnC60JxB;;AmC7yJA;EAQI,kBAxCoB;AnCi1JxB;;AoC50JA;EAEE,4BlCV4B;EkCW5B,kBlC6CU;EkC5CV,elCYW;AFk0Jb;;AoCl1JA;EAMI,mBAAmB;ApCg1JvB;;AoCt1JA;EAQI,mBAAmB;EACnB,0BAA0B;ApCk1J9B;;AoC31JA;EAYI,kBlCKY;AF80JhB;;AoC/1JA;EAcI,kBlCCY;AFo1JhB;;AoCn2JA;EAgBI,iBlCFW;AFy1Jf;;AoCv2JA;EAsCM,uBAH+C;ApCw0JrD;;AoC32JA;EAwCQ,uBlC9CuB;EkC+CvB,clC5DqB;AFm4J7B;;AoCh3JA;EA2CQ,mBlCjDuB;AF03J/B;;AoCp3JA;EAsCM,yBAH+C;ApCq1JrD;;AoCx3JA;EAwCQ,yBlC3DqB;EkC4DrB,YlC/CuB;AFm4J/B;;AoC73JA;EA2CQ,qBlC9DqB;AFo5J7B;;AoCj4JA;EAsCM,yBAH+C;ApCk2JrD;;AoCr4JA;EAwCQ,4BlChDsB;EkCiDtB,yBzBkBa;AX+0JrB;;AoC14JA;EA2CQ,wBlCnDsB;AFs5J9B;;AoC94JA;EAsCM,yBAH+C;ApC+2JrD;;AoCl5JA;EAwCQ,yBlCvDsB;EkCwDtB,WzBoBQ;AX01JhB;;AoCv5JA;EA2CQ,qBlC1DsB;AF06J9B;;AoC35JA;EAsCM,yBzB8B0C;AX21JhD;;AoC/5JA;EAwCQ,yBlCzC0B;EkC0C1B,WzBoBQ;AXu2JhB;;AoCp6JA;EA2CQ,qBlC5C0B;EkC6C1B,czBiC6D;AX41JrE;;AoCz6JA;EAsCM,yBzB8B0C;AXy2JhD;;AoC76JA;EAwCQ,yBlCvC0B;EkCwC1B,WzBoBQ;AXq3JhB;;AoCl7JA;EA2CQ,qBlC1C0B;EkC2C1B,czBiC6D;AX02JrE;;AoCv7JA;EAsCM,yBzB8B0C;AXu3JhD;;AoC37JA;EAwCQ,yBlCxC0B;EkCyC1B,WzBoBQ;AXm4JhB;;AoCh8JA;EA2CQ,qBlC3C0B;EkC4C1B,czBiC6D;AXw3JrE;;AoCr8JA;EAsCM,yBzB8B0C;AXq4JhD;;AoCz8JA;EAwCQ,yBlC1C0B;EkC2C1B,WzBoBQ;AXi5JhB;;AoC98JA;EA2CQ,qBlC7C0B;EkC8C1B,czBiC6D;AXs4JrE;;AoCn9JA;EAsCM,yBzB8B0C;AXm5JhD;;AoCv9JA;EAwCQ,yBlC3C0B;EkC4C1B,yBzBkBa;AXi6JrB;;AoC59JA;EA2CQ,qBlC9C0B;EkC+C1B,czBiC6D;AXo5JrE;;AoCj+JA;EAsCM,yBzB8B0C;AXi6JhD;;AoCr+JA;EAwCQ,yBlCrCyB;EkCsCzB,WzBoBQ;AX66JhB;;AoC1+JA;EA2CQ,qBlCxCyB;EkCyCzB,czBiC6D;AXk6JrE;;AoCj8JA;EACE,mBAAmB;EACnB,yBlC9D4B;EkC+D5B,0BAAgE;EAChE,WzBWc;EyBVd,aAAa;EACb,gBlC7Be;EkC8Bf,8BAA8B;EAC9B,iBAAiB;EACjB,mBAtEiC;EAuEjC,kBAAkB;ApCo8JpB;;AoC98JA;EAYI,YAAY;EACZ,cAAc;EnCgEd,mBmC/DsC;ApCs8J1C;;AoCp9JA;EAgBI,eAjEgC;EAkEhC,yBAAyB;EACzB,0BAA0B;ApCw8J9B;;AoCt8JA;EACE,qBlC9E4B;EkC+E5B,kBlCpBU;EkCqBV,mBAAmB;EACnB,uBAjFmC;EAkFnC,clCrF4B;EkCsF5B,qBAjFiC;ApC0hKnC;;AoC/8JA;;EASI,uBlCjF2B;AF4hK/B;;AoCp9JA;EAWI,6BAlFgD;ApC+hKpD;;AqC/gKA;EAEE,mBAAmB;EACnB,aAAa;EACb,sBAAsB;EACtB,uBAAuB;EACvB,gBAAgB;EAChB,eAAe;EACf,WAxCU;ArCyjKZ;;AqCzhKA;EAWI,aAAa;ArCkhKjB;;AqChhKA;EAEE,wCnC7C2B;AF+jK7B;;AqChhKA;;EAEE,cA9CgC;EA+ChC,+BAA0D;EAC1D,cAAc;EACd,kBAAkB;EAClB,WAAW;ArCmhKb;;ACjgKE;EoCxBF;;IASI,cAAc;IACd,8BAA0D;IAC1D,YAxDuB;ErC8kKzB;AACF;;AqCrhKA;EAEE,gBAAgB;EAChB,YAxD2B;EAyD3B,eAAe;EpCsFb,WoC9IoB;EA0DtB,SAzDoB;EA0DpB,WA5D2B;ArCmlK7B;;AqCrhKA;EACE,aAAa;EACb,sBAAsB;EACtB,8BAAgD;EAChD,gBAAgB;EAChB,uBAAuB;ArCwhKzB;;AqCthKA;;EAEE,mBAAmB;EACnB,4BnCpE4B;EmCqE5B,aAAa;EACb,cAAc;EACd,2BAA2B;EAC3B,aApE4B;EAqE5B,kBAAkB;ArCyhKpB;;AqCvhKA;EACE,gCnC/E4B;EmCgF5B,2BnCpBgB;EmCqBhB,4BnCrBgB;AF+iKlB;;AqCxhKA;EACE,cnCxF4B;EmCyF5B,YAAY;EACZ,cAAc;EACd,iBnC9Da;EmC+Db,cA7E8B;ArCwmKhC;;AqCzhKA;EACE,8BnC/BgB;EmCgChB,+BnChCgB;EmCiChB,6BnC7F4B;AFynK9B;;AqC/hKA;EpC4CI,mBoCtCuC;ArC6hK3C;;AqC3hKA;EpC9CE,iCAAiC;EoCgDjC,uBnC/F6B;EmCgG7B,YAAY;EACZ,cAAc;EACd,cAAc;EACd,aAtF4B;ArConK9B;;AsCxlKA;EACE,uBpC1C6B;EoC2C7B,mBAvDqB;EAwDrB,kBAAkB;EAClB,WAtDW;AtCipKb;;AsC/lKA;EASM,uBpClDyB;EoCmDzB,cpChEuB;AF0pK7B;;AsCpmKA;;EAcU,cpCpEmB;AF+pK7B;;AsCzmKA;;;;EAoBY,yB3BiCqB;E2BhCrB,cpC3EiB;AFuqK7B;;AsCjnKA;EAwBY,qBpC9EiB;AF2qK7B;;AsCrnKA;EA0BQ,cpChFqB;AF+qK7B;;ACxmKE;EqCjBF;;;;IAgCY,cpCtFiB;EFurK3B;EsCjoKF;;;;;;;;;;IAsCc,yB3BemB;I2BdnB,cpC7Fe;EFosK3B;EsC9oKF;;IA0Cc,qBpChGe;EFwsK3B;EsClpKF;;;IA8CU,yB3BOuB;I2BNvB,cpCrGmB;EF8sK3B;EsCxpKF;IAmDc,uBpC5FiB;IoC6FjB,cpC1Ge;EFktK3B;AACF;;AsC7pKA;EASM,yBpC/DuB;EoCgEvB,YpCnDyB;AF2sK/B;;AsClqKA;;EAcU,YpCvDqB;AFgtK/B;;AsCvqKA;;;;EAoBY,uB3BiCqB;E2BhCrB,YpC9DmB;AFwtK/B;;AsC/qKA;EAwBY,mBpCjEmB;AF4tK/B;;AsCnrKA;EA0BQ,YpCnEuB;AFguK/B;;ACtqKE;EqCjBF;;;;IAgCY,YpCzEmB;EFwuK7B;EsC/rKF;;;;;;;;;;IAsCc,uB3BemB;I2BdnB,YpChFiB;EFqvK7B;EsC5sKF;;IA0Cc,mBpCnFiB;EFyvK7B;EsChtKF;;;IA8CU,uB3BOuB;I2BNvB,YpCxFqB;EF+vK7B;EsCttKF;IAmDc,yBpCzGe;IoC0Gf,YpC7FiB;EFmwK7B;AACF;;AsC3tKA;EASM,4BpCpDwB;EoCqDxB,yB3Bce;AXwsKrB;;AsChuKA;;EAcU,yB3BUW;AX6sKrB;;AsCruKA;;;;EAoBY,yB3BiCqB;E2BhCrB,yB3BGS;AXqtKrB;;AsC7uKA;EAwBY,gC3BAS;AXytKrB;;AsCjvKA;EA0BQ,yB3BFa;AX6tKrB;;ACpuKE;EqCjBF;;;;IAgCY,yB3BRS;EXquKnB;EsC7vKF;;;;;;;;;;IAsCc,yB3BemB;I2BdnB,yB3BfO;EXkvKnB;EsC1wKF;;IA0Cc,gC3BlBO;EXsvKnB;EsC9wKF;;;IA8CU,yB3BOuB;I2BNvB,yB3BvBW;EX4vKnB;EsCpxKF;IAmDc,4BpC9FgB;IoC+FhB,yB3B5BO;EXgwKnB;AACF;;AsCzxKA;EASM,yBpC3DwB;EoC4DxB,W3BgBU;AXowKhB;;AsC9xKA;;EAcU,W3BYM;AXywKhB;;AsCnyKA;;;;EAoBY,yB3BiCqB;E2BhCrB,W3BKI;AXixKhB;;AsC3yKA;EAwBY,kB3BEI;AXqxKhB;;AsC/yKA;EA0BQ,W3BAQ;AXyxKhB;;AClyKE;EqCjBF;;;;IAgCY,W3BNI;EXiyKd;EsC3zKF;;;;;;;;;;IAsCc,yB3BemB;I2BdnB,W3BbE;EX8yKd;EsCx0KF;;IA0Cc,kB3BhBE;EXkzKd;EsC50KF;;;IA8CU,yB3BOuB;I2BNvB,W3BrBM;EXwzKd;EsCl1KF;IAmDc,yBpCrGgB;IoCsGhB,W3B1BE;EX4zKd;AACF;;AsCv1KA;EASM,yBpC7C4B;EoC8C5B,W3BgBU;AXk0KhB;;AsC51KA;;EAcU,W3BYM;AXu0KhB;;AsCj2KA;;;;EAoBY,yB3BiCqB;E2BhCrB,W3BKI;AX+0KhB;;AsCz2KA;EAwBY,kB3BEI;AXm1KhB;;AsC72KA;EA0BQ,W3BAQ;AXu1KhB;;ACh2KE;EqCjBF;;;;IAgCY,W3BNI;EX+1Kd;EsCz3KF;;;;;;;;;;IAsCc,yB3BemB;I2BdnB,W3BbE;EX42Kd;EsCt4KF;;IA0Cc,kB3BhBE;EXg3Kd;EsC14KF;;;IA8CU,yB3BOuB;I2BNvB,W3BrBM;EXs3Kd;EsCh5KF;IAmDc,yBpCvFoB;IoCwFpB,W3B1BE;EX03Kd;AACF;;AsCr5KA;EASM,yBpC3C4B;EoC4C5B,W3BgBU;AXg4KhB;;AsC15KA;;EAcU,W3BYM;AXq4KhB;;AsC/5KA;;;;EAoBY,yB3BiCqB;E2BhCrB,W3BKI;AX64KhB;;AsCv6KA;EAwBY,kB3BEI;AXi5KhB;;AsC36KA;EA0BQ,W3BAQ;AXq5KhB;;AC95KE;EqCjBF;;;;IAgCY,W3BNI;EX65Kd;EsCv7KF;;;;;;;;;;IAsCc,yB3BemB;I2BdnB,W3BbE;EX06Kd;EsCp8KF;;IA0Cc,kB3BhBE;EX86Kd;EsCx8KF;;;IA8CU,yB3BOuB;I2BNvB,W3BrBM;EXo7Kd;EsC98KF;IAmDc,yBpCrFoB;IoCsFpB,W3B1BE;EXw7Kd;AACF;;AsCn9KA;EASM,yBpC5C4B;EoC6C5B,W3BgBU;AX87KhB;;AsCx9KA;;EAcU,W3BYM;AXm8KhB;;AsC79KA;;;;EAoBY,yB3BiCqB;E2BhCrB,W3BKI;AX28KhB;;AsCr+KA;EAwBY,kB3BEI;AX+8KhB;;AsCz+KA;EA0BQ,W3BAQ;AXm9KhB;;AC59KE;EqCjBF;;;;IAgCY,W3BNI;EX29Kd;EsCr/KF;;;;;;;;;;IAsCc,yB3BemB;I2BdnB,W3BbE;EXw+Kd;EsClgLF;;IA0Cc,kB3BhBE;EX4+Kd;EsCtgLF;;;IA8CU,yB3BOuB;I2BNvB,W3BrBM;EXk/Kd;EsC5gLF;IAmDc,yBpCtFoB;IoCuFpB,W3B1BE;EXs/Kd;AACF;;AsCjhLA;EASM,yBpC9C4B;EoC+C5B,W3BgBU;AX4/KhB;;AsCthLA;;EAcU,W3BYM;AXigLhB;;AsC3hLA;;;;EAoBY,yB3BiCqB;E2BhCrB,W3BKI;AXygLhB;;AsCniLA;EAwBY,kB3BEI;AX6gLhB;;AsCviLA;EA0BQ,W3BAQ;AXihLhB;;AC1hLE;EqCjBF;;;;IAgCY,W3BNI;EXyhLd;EsCnjLF;;;;;;;;;;IAsCc,yB3BemB;I2BdnB,W3BbE;EXsiLd;EsChkLF;;IA0Cc,kB3BhBE;EX0iLd;EsCpkLF;;;IA8CU,yB3BOuB;I2BNvB,W3BrBM;EXgjLd;EsC1kLF;IAmDc,yBpCxFoB;IoCyFpB,W3B1BE;EXojLd;AACF;;AsC/kLA;EASM,yBpC/C4B;EoCgD5B,yB3Bce;AX4jLrB;;AsCplLA;;EAcU,yB3BUW;AXikLrB;;AsCzlLA;;;;EAoBY,yB3BiCqB;E2BhCrB,yB3BGS;AXykLrB;;AsCjmLA;EAwBY,gC3BAS;AX6kLrB;;AsCrmLA;EA0BQ,yB3BFa;AXilLrB;;ACxlLE;EqCjBF;;;;IAgCY,yB3BRS;EXylLnB;EsCjnLF;;;;;;;;;;IAsCc,yB3BemB;I2BdnB,yB3BfO;EXsmLnB;EsC9nLF;;IA0Cc,gC3BlBO;EX0mLnB;EsCloLF;;;IA8CU,yB3BOuB;I2BNvB,yB3BvBW;EXgnLnB;EsCxoLF;IAmDc,yBpCzFoB;IoC0FpB,yB3B5BO;EXonLnB;AACF;;AsC7oLA;EASM,yBpCzC2B;EoC0C3B,W3BgBU;AXwnLhB;;AsClpLA;;EAcU,W3BYM;AX6nLhB;;AsCvpLA;;;;EAoBY,yB3BiCqB;E2BhCrB,W3BKI;AXqoLhB;;AsC/pLA;EAwBY,kB3BEI;AXyoLhB;;AsCnqLA;EA0BQ,W3BAQ;AX6oLhB;;ACtpLE;EqCjBF;;;;IAgCY,W3BNI;EXqpLd;EsC/qLF;;;;;;;;;;IAsCc,yB3BemB;I2BdnB,W3BbE;EXkqLd;EsC5rLF;;IA0Cc,kB3BhBE;EXsqLd;EsChsLF;;;IA8CU,yB3BOuB;I2BNvB,W3BrBM;EX4qLd;EsCtsLF;IAmDc,yBpCnFmB;IoCoFnB,W3B1BE;EXgrLd;AACF;;AsC3sLA;EAsDI,oBAAoB;EACpB,aAAa;EACb,mBA7GmB;EA8GnB,WAAW;AtCypLf;;AsCltLA;EA2DI,gCpCtG0B;AFiwL9B;;AsCttLA;EALE,OAAO;EACP,eAAe;EACf,QAAQ;EACR,WA/CiB;AtC8wLnB;;AsC7tLA;EAgEI,SAAS;AtCiqLb;;AsCjuLA;EAkEM,iCpC7GwB;AFgxL9B;;AsCruLA;EAoEI,MAAM;AtCqqLV;;AsCnqLA;;EAGI,oBA9HmB;AtCmyLvB;;AsCxqLA;;EAKI,uBAhImB;AtCwyLvB;;AsCtqLA;;EAEE,oBAAoB;EACpB,aAAa;EACb,cAAc;EACd,mBAvIqB;AtCgzLvB;;AsCvqLA;EAIM,6BAA6B;AtCuqLnC;;AsCrqLA;ErCpFE,iCAAiC;EqCsFjC,gBAAgB;EAChB,gBAAgB;EAChB,kBAAkB;AtCwqLpB;;AsCtqLA;EACE,cpClJ4B;EDoB5B,eAAe;EACf,cAAc;EACd,eqC1BqB;ErC2BrB,kBAAkB;EAClB,cqC5BqB;ErC6InB,iBqCWkC;AtC6qLtC;;ACxyLE;EACE,8BAA8B;EAC9B,cAAc;EACd,WAAW;EACX,qBAAqB;EACrB,kBAAkB;EAClB,wBAAwB;EACxB,yBCiCQ;EDhCR,yDAAyD;EACzD,oCC0Ba;EDzBb,WAAW;AD2yLf;;AC1yLI;EACE,oBAAoB;AD6yL1B;;AC5yLI;EACE,oBAAoB;AD+yL1B;;AC9yLI;EACE,oBAAoB;ADizL1B;;AChzLE;EACE,qCAAiC;ADmzLrC;;AC/yLM;EACE,wCAAwC;ADkzLhD;;ACjzLM;EACE,UAAU;ADozLlB;;ACnzLM;EACE,0CAA0C;ADszLlD;;AsCptLA;EACE,aAAa;AtCutLf;;AsCrtLA;;EAEE,cpC3J4B;EoC4J5B,cAAc;EACd,gBAAgB;EAChB,uBAAuB;EACvB,kBAAkB;AtCwtLpB;;AsC9tLA;;EASM,qBAAqB;EACrB,sBAAsB;AtC0tL5B;;AsCxtLA;;EAEE,eAAe;AtC2tLjB;;AsC7tLA;;;;;EAOI,yBpCrK0B;EoCsK1B,cpC9J8B;AF43LlC;;AsC5tLA;EACE,YAAY;EACZ,cAAc;AtC+tLhB;;AsCjuLA;EAII,mBA5KgC;AtC64LpC;;AsCruLA;EAMI,UAAU;AtCmuLd;;AsCzuLA;EAQI,YAAY;EACZ,cAAc;AtCquLlB;;AsC9uLA;EAWI,oCAAoC;EACpC,mBA/LmB;EAgMnB,kCAAkC;AtCuuLtC;;AsCpvLA;EAgBM,6BApLyC;EAqLzC,4BpCjL4B;AFy5LlC;;AsCzvLA;EAmBM,6BApL0C;EAqL1C,4BpCpL4B;EoCqL5B,0BApLuC;EAqLvC,wBApLqC;EAqLrC,cpCvL4B;EoCwL5B,kCAAwE;AtC0uL9E;;AsCxuLA;EACE,YAAY;EACZ,cAAc;AtC2uLhB;;AsCzuLA;ErCpEI,oBqCqEoC;AtC4uLxC;;AsC7uLA;EAII,qBpClM8B;EoCmM9B,oBAAoB;ErCjEpB,cqCkE6B;AtC6uLjC;;AsC3uLA;EACE,mBAAmB;EACnB,sBAAsB;EACtB,mBAAmB;AtC8uLrB;;AsCjvLA;EAKI,oBAAoB;EACpB,qBAAqB;AtCgvLzB;;AsC9uLA;EACE,4BpCxN4B;EoCyN5B,YAAY;EACZ,aAAa;EACb,WA9LyB;EA+LzB,gBAAgB;AtCivLlB;;AC74LE;EqCrBF;IAqLI,cAAc;EtCkvLhB;EsCjvLA;;IAGI,mBAAmB;IACnB,aAAa;EtCkvLjB;EsCjvLA;IAEI,aAAa;EtCkvLjB;EsC10LF;IA0FI,uBpCxO2B;IoCyO3B,4CpCtPyB;IoCuPzB,iBAAiB;EtCmvLnB;EsCtvLA;IAKI,cAAc;EtCovLlB;EsClvLA;IA1MA,OAAO;IACP,eAAe;IACf,QAAQ;IACR,WA/CiB;EtC8+LjB;EsCxvLA;IAKI,SAAS;EtCsvLb;EsC3vLA;IAOM,4CpClQqB;EFy/L3B;EsC9vLA;IASI,MAAM;EtCwvLV;EsCjwLA;IrC/LA,iCAAiC;IqC6M3B,iCAA2C;IAC3C,cAAc;EtCuvLpB;EsCtvLA;;IAGI,oBA7QiB;EtCogMrB;EsC1vLA;;IAKI,uBA/QiB;EtCwgMrB;AACF;;ACn8LE;EqC4MA;;;;IAIE,oBAAoB;IACpB,aAAa;EtC2vLf;EsC79LF;IAoOI,mBAzRmB;EtCqhMrB;EsC7vLA;IAGI,kBAzR0B;EtCshM9B;EsChwLA;;IAMM,mBAAmB;EtC8vLzB;EsCpwLA;;IASM,kBpC/NI;EF89LV;EsCxwLA;;;;IAgBQ,wCAAwC;EtC8vLhD;EsC9wLA;IAuBU,wCAAwC;EtC0vLlD;EsCjxLA;IA4BU,4BpC1SkB;IoC2SlB,cpCtTiB;EF8iM3B;EsCrxLA;IA+BU,4BpC7SkB;IoC8SlB,cpCrSsB;EF8hMhC;EsC55LF;IAqKI,aAAa;EtC0vLf;EsCv5LF;;IAgKI,mBAAmB;IACnB,aAAa;EtC2vLf;EsCt4LF;IA8IM,oBAAoB;EtC2vLxB;EsC7vLA;IAKM,oDAAoD;EtC2vL1D;EsChwLA;IAOM,gCpC/TsB;IoCgUtB,0BAAkE;IAClE,gBAAgB;IAChB,YAAY;IACZ,4CpC3UqB;IoC4UrB,SAAS;EtC4vLf;EsCxwLA;IAkBM,cAAc;EtCyvLpB;EsCxvLM;IAEE,UAAU;IACV,oBAAoB;IACpB,wBAAwB;EtCyvLhC;EsCr7LF;IA8LI,YAAY;IACZ,cAAc;EtC0vLhB;EsCzvLA;IACE,2BAA2B;IrC9M3B,kBqC+MoC;EtC2vLtC;EsC1vLA;IACE,yBAAyB;IrCjNzB,iBqCkNoC;EtC4vLtC;EsCl4LF;IAwII,uBpCrV2B;IoCsV3B,8BpC/Rc;IoCgSd,+BpChSc;IoCiSd,6BpC7V0B;IoC8V1B,2CpCtWyB;IoCuWzB,aAAa;IACb,mBAAmB;IrClNnB,OqCmNuB;IACvB,eAAe;IACf,kBAAkB;IAClB,SAAS;IACT,WAhVkB;EtC6kMpB;EsCh5LF;IAqJM,sBAAsB;IACtB,mBAAmB;EtC8vLvB;EsC7wLA;IrCnNE,mBqCoOuC;EtC+vLzC;EsChxLA;IAoBM,4BpC1WsB;IoC2WtB,cpCtXqB;EFqnM3B;EsCpxLA;IAuBM,4BpC7WsB;IoC8WtB,cpCrW0B;EFqmMhC;EsC/vLE;IAEE,kBpCxTY;IoCyTZ,gBAAgB;IAChB,4EpC9XuB;IoC+XvB,cAAc;IACd,UAAU;IACV,oBAAoB;IACpB,wBAA8C;IAC9C,2BAA2B;IAC3B,yBpC9TM;IoC+TN,uCAAuC;EtCgwL3C;EsCpyLA;IAsCI,UAAU;IACV,QAAQ;EtCiwLZ;EsCv6LF;IAwKI,cAAc;EtCkwLhB;EsCjwLA;;IrC7PE,qBqCgQyC;EtCkwL3C;EsCrwLA;;IrC7PE,sBqCkQyC;EtCowL3C;EsClwLA;IAjWA,OAAO;IACP,eAAe;IACf,QAAQ;IACR,WA/CiB;EtCqpMjB;EsCxwLA;IAKI,SAAS;EtCswLb;EsC3wLA;IAOM,4CpCzZqB;EFgqM3B;EsC9wLA;IASI,MAAM;EtCwwLV;EsCvwLA;;IAGI,oBA9ZiB;EtCsqMrB;EsC3wLA;;IAKI,uBAhaiB;EtC0qMrB;EsC/wLA;;IAOI,oBAA4D;EtC4wLhE;EsCnxLA;;IASI,uBAA+D;EtC8wLnE;EsC5wLA;;IAGI,cpC1auB;EFurM3B;EsChxLA;;IAKI,6BAja2C;EtCgrM/C;EsC9wLA;IAKM,yBpCtasB;EFkrM5B;AACF;;AsCzwLA;EAEI,iCAA2C;AtC2wL/C;;AuCtqMA;EAEE,erCIW;EqCHX,gBAhC0B;AvCwsM5B;;AuC3qMA;EAMI,kBrCCY;AFwqMhB;;AuC/qMA;EAQI,kBrCHY;AF8qMhB;;AuCnrMA;EAUI,iBrCNW;AFmrMf;;AuCvrMA;;EAcM,iBAAiB;EACjB,kBAAkB;EAClB,uBrCwBmB;AFspMzB;;AuC9rMA;EAkBM,uBrCsBmB;AF0pMzB;;AuC9qMA;;EAEE,mBAAmB;EACnB,aAAa;EACb,uBAAuB;EACvB,kBAAkB;AvCirMpB;;AuC/qMA;;;;EAME,cA3D6B;EA4D7B,uBAAuB;EACvB,eA5D8B;EA6D9B,mBA5DkC;EA6DlC,oBA5DmC;EA6DnC,kBAAkB;AvCgrMpB;;AuC9qMA;;;EAGE,qBrChE4B;EqCiE5B,crCrE4B;EqCsE5B,gBpCvEoB;AHwvMtB;;AuCtrMA;;;EAOI,qBrCrE0B;EqCsE1B,crCzE0B;AF8vM9B;;AuC7rMA;;;EAUI,qBrC3D8B;AFovMlC;;AuCnsMA;;;EAYI,iDrCjFyB;AF8wM7B;;AuCzsMA;;;EAcI,yBrC3E0B;EqC4E1B,qBrC5E0B;EqC6E1B,gBAAgB;EAChB,crChF0B;EqCiF1B,YAAY;AvCisMhB;;AuC/rMA;;EAEE,oBAAoB;EACpB,qBAAqB;EACrB,mBAAmB;AvCksMrB;;AuChsMA;EAEI,yBrC7E8B;EqC8E9B,qBrC9E8B;EqC+E9B,W5BnBY;AXqtMhB;;AuChsMA;EACE,crC/F4B;EqCgG5B,oBAAoB;AvCmsMtB;;AuCjsMA;EACE,eAAe;AvCosMjB;;AC/tME;EsClDF;IAiFI,eAAe;EvCqsMjB;EuC1tMF;;IAwBI,YAAY;IACZ,cAAc;EvCssMhB;EuCrsMA;IAEI,YAAY;IACZ,cAAc;EvCssMlB;AACF;;AC1uME;EsCsBF;IAiBI,YAAY;IACZ,cAAc;IACd,2BAA2B;IAC3B,QAAQ;EvCwsMV;EuCvsMA;IACE,QAAQ;EvCysMV;EuCxsMA;IACE,QAAQ;EvC0sMV;EuC9yMF;IAsGI,8BAA8B;EvC2sMhC;EuC5sMA;IAIM,QAAQ;EvC2sMd;EuC/sMA;IAMM,uBAAuB;IACvB,QAAQ;EvC4sMd;EuCntMA;IASM,QAAQ;EvC6sMd;EuCttMA;IAYM,QAAQ;EvC6sMd;EuCztMA;IAcM,QAAQ;EvC8sMd;EuC5tMA;IAgBM,yBAAyB;IACzB,QAAQ;EvC+sMd;AACF;;AwCv0MA;EACE,kBtCuCgB;EsCtChB,0FtC9B2B;EsC+B3B,etCIW;AFs0Mb;;AwC70MA;EAKI,qBtCakB;AF+zMtB;;AwCj1MA;EAYQ,uBtC3BuB;EsC4BvB,ctCzCqB;AFk3M7B;;AwCt1MA;EAeQ,0BtC9BuB;AFy2M/B;;AwC11MA;EAiBQ,YtChCuB;AF62M/B;;AwC91MA;EAYQ,yBtCxCqB;EsCyCrB,YtC5BuB;AFk3M/B;;AwCn2MA;EAeQ,4BtC3CqB;AFm4M7B;;AwCv2MA;EAiBQ,ctC7CqB;AFu4M7B;;AwC32MA;EAYQ,4BtC7BsB;EsC8BtB,yB7BqCa;AX8zMrB;;AwCh3MA;EAeQ,+BtChCsB;AFq4M9B;;AwCp3MA;EAiBQ,iBtClCsB;AFy4M9B;;AwCx3MA;EAYQ,yBtCpCsB;EsCqCtB,W7BuCQ;AXy0MhB;;AwC73MA;EAeQ,4BtCvCsB;AFy5M9B;;AwCj4MA;EAiBQ,ctCzCsB;AF65M9B;;AwCr4MA;EAYQ,yBtCtB0B;EsCuB1B,W7BuCQ;AXs1MhB;;AwC14MA;EAeQ,4BtCzB0B;AFw5MlC;;AwC94MA;EAiBQ,ctC3B0B;AF45MlC;;AwCl5MA;EAYQ,yBtCpB0B;EsCqB1B,W7BuCQ;AXm2MhB;;AwCv5MA;EAeQ,4BtCvB0B;AFm6MlC;;AwC35MA;EAiBQ,ctCzB0B;AFu6MlC;;AwC/5MA;EAYQ,yBtCrB0B;EsCsB1B,W7BuCQ;AXg3MhB;;AwCp6MA;EAeQ,4BtCxB0B;AFi7MlC;;AwCx6MA;EAiBQ,ctC1B0B;AFq7MlC;;AwC56MA;EAYQ,yBtCvB0B;EsCwB1B,W7BuCQ;AX63MhB;;AwCj7MA;EAeQ,4BtC1B0B;AFg8MlC;;AwCr7MA;EAiBQ,ctC5B0B;AFo8MlC;;AwCz7MA;EAYQ,yBtCxB0B;EsCyB1B,yB7BqCa;AX44MrB;;AwC97MA;EAeQ,4BtC3B0B;AF88MlC;;AwCl8MA;EAiBQ,ctC7B0B;AFk9MlC;;AwCt8MA;EAYQ,yBtClByB;EsCmBzB,W7BuCQ;AXu5MhB;;AwC38MA;EAeQ,4BtCrByB;AFq9MjC;;AwC/8MA;EAiBQ,ctCvByB;AFy9MjC;;AwCh8MA;;EAGI,gCtCzC2B;AF2+M/B;;AwCh8MA;EACE,yBtC5C6B;EsC6C7B,0BAA8C;EAC9C,ctCnD4B;EsCoD5B,iBAhDyB;EAiDzB,gBtCfe;EsCgBf,iBArD8B;EAsD9B,mBArDgC;AxCw/MlC;;AwCj8MA;EACE,qBAAqB;EACrB,aAAa;EACb,kBArD4B;EAsD5B,uBAAuB;AxCo8MzB;;AwCx8MA;EAMI,gCtC3D0B;EsC4D1B,mBAAmB;EACnB,cAAc;AxCs8MlB;;AwC98MA;EAWM,4BtCnEwB;EsCoExB,ctCrEwB;AF4gN9B;;AwCr8MA;EAEI,ctCxE0B;AF+gN9B;;AwCz8MA;EAIM,ctC3D4B;AFogNlC;;AwCv8MA;EACE,mBAAmB;EACnB,ctC/E4B;EsCgF5B,aAAa;EACb,2BAA2B;EAC3B,qBAAqB;AxC08MvB;;AwC/8MA;EvC6DI,oBuCtDsC;AxC48M1C;;AwCn9MA;EASI,YAAY;EACZ,cAAc;EACd,WAAW;AxC88Mf;;AwCz9MA;EAaI,eAAe;AxCg9MnB;;AwC79MA;EAeI,0BtC5E8B;EsC6E9B,ctC7F0B;AF+iN9B;;AwCl+MA;EAkBM,ctC/E4B;AFmiNlC;;AwCt+MA;EAoBI,8BtCjCc;EsCkCd,+BtClCc;AFw/MlB;;AwCp9MA;;EAEE,eAAe;AxCu9MjB;;AwCz9MA;;EAII,4BtCjG0B;AF2jN9B;;AwCx9MA;EvC9FE,qBAAqB;EACrB,euC8FgB;EvC7FhB,WuC6FqB;EvC5FrB,gBuC4FqB;EvC3FrB,kBAAkB;EAClB,mBAAmB;EACnB,UuCyFqB;EACrB,ctC1G4B;EDwI1B,oBuC7BoC;AxCi+MxC;;AwCp+MA;EAKI,kBAAkB;EAClB,oBAAoB;AxCm+MxB;;AyC7jNA;ExCkCE,iCAAiC;EwC9BjC,oBAAoB;EACpB,aAAa;EACb,evCGW;EuCFX,8BAA8B;EAC9B,gBAAgB;EAChB,gBAAgB;EAChB,mBAAmB;AzC8jNrB;;AyCxkNA;EAYI,mBAAmB;EACnB,4BvC/B0B;EuCgC1B,0BAzC4B;EA0C5B,wBAzC0B;EA0C1B,cvCrC0B;EuCsC1B,aAAa;EACb,uBAAuB;EACvB,mBAA6C;EAC7C,kBAxCyB;EAyCzB,mBAAmB;AzCgkNvB;;AyCrlNA;EAuBM,4BvC7CwB;EuC8CxB,cvC9CwB;AFgnN9B;;AyC1lNA;EA0BI,cAAc;AzCokNlB;;AyC9lNA;EA6BQ,4BvCnC0B;EuCoC1B,cvCpC0B;AFymNlC;;AyCnmNA;EAgCI,mBAAmB;EACnB,4BvCnD0B;EuCoD1B,0BA7D4B;EA8D5B,wBA7D0B;EA8D1B,aAAa;EACb,YAAY;EACZ,cAAc;EACd,2BAA2B;AzCukN/B;;AyC9mNA;EAyCM,qBAAqB;AzCykN3B;;AyClnNA;EA2CM,UAAU;EACV,uBAAuB;EACvB,oBAAoB;EACpB,qBAAqB;AzC2kN3B;;AyCznNA;EAgDM,yBAAyB;EACzB,oBAAoB;AzC6kN1B;;AyC9nNA;ExCoHI,mBwChEuC;AzC8kN3C;;AyCloNA;ExCoHI,kBwC9DuC;AzCglN3C;;AyCtoNA;EA0DM,uBAAuB;AzCglN7B;;AyC1oNA;EA6DM,yBAAyB;AzCilN/B;;AyC9oNA;EAiEM,6BAA6B;EAE3B,0BAAkE;AzCglN1E;;AyCnpNA;EAuEQ,4BvCtFsB;EuCuFtB,4BvC1FsB;AF0qN9B;;AyCxpNA;EA4EU,uBvCzFqB;EuC0FrB,qBvC/FoB;EuCgGpB,2CAA2E;AzCglNrF;;AyC9pNA;EAiFM,YAAY;EACZ,cAAc;AzCilNpB;;AyCnqNA;EAqFM,qBvCvGwB;EuCwGxB,mBA/F+B;EAgG/B,iBA/F6B;EAgG7B,gBAAgB;EAChB,kBAAkB;AzCklNxB;;AyC3qNA;EA2FQ,4BvC1GsB;EuC2GtB,qBvC/GsB;EuCgHtB,UAAU;AzColNlB;;AyCjrNA;ExCoHI,iBwCpBuE;AzCqlN3E;;AyCrrNA;EAmGU,2BvC1DE;EuC2DF,8BvC3DE;AFipNZ;;AyC1rNA;EA0GU,4BvCjEE;EuCkEF,+BvClEE;AFspNZ;;AyC/rNA;EAiHU,yBvCvHwB;EuCwHxB,qBvCxHwB;EuCyHxB,W9B7DM;E8B8DN,UAAU;AzCklNpB;;AyCtsNA;EAsHM,mBAAmB;AzColNzB;;AyC1sNA;EA2HY,mCvChFa;EuCiFb,gCvCjFa;EuCkFb,oBAAoB;AzCmlNhC;;AyChtNA;EAoIY,oCvCzFa;EuC0Fb,iCvC1Fa;EuC2Fb,qBAAqB;AzCglNjC;;AyCttNA;EA6II,kBvCnIY;AFgtNhB;;AyC1tNA;EA+II,kBvCvIY;AFstNhB;;AyC9tNA;EAiJI,iBvC1IW;AF2tNf;;A0C9vNA,eAAA;ACEA;EACE,cAAc;EACd,aAAa;EACb,YAAY;EACZ,cAAc;EACd,gBAPkB;A3CuwNpB;;A2C/vNE;EACE,UAAU;A3CkwNd;;A2CjwNE;EACE,UAAU;EACV,WAAW;A3CowNf;;A2CnwNE;EACE,UAAU;EACV,UAAU;A3CswNd;;A2CrwNE;EACE,UAAU;EACV,eAAe;A3CwwNnB;;A2CvwNE;EACE,UAAU;EACV,UAAU;A3C0wNd;;A2CzwNE;EACE,UAAU;EACV,eAAe;A3C4wNnB;;A2C3wNE;EACE,UAAU;EACV,UAAU;A3C8wNd;;A2C7wNE;EACE,UAAU;EACV,UAAU;A3CgxNd;;A2C/wNE;EACE,UAAU;EACV,UAAU;A3CkxNd;;A2CjxNE;EACE,UAAU;EACV,UAAU;A3CoxNd;;A2CnxNE;EACE,UAAU;EACV,UAAU;A3CsxNd;;A2CrxNE;E1CwGE,gB0CvGmC;A3CwxNvC;;A2CvxNE;E1CsGE,qB0CrGwC;A3C0xN5C;;A2CzxNE;E1CoGE,gB0CnGmC;A3C4xNvC;;A2C3xNE;E1CkGE,qB0CjGwC;A3C8xN5C;;A2C7xNE;E1CgGE,gB0C/FmC;A3CgyNvC;;A2C/xNE;E1C8FE,gB0C7FmC;A3CkyNvC;;A2CjyNE;E1C4FE,gB0C3FmC;A3CoyNvC;;A2CnyNE;E1C0FE,gB0CzFmC;A3CsyNvC;;A2CryNE;E1CwFE,gB0CvFmC;A3CwyNvC;;A2CtyNI;EACE,UAAU;EACV,SAA0B;A3CyyNhC;;A2CxyNI;E1CkFA,e0CjFqD;A3C2yNzD;;A2C/yNI;EACE,UAAU;EACV,eAA0B;A3CkzNhC;;A2CjzNI;E1CkFA,qB0CjFqD;A3CozNzD;;A2CxzNI;EACE,UAAU;EACV,gBAA0B;A3C2zNhC;;A2C1zNI;E1CkFA,sB0CjFqD;A3C6zNzD;;A2Cj0NI;EACE,UAAU;EACV,UAA0B;A3Co0NhC;;A2Cn0NI;E1CkFA,gB0CjFqD;A3Cs0NzD;;A2C10NI;EACE,UAAU;EACV,gBAA0B;A3C60NhC;;A2C50NI;E1CkFA,sB0CjFqD;A3C+0NzD;;A2Cn1NI;EACE,UAAU;EACV,gBAA0B;A3Cs1NhC;;A2Cr1NI;E1CkFA,sB0CjFqD;A3Cw1NzD;;A2C51NI;EACE,UAAU;EACV,UAA0B;A3C+1NhC;;A2C91NI;E1CkFA,gB0CjFqD;A3Ci2NzD;;A2Cr2NI;EACE,UAAU;EACV,gBAA0B;A3Cw2NhC;;A2Cv2NI;E1CkFA,sB0CjFqD;A3C02NzD;;A2C92NI;EACE,UAAU;EACV,gBAA0B;A3Ci3NhC;;A2Ch3NI;E1CkFA,sB0CjFqD;A3Cm3NzD;;A2Cv3NI;EACE,UAAU;EACV,UAA0B;A3C03NhC;;A2Cz3NI;E1CkFA,gB0CjFqD;A3C43NzD;;A2Ch4NI;EACE,UAAU;EACV,gBAA0B;A3Cm4NhC;;A2Cl4NI;E1CkFA,sB0CjFqD;A3Cq4NzD;;A2Cz4NI;EACE,UAAU;EACV,gBAA0B;A3C44NhC;;A2C34NI;E1CkFA,sB0CjFqD;A3C84NzD;;A2Cl5NI;EACE,UAAU;EACV,WAA0B;A3Cq5NhC;;A2Cp5NI;E1CkFA,iB0CjFqD;A3Cu5NzD;;ACr4NE;E0C/EF;IAgEM,UAAU;E3Cy5Nd;E2Cz9NF;IAkEM,UAAU;IACV,WAAW;E3C05Nf;E2C79NF;IAqEM,UAAU;IACV,UAAU;E3C25Nd;E2Cj+NF;IAwEM,UAAU;IACV,eAAe;E3C45NnB;E2Cr+NF;IA2EM,UAAU;IACV,UAAU;E3C65Nd;E2Cz+NF;IA8EM,UAAU;IACV,eAAe;E3C85NnB;E2C7+NF;IAiFM,UAAU;IACV,UAAU;E3C+5Nd;E2Cj/NF;IAoFM,UAAU;IACV,UAAU;E3Cg6Nd;E2Cr/NF;IAuFM,UAAU;IACV,UAAU;E3Ci6Nd;E2Cz/NF;IA0FM,UAAU;IACV,UAAU;E3Ck6Nd;E2C7/NF;IA6FM,UAAU;IACV,UAAU;E3Cm6Nd;E2CjgOF;I1C8II,gB0C9CqC;E3Co6NvC;E2CpgOF;I1C8II,qB0C5C0C;E3Cq6N5C;E2CvgOF;I1C8II,gB0C1CqC;E3Cs6NvC;E2C1gOF;I1C8II,qB0CxC0C;E3Cu6N5C;E2C7gOF;I1C8II,gB0CtCqC;E3Cw6NvC;E2ChhOF;I1C8II,gB0CpCqC;E3Cy6NvC;E2CnhOF;I1C8II,gB0ClCqC;E3C06NvC;E2CthOF;I1C8II,gB0ChCqC;E3C26NvC;E2CzhOF;I1C8II,gB0C9BqC;E3C46NvC;E2C5hOF;IAmHQ,UAAU;IACV,SAA0B;E3C46NhC;E2ChiOF;I1C8II,e0CxBuD;E3C66NzD;E2CniOF;IAmHQ,UAAU;IACV,eAA0B;E3Cm7NhC;E2CviOF;I1C8II,qB0CxBuD;E3Co7NzD;E2C1iOF;IAmHQ,UAAU;IACV,gBAA0B;E3C07NhC;E2C9iOF;I1C8II,sB0CxBuD;E3C27NzD;E2CjjOF;IAmHQ,UAAU;IACV,UAA0B;E3Ci8NhC;E2CrjOF;I1C8II,gB0CxBuD;E3Ck8NzD;E2CxjOF;IAmHQ,UAAU;IACV,gBAA0B;E3Cw8NhC;E2C5jOF;I1C8II,sB0CxBuD;E3Cy8NzD;E2C/jOF;IAmHQ,UAAU;IACV,gBAA0B;E3C+8NhC;E2CnkOF;I1C8II,sB0CxBuD;E3Cg9NzD;E2CtkOF;IAmHQ,UAAU;IACV,UAA0B;E3Cs9NhC;E2C1kOF;I1C8II,gB0CxBuD;E3Cu9NzD;E2C7kOF;IAmHQ,UAAU;IACV,gBAA0B;E3C69NhC;E2CjlOF;I1C8II,sB0CxBuD;E3C89NzD;E2CplOF;IAmHQ,UAAU;IACV,gBAA0B;E3Co+NhC;E2CxlOF;I1C8II,sB0CxBuD;E3Cq+NzD;E2C3lOF;IAmHQ,UAAU;IACV,UAA0B;E3C2+NhC;E2C/lOF;I1C8II,gB0CxBuD;E3C4+NzD;E2ClmOF;IAmHQ,UAAU;IACV,gBAA0B;E3Ck/NhC;E2CtmOF;I1C8II,sB0CxBuD;E3Cm/NzD;E2CzmOF;IAmHQ,UAAU;IACV,gBAA0B;E3Cy/NhC;E2C7mOF;I1C8II,sB0CxBuD;E3C0/NzD;E2ChnOF;IAmHQ,UAAU;IACV,WAA0B;E3CggOhC;E2CpnOF;I1C8II,iB0CxBuD;E3CigOzD;AACF;;ACriOE;E0CnFF;IA0HM,UAAU;E3CmgOd;E2C7nOF;IA6HM,UAAU;IACV,WAAW;E3CmgOf;E2CjoOF;IAiIM,UAAU;IACV,UAAU;E3CmgOd;E2CroOF;IAqIM,UAAU;IACV,eAAe;E3CmgOnB;E2CzoOF;IAyIM,UAAU;IACV,UAAU;E3CmgOd;E2C7oOF;IA6IM,UAAU;IACV,eAAe;E3CmgOnB;E2CjpOF;IAiJM,UAAU;IACV,UAAU;E3CmgOd;E2CrpOF;IAqJM,UAAU;IACV,UAAU;E3CmgOd;E2CzpOF;IAyJM,UAAU;IACV,UAAU;E3CmgOd;E2C7pOF;IA6JM,UAAU;IACV,UAAU;E3CmgOd;E2CjqOF;IAiKM,UAAU;IACV,UAAU;E3CmgOd;E2CrqOF;I1C8II,gB0CuBqC;E3CmgOvC;E2CxqOF;I1C8II,qB0C0B0C;E3CmgO5C;E2C3qOF;I1C8II,gB0C6BqC;E3CmgOvC;E2C9qOF;I1C8II,qB0CgC0C;E3CmgO5C;E2CjrOF;I1C8II,gB0CmCqC;E3CmgOvC;E2CprOF;I1C8II,gB0CsCqC;E3CmgOvC;E2CvrOF;I1C8II,gB0CyCqC;E3CmgOvC;E2C1rOF;I1C8II,gB0C4CqC;E3CmgOvC;E2C7rOF;I1C8II,gB0C+CqC;E3CmgOvC;E2ChsOF;IAiMQ,UAAU;IACV,SAA0B;E3CkgOhC;E2CpsOF;I1C8II,e0CuDuD;E3CkgOzD;E2CvsOF;IAiMQ,UAAU;IACV,eAA0B;E3CygOhC;E2C3sOF;I1C8II,qB0CuDuD;E3CygOzD;E2C9sOF;IAiMQ,UAAU;IACV,gBAA0B;E3CghOhC;E2CltOF;I1C8II,sB0CuDuD;E3CghOzD;E2CrtOF;IAiMQ,UAAU;IACV,UAA0B;E3CuhOhC;E2CztOF;I1C8II,gB0CuDuD;E3CuhOzD;E2C5tOF;IAiMQ,UAAU;IACV,gBAA0B;E3C8hOhC;E2ChuOF;I1C8II,sB0CuDuD;E3C8hOzD;E2CnuOF;IAiMQ,UAAU;IACV,gBAA0B;E3CqiOhC;E2CvuOF;I1C8II,sB0CuDuD;E3CqiOzD;E2C1uOF;IAiMQ,UAAU;IACV,UAA0B;E3C4iOhC;E2C9uOF;I1C8II,gB0CuDuD;E3C4iOzD;E2CjvOF;IAiMQ,UAAU;IACV,gBAA0B;E3CmjOhC;E2CrvOF;I1C8II,sB0CuDuD;E3CmjOzD;E2CxvOF;IAiMQ,UAAU;IACV,gBAA0B;E3C0jOhC;E2C5vOF;I1C8II,sB0CuDuD;E3C0jOzD;E2C/vOF;IAiMQ,UAAU;IACV,UAA0B;E3CikOhC;E2CnwOF;I1C8II,gB0CuDuD;E3CikOzD;E2CtwOF;IAiMQ,UAAU;IACV,gBAA0B;E3CwkOhC;E2C1wOF;I1C8II,sB0CuDuD;E3CwkOzD;E2C7wOF;IAiMQ,UAAU;IACV,gBAA0B;E3C+kOhC;E2CjxOF;I1C8II,sB0CuDuD;E3C+kOzD;E2CpxOF;IAiMQ,UAAU;IACV,WAA0B;E3CslOhC;E2CxxOF;I1C8II,iB0CuDuD;E3CslOzD;AACF;;ACjsOE;E0C3FF;IAwMM,UAAU;E3CylOd;E2CjyOF;IA0MM,UAAU;IACV,WAAW;E3C0lOf;E2CryOF;IA6MM,UAAU;IACV,UAAU;E3C2lOd;E2CzyOF;IAgNM,UAAU;IACV,eAAe;E3C4lOnB;E2C7yOF;IAmNM,UAAU;IACV,UAAU;E3C6lOd;E2CjzOF;IAsNM,UAAU;IACV,eAAe;E3C8lOnB;E2CrzOF;IAyNM,UAAU;IACV,UAAU;E3C+lOd;E2CzzOF;IA4NM,UAAU;IACV,UAAU;E3CgmOd;E2C7zOF;IA+NM,UAAU;IACV,UAAU;E3CimOd;E2Cj0OF;IAkOM,UAAU;IACV,UAAU;E3CkmOd;E2Cr0OF;IAqOM,UAAU;IACV,UAAU;E3CmmOd;E2Cz0OF;I1C8II,gB0C0FqC;E3ComOvC;E2C50OF;I1C8II,qB0C4F0C;E3CqmO5C;E2C/0OF;I1C8II,gB0C8FqC;E3CsmOvC;E2Cl1OF;I1C8II,qB0CgG0C;E3CumO5C;E2Cr1OF;I1C8II,gB0CkGqC;E3CwmOvC;E2Cx1OF;I1C8II,gB0CoGqC;E3CymOvC;E2C31OF;I1C8II,gB0CsGqC;E3C0mOvC;E2C91OF;I1C8II,gB0CwGqC;E3C2mOvC;E2Cj2OF;I1C8II,gB0C0GqC;E3C4mOvC;E2Cp2OF;IA2PQ,UAAU;IACV,SAA0B;E3C4mOhC;E2Cx2OF;I1C8II,e0CgHuD;E3C6mOzD;E2C32OF;IA2PQ,UAAU;IACV,eAA0B;E3CmnOhC;E2C/2OF;I1C8II,qB0CgHuD;E3ConOzD;E2Cl3OF;IA2PQ,UAAU;IACV,gBAA0B;E3C0nOhC;E2Ct3OF;I1C8II,sB0CgHuD;E3C2nOzD;E2Cz3OF;IA2PQ,UAAU;IACV,UAA0B;E3CioOhC;E2C73OF;I1C8II,gB0CgHuD;E3CkoOzD;E2Ch4OF;IA2PQ,UAAU;IACV,gBAA0B;E3CwoOhC;E2Cp4OF;I1C8II,sB0CgHuD;E3CyoOzD;E2Cv4OF;IA2PQ,UAAU;IACV,gBAA0B;E3C+oOhC;E2C34OF;I1C8II,sB0CgHuD;E3CgpOzD;E2C94OF;IA2PQ,UAAU;IACV,UAA0B;E3CspOhC;E2Cl5OF;I1C8II,gB0CgHuD;E3CupOzD;E2Cr5OF;IA2PQ,UAAU;IACV,gBAA0B;E3C6pOhC;E2Cz5OF;I1C8II,sB0CgHuD;E3C8pOzD;E2C55OF;IA2PQ,UAAU;IACV,gBAA0B;E3CoqOhC;E2Ch6OF;I1C8II,sB0CgHuD;E3CqqOzD;E2Cn6OF;IA2PQ,UAAU;IACV,UAA0B;E3C2qOhC;E2Cv6OF;I1C8II,gB0CgHuD;E3C4qOzD;E2C16OF;IA2PQ,UAAU;IACV,gBAA0B;E3CkrOhC;E2C96OF;I1C8II,sB0CgHuD;E3CmrOzD;E2Cj7OF;IA2PQ,UAAU;IACV,gBAA0B;E3CyrOhC;E2Cr7OF;I1C8II,sB0CgHuD;E3C0rOzD;E2Cx7OF;IA2PQ,UAAU;IACV,WAA0B;E3CgsOhC;E2C57OF;I1C8II,iB0CgHuD;E3CisOzD;AACF;;ACj2OE;E0C/FF;IAiQM,UAAU;E3CosOd;E2Cr8OF;IAmQM,UAAU;IACV,WAAW;E3CqsOf;E2Cz8OF;IAsQM,UAAU;IACV,UAAU;E3CssOd;E2C78OF;IAyQM,UAAU;IACV,eAAe;E3CusOnB;E2Cj9OF;IA4QM,UAAU;IACV,UAAU;E3CwsOd;E2Cr9OF;IA+QM,UAAU;IACV,eAAe;E3CysOnB;E2Cz9OF;IAkRM,UAAU;IACV,UAAU;E3C0sOd;E2C79OF;IAqRM,UAAU;IACV,UAAU;E3C2sOd;E2Cj+OF;IAwRM,UAAU;IACV,UAAU;E3C4sOd;E2Cr+OF;IA2RM,UAAU;IACV,UAAU;E3C6sOd;E2Cz+OF;IA8RM,UAAU;IACV,UAAU;E3C8sOd;E2C7+OF;I1C8II,gB0CmJqC;E3C+sOvC;E2Ch/OF;I1C8II,qB0CqJ0C;E3CgtO5C;E2Cn/OF;I1C8II,gB0CuJqC;E3CitOvC;E2Ct/OF;I1C8II,qB0CyJ0C;E3CktO5C;E2Cz/OF;I1C8II,gB0C2JqC;E3CmtOvC;E2C5/OF;I1C8II,gB0C6JqC;E3CotOvC;E2C//OF;I1C8II,gB0C+JqC;E3CqtOvC;E2ClgPF;I1C8II,gB0CiKqC;E3CstOvC;E2CrgPF;I1C8II,gB0CmKqC;E3CutOvC;E2CxgPF;IAoTQ,UAAU;IACV,SAA0B;E3CutOhC;E2C5gPF;I1C8II,e0CyKuD;E3CwtOzD;E2C/gPF;IAoTQ,UAAU;IACV,eAA0B;E3C8tOhC;E2CnhPF;I1C8II,qB0CyKuD;E3C+tOzD;E2CthPF;IAoTQ,UAAU;IACV,gBAA0B;E3CquOhC;E2C1hPF;I1C8II,sB0CyKuD;E3CsuOzD;E2C7hPF;IAoTQ,UAAU;IACV,UAA0B;E3C4uOhC;E2CjiPF;I1C8II,gB0CyKuD;E3C6uOzD;E2CpiPF;IAoTQ,UAAU;IACV,gBAA0B;E3CmvOhC;E2CxiPF;I1C8II,sB0CyKuD;E3CovOzD;E2C3iPF;IAoTQ,UAAU;IACV,gBAA0B;E3C0vOhC;E2C/iPF;I1C8II,sB0CyKuD;E3C2vOzD;E2CljPF;IAoTQ,UAAU;IACV,UAA0B;E3CiwOhC;E2CtjPF;I1C8II,gB0CyKuD;E3CkwOzD;E2CzjPF;IAoTQ,UAAU;IACV,gBAA0B;E3CwwOhC;E2C7jPF;I1C8II,sB0CyKuD;E3CywOzD;E2ChkPF;IAoTQ,UAAU;IACV,gBAA0B;E3C+wOhC;E2CpkPF;I1C8II,sB0CyKuD;E3CgxOzD;E2CvkPF;IAoTQ,UAAU;IACV,UAA0B;E3CsxOhC;E2C3kPF;I1C8II,gB0CyKuD;E3CuxOzD;E2C9kPF;IAoTQ,UAAU;IACV,gBAA0B;E3C6xOhC;E2CllPF;I1C8II,sB0CyKuD;E3C8xOzD;E2CrlPF;IAoTQ,UAAU;IACV,gBAA0B;E3CoyOhC;E2CzlPF;I1C8II,sB0CyKuD;E3CqyOzD;E2C5lPF;IAoTQ,UAAU;IACV,WAA0B;E3C2yOhC;E2ChmPF;I1C8II,iB0CyKuD;E3C4yOzD;AACF;;ACt/OI;E0C9GJ;IA0TM,UAAU;E3C+yOd;E2CzmPF;IA4TM,UAAU;IACV,WAAW;E3CgzOf;E2C7mPF;IA+TM,UAAU;IACV,UAAU;E3CizOd;E2CjnPF;IAkUM,UAAU;IACV,eAAe;E3CkzOnB;E2CrnPF;IAqUM,UAAU;IACV,UAAU;E3CmzOd;E2CznPF;IAwUM,UAAU;IACV,eAAe;E3CozOnB;E2C7nPF;IA2UM,UAAU;IACV,UAAU;E3CqzOd;E2CjoPF;IA8UM,UAAU;IACV,UAAU;E3CszOd;E2CroPF;IAiVM,UAAU;IACV,UAAU;E3CuzOd;E2CzoPF;IAoVM,UAAU;IACV,UAAU;E3CwzOd;E2C7oPF;IAuVM,UAAU;IACV,UAAU;E3CyzOd;E2CjpPF;I1C8II,gB0C4MqC;E3C0zOvC;E2CppPF;I1C8II,qB0C8M0C;E3C2zO5C;E2CvpPF;I1C8II,gB0CgNqC;E3C4zOvC;E2C1pPF;I1C8II,qB0CkN0C;E3C6zO5C;E2C7pPF;I1C8II,gB0CoNqC;E3C8zOvC;E2ChqPF;I1C8II,gB0CsNqC;E3C+zOvC;E2CnqPF;I1C8II,gB0CwNqC;E3Cg0OvC;E2CtqPF;I1C8II,gB0C0NqC;E3Ci0OvC;E2CzqPF;I1C8II,gB0C4NqC;E3Ck0OvC;E2C5qPF;IA6WQ,UAAU;IACV,SAA0B;E3Ck0OhC;E2ChrPF;I1C8II,e0CkOuD;E3Cm0OzD;E2CnrPF;IA6WQ,UAAU;IACV,eAA0B;E3Cy0OhC;E2CvrPF;I1C8II,qB0CkOuD;E3C00OzD;E2C1rPF;IA6WQ,UAAU;IACV,gBAA0B;E3Cg1OhC;E2C9rPF;I1C8II,sB0CkOuD;E3Ci1OzD;E2CjsPF;IA6WQ,UAAU;IACV,UAA0B;E3Cu1OhC;E2CrsPF;I1C8II,gB0CkOuD;E3Cw1OzD;E2CxsPF;IA6WQ,UAAU;IACV,gBAA0B;E3C81OhC;E2C5sPF;I1C8II,sB0CkOuD;E3C+1OzD;E2C/sPF;IA6WQ,UAAU;IACV,gBAA0B;E3Cq2OhC;E2CntPF;I1C8II,sB0CkOuD;E3Cs2OzD;E2CttPF;IA6WQ,UAAU;IACV,UAA0B;E3C42OhC;E2C1tPF;I1C8II,gB0CkOuD;E3C62OzD;E2C7tPF;IA6WQ,UAAU;IACV,gBAA0B;E3Cm3OhC;E2CjuPF;I1C8II,sB0CkOuD;E3Co3OzD;E2CpuPF;IA6WQ,UAAU;IACV,gBAA0B;E3C03OhC;E2CxuPF;I1C8II,sB0CkOuD;E3C23OzD;E2C3uPF;IA6WQ,UAAU;IACV,UAA0B;E3Ci4OhC;E2C/uPF;I1C8II,gB0CkOuD;E3Ck4OzD;E2ClvPF;IA6WQ,UAAU;IACV,gBAA0B;E3Cw4OhC;E2CtvPF;I1C8II,sB0CkOuD;E3Cy4OzD;E2CzvPF;IA6WQ,UAAU;IACV,gBAA0B;E3C+4OhC;E2C7vPF;I1C8II,sB0CkOuD;E3Cg5OzD;E2ChwPF;IA6WQ,UAAU;IACV,WAA0B;E3Cs5OhC;E2CpwPF;I1C8II,iB0CkOuD;E3Cu5OzD;AACF;;AC3oPI;E0C7HJ;IAmXM,UAAU;E3C05Od;E2C7wPF;IAqXM,UAAU;IACV,WAAW;E3C25Of;E2CjxPF;IAwXM,UAAU;IACV,UAAU;E3C45Od;E2CrxPF;IA2XM,UAAU;IACV,eAAe;E3C65OnB;E2CzxPF;IA8XM,UAAU;IACV,UAAU;E3C85Od;E2C7xPF;IAiYM,UAAU;IACV,eAAe;E3C+5OnB;E2CjyPF;IAoYM,UAAU;IACV,UAAU;E3Cg6Od;E2CryPF;IAuYM,UAAU;IACV,UAAU;E3Ci6Od;E2CzyPF;IA0YM,UAAU;IACV,UAAU;E3Ck6Od;E2C7yPF;IA6YM,UAAU;IACV,UAAU;E3Cm6Od;E2CjzPF;IAgZM,UAAU;IACV,UAAU;E3Co6Od;E2CrzPF;I1C8II,gB0CqQqC;E3Cq6OvC;E2CxzPF;I1C8II,qB0CuQ0C;E3Cs6O5C;E2C3zPF;I1C8II,gB0CyQqC;E3Cu6OvC;E2C9zPF;I1C8II,qB0C2Q0C;E3Cw6O5C;E2Cj0PF;I1C8II,gB0C6QqC;E3Cy6OvC;E2Cp0PF;I1C8II,gB0C+QqC;E3C06OvC;E2Cv0PF;I1C8II,gB0CiRqC;E3C26OvC;E2C10PF;I1C8II,gB0CmRqC;E3C46OvC;E2C70PF;I1C8II,gB0CqRqC;E3C66OvC;E2Ch1PF;IAsaQ,UAAU;IACV,SAA0B;E3C66OhC;E2Cp1PF;I1C8II,e0C2RuD;E3C86OzD;E2Cv1PF;IAsaQ,UAAU;IACV,eAA0B;E3Co7OhC;E2C31PF;I1C8II,qB0C2RuD;E3Cq7OzD;E2C91PF;IAsaQ,UAAU;IACV,gBAA0B;E3C27OhC;E2Cl2PF;I1C8II,sB0C2RuD;E3C47OzD;E2Cr2PF;IAsaQ,UAAU;IACV,UAA0B;E3Ck8OhC;E2Cz2PF;I1C8II,gB0C2RuD;E3Cm8OzD;E2C52PF;IAsaQ,UAAU;IACV,gBAA0B;E3Cy8OhC;E2Ch3PF;I1C8II,sB0C2RuD;E3C08OzD;E2Cn3PF;IAsaQ,UAAU;IACV,gBAA0B;E3Cg9OhC;E2Cv3PF;I1C8II,sB0C2RuD;E3Ci9OzD;E2C13PF;IAsaQ,UAAU;IACV,UAA0B;E3Cu9OhC;E2C93PF;I1C8II,gB0C2RuD;E3Cw9OzD;E2Cj4PF;IAsaQ,UAAU;IACV,gBAA0B;E3C89OhC;E2Cr4PF;I1C8II,sB0C2RuD;E3C+9OzD;E2Cx4PF;IAsaQ,UAAU;IACV,gBAA0B;E3Cq+OhC;E2C54PF;I1C8II,sB0C2RuD;E3Cs+OzD;E2C/4PF;IAsaQ,UAAU;IACV,UAA0B;E3C4+OhC;E2Cn5PF;I1C8II,gB0C2RuD;E3C6+OzD;E2Ct5PF;IAsaQ,UAAU;IACV,gBAA0B;E3Cm/OhC;E2C15PF;I1C8II,sB0C2RuD;E3Co/OzD;E2C75PF;IAsaQ,UAAU;IACV,gBAA0B;E3C0/OhC;E2Cj6PF;I1C8II,sB0C2RuD;E3C2/OzD;E2Cp6PF;IAsaQ,UAAU;IACV,WAA0B;E3CigPhC;E2Cx6PF;I1C8II,iB0C2RuD;E3CkgPzD;AACF;;A2CjgPA;E1C7RI,qB0ChJgB;E1CgJhB,sB0ChJgB;EAgblB,oBAhbkB;A3Co7PpB;;A2CvgPA;EAKI,uBAlbgB;A3Cw7PpB;;A2C3gPA;EAOI,qCAA4C;A3CwgPhD;;A2C/gPA;EAUI,uBAAuB;A3CygP3B;;A2CnhPA;E1C7RI,c0CySiC;E1CzSjC,e0C0SiC;EACjC,aAAa;A3C2gPjB;;A2CzhPA;EAgBM,SAAS;EACT,qBAAqB;A3C6gP3B;;A2C9hPA;EAmBM,qBAAqB;A3C+gP3B;;A2CliPA;EAqBM,gBAAgB;A3CihPtB;;A2CtiPA;EAuBI,aAAa;A3CmhPjB;;A2C1iPA;EAyBI,eAAe;A3CqhPnB;;A2C9iPA;EA2BI,mBAAmB;A3CuhPvB;;AC14PE;E0CwVF;IA+BM,aAAa;E3CwhPjB;AACF;;ACp4PE;E0C4UF;IAmCM,aAAa;E3C0hPjB;AACF;;A2CxhPE;EACE,oBAAY;E1CpUZ,wC0CqU2D;E1CrU3D,yC0CsU2D;A3C2hP/D;;A2C9hPE;EAKI,8BAA8B;EAC9B,+BAA+B;A3C6hPrC;;A2CniPE;EASM,iBAAY;A3C8hPpB;;ACz6PE;E0CkYA;IAYQ,iBAAY;E3CgiPpB;AACF;;AC36PE;E0C8XA;IAeQ,iBAAY;E3CmiPpB;AACF;;AC76PE;E0C0XA;IAkBQ,iBAAY;E3CsiPpB;AACF;;AC/6PE;E0CsXA;IAqBQ,iBAAY;E3CyiPpB;AACF;;ACj7PE;E0CkXA;IAwBQ,iBAAY;E3C4iPpB;AACF;;ACl7PI;E0C6WF;IA2BQ,iBAAY;E3C+iPpB;AACF;;AC96PI;E0CmWF;IA8BQ,iBAAY;E3CkjPpB;AACF;;AC/6PI;E0C8VF;IAiCQ,iBAAY;E3CqjPpB;AACF;;AC36PI;E0CoVF;IAoCQ,iBAAY;E3CwjPpB;AACF;;A2C7lPE;EASM,oBAAY;A3CwlPpB;;ACn+PE;E0CkYA;IAYQ,oBAAY;E3C0lPpB;AACF;;ACr+PE;E0C8XA;IAeQ,oBAAY;E3C6lPpB;AACF;;ACv+PE;E0C0XA;IAkBQ,oBAAY;E3CgmPpB;AACF;;ACz+PE;E0CsXA;IAqBQ,oBAAY;E3CmmPpB;AACF;;AC3+PE;E0CkXA;IAwBQ,oBAAY;E3CsmPpB;AACF;;AC5+PI;E0C6WF;IA2BQ,oBAAY;E3CymPpB;AACF;;ACx+PI;E0CmWF;IA8BQ,oBAAY;E3C4mPpB;AACF;;ACz+PI;E0C8VF;IAiCQ,oBAAY;E3C+mPpB;AACF;;ACr+PI;E0CoVF;IAoCQ,oBAAY;E3CknPpB;AACF;;A2CvpPE;EASM,mBAAY;A3CkpPpB;;AC7hQE;E0CkYA;IAYQ,mBAAY;E3CopPpB;AACF;;AC/hQE;E0C8XA;IAeQ,mBAAY;E3CupPpB;AACF;;ACjiQE;E0C0XA;IAkBQ,mBAAY;E3C0pPpB;AACF;;ACniQE;E0CsXA;IAqBQ,mBAAY;E3C6pPpB;AACF;;ACriQE;E0CkXA;IAwBQ,mBAAY;E3CgqPpB;AACF;;ACtiQI;E0C6WF;IA2BQ,mBAAY;E3CmqPpB;AACF;;ACliQI;E0CmWF;IA8BQ,mBAAY;E3CsqPpB;AACF;;ACniQI;E0C8VF;IAiCQ,mBAAY;E3CyqPpB;AACF;;AC/hQI;E0CoVF;IAoCQ,mBAAY;E3C4qPpB;AACF;;A2CjtPE;EASM,oBAAY;A3C4sPpB;;ACvlQE;E0CkYA;IAYQ,oBAAY;E3C8sPpB;AACF;;ACzlQE;E0C8XA;IAeQ,oBAAY;E3CitPpB;AACF;;AC3lQE;E0C0XA;IAkBQ,oBAAY;E3CotPpB;AACF;;AC7lQE;E0CsXA;IAqBQ,oBAAY;E3CutPpB;AACF;;AC/lQE;E0CkXA;IAwBQ,oBAAY;E3C0tPpB;AACF;;AChmQI;E0C6WF;IA2BQ,oBAAY;E3C6tPpB;AACF;;AC5lQI;E0CmWF;IA8BQ,oBAAY;E3CguPpB;AACF;;AC7lQI;E0C8VF;IAiCQ,oBAAY;E3CmuPpB;AACF;;ACzlQI;E0CoVF;IAoCQ,oBAAY;E3CsuPpB;AACF;;A2C3wPE;EASM,iBAAY;A3CswPpB;;ACjpQE;E0CkYA;IAYQ,iBAAY;E3CwwPpB;AACF;;ACnpQE;E0C8XA;IAeQ,iBAAY;E3C2wPpB;AACF;;ACrpQE;E0C0XA;IAkBQ,iBAAY;E3C8wPpB;AACF;;ACvpQE;E0CsXA;IAqBQ,iBAAY;E3CixPpB;AACF;;ACzpQE;E0CkXA;IAwBQ,iBAAY;E3CoxPpB;AACF;;AC1pQI;E0C6WF;IA2BQ,iBAAY;E3CuxPpB;AACF;;ACtpQI;E0CmWF;IA8BQ,iBAAY;E3C0xPpB;AACF;;ACvpQI;E0C8VF;IAiCQ,iBAAY;E3C6xPpB;AACF;;ACnpQI;E0CoVF;IAoCQ,iBAAY;E3CgyPpB;AACF;;A2Cr0PE;EASM,oBAAY;A3Cg0PpB;;AC3sQE;E0CkYA;IAYQ,oBAAY;E3Ck0PpB;AACF;;AC7sQE;E0C8XA;IAeQ,oBAAY;E3Cq0PpB;AACF;;AC/sQE;E0C0XA;IAkBQ,oBAAY;E3Cw0PpB;AACF;;ACjtQE;E0CsXA;IAqBQ,oBAAY;E3C20PpB;AACF;;ACntQE;E0CkXA;IAwBQ,oBAAY;E3C80PpB;AACF;;ACptQI;E0C6WF;IA2BQ,oBAAY;E3Ci1PpB;AACF;;AChtQI;E0CmWF;IA8BQ,oBAAY;E3Co1PpB;AACF;;ACjtQI;E0C8VF;IAiCQ,oBAAY;E3Cu1PpB;AACF;;AC7sQI;E0CoVF;IAoCQ,oBAAY;E3C01PpB;AACF;;A2C/3PE;EASM,mBAAY;A3C03PpB;;ACrwQE;E0CkYA;IAYQ,mBAAY;E3C43PpB;AACF;;ACvwQE;E0C8XA;IAeQ,mBAAY;E3C+3PpB;AACF;;ACzwQE;E0C0XA;IAkBQ,mBAAY;E3Ck4PpB;AACF;;AC3wQE;E0CsXA;IAqBQ,mBAAY;E3Cq4PpB;AACF;;AC7wQE;E0CkXA;IAwBQ,mBAAY;E3Cw4PpB;AACF;;AC9wQI;E0C6WF;IA2BQ,mBAAY;E3C24PpB;AACF;;AC1wQI;E0CmWF;IA8BQ,mBAAY;E3C84PpB;AACF;;AC3wQI;E0C8VF;IAiCQ,mBAAY;E3Ci5PpB;AACF;;ACvwQI;E0CoVF;IAoCQ,mBAAY;E3Co5PpB;AACF;;A2Cz7PE;EASM,oBAAY;A3Co7PpB;;AC/zQE;E0CkYA;IAYQ,oBAAY;E3Cs7PpB;AACF;;ACj0QE;E0C8XA;IAeQ,oBAAY;E3Cy7PpB;AACF;;ACn0QE;E0C0XA;IAkBQ,oBAAY;E3C47PpB;AACF;;ACr0QE;E0CsXA;IAqBQ,oBAAY;E3C+7PpB;AACF;;ACv0QE;E0CkXA;IAwBQ,oBAAY;E3Ck8PpB;AACF;;ACx0QI;E0C6WF;IA2BQ,oBAAY;E3Cq8PpB;AACF;;ACp0QI;E0CmWF;IA8BQ,oBAAY;E3Cw8PpB;AACF;;ACr0QI;E0C8VF;IAiCQ,oBAAY;E3C28PpB;AACF;;ACj0QI;E0CoVF;IAoCQ,oBAAY;E3C88PpB;AACF;;A2Cn/PE;EASM,iBAAY;A3C8+PpB;;ACz3QE;E0CkYA;IAYQ,iBAAY;E3Cg/PpB;AACF;;AC33QE;E0C8XA;IAeQ,iBAAY;E3Cm/PpB;AACF;;AC73QE;E0C0XA;IAkBQ,iBAAY;E3Cs/PpB;AACF;;AC/3QE;E0CsXA;IAqBQ,iBAAY;E3Cy/PpB;AACF;;ACj4QE;E0CkXA;IAwBQ,iBAAY;E3C4/PpB;AACF;;ACl4QI;E0C6WF;IA2BQ,iBAAY;E3C+/PpB;AACF;;AC93QI;E0CmWF;IA8BQ,iBAAY;E3CkgQpB;AACF;;AC/3QI;E0C8VF;IAiCQ,iBAAY;E3CqgQpB;AACF;;AC33QI;E0CoVF;IAoCQ,iBAAY;E3CwgQpB;AACF;;A4C9/QA;EACE,oBAAoB;EACpB,cAAc;EACd,aAAa;EACb,YAAY;EACZ,cAAc;EACd,+BAAuB;EAAvB,4BAAuB;EAAvB,uBAAuB;A5CigRzB;;A4CvgRA;EASI,qBAA+B;EAC/B,sBAAgC;EAChC,oBAA8B;A5CkgRlC;;A4C7gRA;EAaM,uBAAiC;A5CogRvC;;A4CjhRA;EAeM,sBAjBgB;A5CuhRtB;;A4CrhRA;EAiBI,oBAAoB;A5CwgRxB;;A4CzhRA;EAmBI,gBArBkB;A5C+hRtB;;A4C7hRA;EAqBI,sBAAsB;A5C4gR1B;;A4CjiRA;EAuBM,gCAAgC;A5C8gRtC;;ACl9QE;E2CnFF;IA2BM,aAAa;E5C+gRjB;E4C1iRF;IA8BQ,UAAU;IACV,eAAuB;E5C+gR7B;E4C9iRF;IA8BQ,UAAU;IACV,gBAAuB;E5CmhR7B;E4CljRF;IA8BQ,UAAU;IACV,UAAuB;E5CuhR7B;E4CtjRF;IA8BQ,UAAU;IACV,gBAAuB;E5C2hR7B;E4C1jRF;IA8BQ,UAAU;IACV,gBAAuB;E5C+hR7B;E4C9jRF;IA8BQ,UAAU;IACV,UAAuB;E5CmiR7B;E4ClkRF;IA8BQ,UAAU;IACV,gBAAuB;E5CuiR7B;E4CtkRF;IA8BQ,UAAU;IACV,gBAAuB;E5C2iR7B;E4C1kRF;IA8BQ,UAAU;IACV,UAAuB;E5C+iR7B;E4C9kRF;IA8BQ,UAAU;IACV,gBAAuB;E5CmjR7B;E4CllRF;IA8BQ,UAAU;IACV,gBAAuB;E5CujR7B;E4CtlRF;IA8BQ,UAAU;IACV,WAAuB;E5C2jR7B;AACF;;A6C7lRA,kBAAA;ACEE;EACE,uBAAwB;A9C+lR5B;;A8C9lRE;EAGI,yBAA0C;A9C+lRhD;;A8C9lRE;EACE,kCAAmC;A9CimRvC;;A8CxmRE;EACE,yBAAwB;A9C2mR5B;;A8C1mRE;EAGI,uBAA0C;A9C2mRhD;;A8C1mRE;EACE,oCAAmC;A9C6mRvC;;A8CpnRE;EACE,4BAAwB;A9CunR5B;;A8CtnRE;EAGI,yBAA0C;A9CunRhD;;A8CtnRE;EACE,uCAAmC;A9CynRvC;;A8ChoRE;EACE,yBAAwB;A9CmoR5B;;A8CloRE;EAGI,yBAA0C;A9CmoRhD;;A8CloRE;EACE,oCAAmC;A9CqoRvC;;A8C5oRE;EACE,yBAAwB;A9C+oR5B;;A8C9oRE;EAGI,yBAA0C;A9C+oRhD;;A8C9oRE;EACE,oCAAmC;A9CipRvC;;A8C5oRI;EACE,yBAA8B;A9C+oRpC;;A8C9oRI;EAGI,yBAAgD;A9C+oRxD;;A8C9oRI;EACE,oCAAyC;A9CipR/C;;A8C/oRI;EACE,yBAA6B;A9CkpRnC;;A8CjpRI;EAGI,yBAAgD;A9CkpRxD;;A8CjpRI;EACE,oCAAwC;A9CopR9C;;A8ChrRE;EACE,yBAAwB;A9CmrR5B;;A8ClrRE;EAGI,yBAA0C;A9CmrRhD;;A8ClrRE;EACE,oCAAmC;A9CqrRvC;;A8ChrRI;EACE,yBAA8B;A9CmrRpC;;A8ClrRI;EAGI,yBAAgD;A9CmrRxD;;A8ClrRI;EACE,oCAAyC;A9CqrR/C;;A8CnrRI;EACE,yBAA6B;A9CsrRnC;;A8CrrRI;EAGI,yBAAgD;A9CsrRxD;;A8CrrRI;EACE,oCAAwC;A9CwrR9C;;A8CptRE;EACE,yBAAwB;A9CutR5B;;A8CttRE;EAGI,yBAA0C;A9CutRhD;;A8CttRE;EACE,oCAAmC;A9CytRvC;;A8CptRI;EACE,yBAA8B;A9CutRpC;;A8CttRI;EAGI,yBAAgD;A9CutRxD;;A8CttRI;EACE,oCAAyC;A9CytR/C;;A8CvtRI;EACE,yBAA6B;A9C0tRnC;;A8CztRI;EAGI,yBAAgD;A9C0tRxD;;A8CztRI;EACE,oCAAwC;A9C4tR9C;;A8CxvRE;EACE,yBAAwB;A9C2vR5B;;A8C1vRE;EAGI,yBAA0C;A9C2vRhD;;A8C1vRE;EACE,oCAAmC;A9C6vRvC;;A8CxvRI;EACE,yBAA8B;A9C2vRpC;;A8C1vRI;EAGI,yBAAgD;A9C2vRxD;;A8C1vRI;EACE,oCAAyC;A9C6vR/C;;A8C3vRI;EACE,yBAA6B;A9C8vRnC;;A8C7vRI;EAGI,yBAAgD;A9C8vRxD;;A8C7vRI;EACE,oCAAwC;A9CgwR9C;;A8C5xRE;EACE,yBAAwB;A9C+xR5B;;A8C9xRE;EAGI,yBAA0C;A9C+xRhD;;A8C9xRE;EACE,oCAAmC;A9CiyRvC;;A8C5xRI;EACE,yBAA8B;A9C+xRpC;;A8C9xRI;EAGI,yBAAgD;A9C+xRxD;;A8C9xRI;EACE,oCAAyC;A9CiyR/C;;A8C/xRI;EACE,yBAA6B;A9CkyRnC;;A8CjyRI;EAGI,yBAAgD;A9CkyRxD;;A8CjyRI;EACE,oCAAwC;A9CoyR9C;;A8Ch0RE;EACE,yBAAwB;A9Cm0R5B;;A8Cl0RE;EAGI,yBAA0C;A9Cm0RhD;;A8Cl0RE;EACE,oCAAmC;A9Cq0RvC;;A8Ch0RI;EACE,yBAA8B;A9Cm0RpC;;A8Cl0RI;EAGI,yBAAgD;A9Cm0RxD;;A8Cl0RI;EACE,oCAAyC;A9Cq0R/C;;A8Cn0RI;EACE,yBAA6B;A9Cs0RnC;;A8Cr0RI;EAGI,yBAAgD;A9Cs0RxD;;A8Cr0RI;EACE,oCAAwC;A9Cw0R9C;;A8Cr0RE;EACE,yBAAwB;A9Cw0R5B;;A8Cv0RE;EACE,oCAAmC;A9C00RvC;;A8C70RE;EACE,yBAAwB;A9Cg1R5B;;A8C/0RE;EACE,oCAAmC;A9Ck1RvC;;A8Cr1RE;EACE,yBAAwB;A9Cw1R5B;;A8Cv1RE;EACE,oCAAmC;A9C01RvC;;A8C71RE;EACE,yBAAwB;A9Cg2R5B;;A8C/1RE;EACE,oCAAmC;A9Ck2RvC;;A8Cr2RE;EACE,yBAAwB;A9Cw2R5B;;A8Cv2RE;EACE,oCAAmC;A9C02RvC;;A8C72RE;EACE,yBAAwB;A9Cg3R5B;;A8C/2RE;EACE,oCAAmC;A9Ck3RvC;;A8Cr3RE;EACE,yBAAwB;A9Cw3R5B;;A8Cv3RE;EACE,oCAAmC;A9C03RvC;;A8C73RE;EACE,4BAAwB;A9Cg4R5B;;A8C/3RE;EACE,uCAAmC;A9Ck4RvC;;A8Cr4RE;EACE,yBAAwB;A9Cw4R5B;;A8Cv4RE;EACE,oCAAmC;A9C04RvC;;A+C56RE;EACE,8BAAiC;A/C+6RrC;;A+Ch7RE;EACE,sCAAiC;A/Cm7RrC;;A+Cp7RE;EACE,iCAAiC;A/Cu7RrC;;A+Cx7RE;EACE,yCAAiC;A/C27RrC;;A+Cv7RE;EACE,4BAA4B;A/C07RhC;;A+C37RE;EACE,0BAA4B;A/C87RhC;;A+C/7RE;EACE,kCAA4B;A/Ck8RhC;;A+C97RE;EACE,sCAAkC;A/Ci8RtC;;A+Cl8RE;EACE,oCAAkC;A/Cq8RtC;;A+Ct8RE;EACE,kCAAkC;A/Cy8RtC;;A+C18RE;EACE,yCAAkC;A/C68RtC;;A+C98RE;EACE,wCAAkC;A/Ci9RtC;;A+Cl9RE;EACE,wCAAkC;A/Cq9RtC;;A+Ct9RE;EACE,iCAAkC;A/Cy9RtC;;A+C19RE;EACE,+BAAkC;A/C69RtC;;A+C99RE;EACE,gCAAkC;A/Ci+RtC;;A+Cl+RE;EACE,iCAAkC;A/Cq+RtC;;A+Cj+RE;EACE,oCAAgC;A/Co+RpC;;A+Cr+RE;EACE,kCAAgC;A/Cw+RpC;;A+Cz+RE;EACE,gCAAgC;A/C4+RpC;;A+C7+RE;EACE,uCAAgC;A/Cg/RpC;;A+Cj/RE;EACE,sCAAgC;A/Co/RpC;;A+Cr/RE;EACE,sCAAgC;A/Cw/RpC;;A+Cz/RE;EACE,iCAAgC;A/C4/RpC;;A+C7/RE;EACE,+BAAgC;A/CggSpC;;A+CjgSE;EACE,6BAAgC;A/CogSpC;;A+CrgSE;EACE,kCAAgC;A/CwgSpC;;A+CpgSE;EACE,+BAA8B;A/CugSlC;;A+CxgSE;EACE,kCAA8B;A/C2gSlC;;A+C5gSE;EACE,gCAA8B;A/C+gSlC;;A+ChhSE;EACE,8BAA8B;A/CmhSlC;;A+CphSE;EACE,gCAA8B;A/CuhSlC;;A+CxhSE;EACE,6BAA8B;A/C2hSlC;;A+C5hSE;EACE,2BAA8B;A/C+hSlC;;A+ChiSE;EACE,kCAA8B;A/CmiSlC;;A+CpiSE;EACE,gCAA8B;A/CuiSlC;;A+CniSE;EACE,2BAA6B;A/CsiSjC;;A+CviSE;EACE,iCAA6B;A/C0iSjC;;A+C3iSE;EACE,+BAA6B;A/C8iSjC;;A+C/iSE;EACE,6BAA6B;A/CkjSjC;;A+CnjSE;EACE,+BAA6B;A/CsjSjC;;A+CvjSE;EACE,8BAA6B;A/C0jSjC;;A+CrjSI;EACE,uBAAqC;A/CwjS3C;;A+CzjSI;EACE,uBAAqC;A/C4jS3C;;A+C7jSI;EACE,uBAAqC;A/CgkS3C;;A+CjkSI;EACE,uBAAqC;A/CokS3C;;A+CrkSI;EACE,uBAAqC;A/CwkS3C;;A+CzkSI;EACE,uBAAqC;A/C4kS3C;;A+C7kSI;EACE,yBAAqC;A/CglS3C;;A+CjlSI;EACE,yBAAqC;A/ColS3C;;A+CrlSI;EACE,yBAAqC;A/CwlS3C;;A+CzlSI;EACE,yBAAqC;A/C4lS3C;;A+C7lSI;EACE,yBAAqC;A/CgmS3C;;A+CjmSI;EACE,yBAAqC;A/ComS3C;;ACnoSE;EACE,WAAW;EACX,YAAY;EACZ,cAAc;ADsoSlB;;AgDzoSA;EACE,sBAAsB;AhD4oSxB;;AgD1oSA;EACE,uBAAuB;AhD6oSzB;;AiDppSA;EACE,2BAA2B;AjDupS7B;;AiDrpSA;EACE,2BAA2B;AjDwpS7B;;AiDtpSA;EACE,0BAA0B;AjDypS5B;;AkDhqSA;EACE,2BAA2B;AlDmqS7B;;AmDjqSA;EACE,6BAA6B;AnDoqS/B;;AoDxqSA;EACE,oBAAoB;ApD2qStB;;AoDzqSA;EACE,qBAAqB;ApD4qSvB;;AoDjqSI;EACE,oBAA+B;ApDoqSrC;;AoDjqSM;EACE,wBAA8C;ApDoqStD;;AoDrqSM;EACE,0BAA8C;ApDwqStD;;AoDzqSM;EACE,2BAA8C;ApD4qStD;;AoD7qSM;EACE,yBAA8C;ApDgrStD;;AoD7qSM;EACE,yBAAyC;EACzC,0BAA2C;ApDgrSnD;;AoD7qSM;EACE,wBAAuC;EACvC,2BAA6C;ApDgrSrD;;AoD/rSI;EACE,0BAA+B;ApDksSrC;;AoD/rSM;EACE,8BAA8C;ApDksStD;;AoDnsSM;EACE,gCAA8C;ApDssStD;;AoDvsSM;EACE,iCAA8C;ApD0sStD;;AoD3sSM;EACE,+BAA8C;ApD8sStD;;AoD3sSM;EACE,+BAAyC;EACzC,gCAA2C;ApD8sSnD;;AoD3sSM;EACE,8BAAuC;EACvC,iCAA6C;ApD8sSrD;;AoD7tSI;EACE,yBAA+B;ApDguSrC;;AoD7tSM;EACE,6BAA8C;ApDguStD;;AoDjuSM;EACE,+BAA8C;ApDouStD;;AoDruSM;EACE,gCAA8C;ApDwuStD;;AoDzuSM;EACE,8BAA8C;ApD4uStD;;AoDzuSM;EACE,8BAAyC;EACzC,+BAA2C;ApD4uSnD;;AoDzuSM;EACE,6BAAuC;EACvC,gCAA6C;ApD4uSrD;;AoD3vSI;EACE,0BAA+B;ApD8vSrC;;AoD3vSM;EACE,8BAA8C;ApD8vStD;;AoD/vSM;EACE,gCAA8C;ApDkwStD;;AoDnwSM;EACE,iCAA8C;ApDswStD;;AoDvwSM;EACE,+BAA8C;ApD0wStD;;AoDvwSM;EACE,+BAAyC;EACzC,gCAA2C;ApD0wSnD;;AoDvwSM;EACE,8BAAuC;EACvC,iCAA6C;ApD0wSrD;;AoDzxSI;EACE,uBAA+B;ApD4xSrC;;AoDzxSM;EACE,2BAA8C;ApD4xStD;;AoD7xSM;EACE,6BAA8C;ApDgyStD;;AoDjySM;EACE,8BAA8C;ApDoyStD;;AoDrySM;EACE,4BAA8C;ApDwyStD;;AoDrySM;EACE,4BAAyC;EACzC,6BAA2C;ApDwySnD;;AoDrySM;EACE,2BAAuC;EACvC,8BAA6C;ApDwySrD;;AoDvzSI;EACE,yBAA+B;ApD0zSrC;;AoDvzSM;EACE,6BAA8C;ApD0zStD;;AoD3zSM;EACE,+BAA8C;ApD8zStD;;AoD/zSM;EACE,gCAA8C;ApDk0StD;;AoDn0SM;EACE,8BAA8C;ApDs0StD;;AoDn0SM;EACE,8BAAyC;EACzC,+BAA2C;ApDs0SnD;;AoDn0SM;EACE,6BAAuC;EACvC,gCAA6C;ApDs0SrD;;AoDr1SI;EACE,uBAA+B;ApDw1SrC;;AoDr1SM;EACE,2BAA8C;ApDw1StD;;AoDz1SM;EACE,6BAA8C;ApD41StD;;AoD71SM;EACE,8BAA8C;ApDg2StD;;AoDj2SM;EACE,4BAA8C;ApDo2StD;;AoDj2SM;EACE,4BAAyC;EACzC,6BAA2C;ApDo2SnD;;AoDj2SM;EACE,2BAAuC;EACvC,8BAA6C;ApDo2SrD;;AoDn3SI;EACE,qBAA+B;ApDs3SrC;;AoDn3SM;EACE,yBAA8C;ApDs3StD;;AoDv3SM;EACE,2BAA8C;ApD03StD;;AoD33SM;EACE,4BAA8C;ApD83StD;;AoD/3SM;EACE,0BAA8C;ApDk4StD;;AoD/3SM;EACE,0BAAyC;EACzC,2BAA2C;ApDk4SnD;;AoD/3SM;EACE,yBAAuC;EACvC,4BAA6C;ApDk4SrD;;AoDj5SI;EACE,2BAA+B;ApDo5SrC;;AoDj5SM;EACE,+BAA8C;ApDo5StD;;AoDr5SM;EACE,iCAA8C;ApDw5StD;;AoDz5SM;EACE,kCAA8C;ApD45StD;;AoD75SM;EACE,gCAA8C;ApDg6StD;;AoD75SM;EACE,gCAAyC;EACzC,iCAA2C;ApDg6SnD;;AoD75SM;EACE,+BAAuC;EACvC,kCAA6C;ApDg6SrD;;AoD/6SI;EACE,0BAA+B;ApDk7SrC;;AoD/6SM;EACE,8BAA8C;ApDk7StD;;AoDn7SM;EACE,gCAA8C;ApDs7StD;;AoDv7SM;EACE,iCAA8C;ApD07StD;;AoD37SM;EACE,+BAA8C;ApD87StD;;AoD37SM;EACE,+BAAyC;EACzC,gCAA2C;ApD87SnD;;AoD37SM;EACE,8BAAuC;EACvC,iCAA6C;ApD87SrD;;AoD78SI;EACE,2BAA+B;ApDg9SrC;;AoD78SM;EACE,+BAA8C;ApDg9StD;;AoDj9SM;EACE,iCAA8C;ApDo9StD;;AoDr9SM;EACE,kCAA8C;ApDw9StD;;AoDz9SM;EACE,gCAA8C;ApD49StD;;AoDz9SM;EACE,gCAAyC;EACzC,iCAA2C;ApD49SnD;;AoDz9SM;EACE,+BAAuC;EACvC,kCAA6C;ApD49SrD;;AoD3+SI;EACE,wBAA+B;ApD8+SrC;;AoD3+SM;EACE,4BAA8C;ApD8+StD;;AoD/+SM;EACE,8BAA8C;ApDk/StD;;AoDn/SM;EACE,+BAA8C;ApDs/StD;;AoDv/SM;EACE,6BAA8C;ApD0/StD;;AoDv/SM;EACE,6BAAyC;EACzC,8BAA2C;ApD0/SnD;;AoDv/SM;EACE,4BAAuC;EACvC,+BAA6C;ApD0/SrD;;AoDzgTI;EACE,0BAA+B;ApD4gTrC;;AoDzgTM;EACE,8BAA8C;ApD4gTtD;;AoD7gTM;EACE,gCAA8C;ApDghTtD;;AoDjhTM;EACE,iCAA8C;ApDohTtD;;AoDrhTM;EACE,+BAA8C;ApDwhTtD;;AoDrhTM;EACE,+BAAyC;EACzC,gCAA2C;ApDwhTnD;;AoDrhTM;EACE,8BAAuC;EACvC,iCAA6C;ApDwhTrD;;AoDviTI;EACE,wBAA+B;ApD0iTrC;;AoDviTM;EACE,4BAA8C;ApD0iTtD;;AoD3iTM;EACE,8BAA8C;ApD8iTtD;;AoD/iTM;EACE,+BAA8C;ApDkjTtD;;AoDnjTM;EACE,6BAA8C;ApDsjTtD;;AoDnjTM;EACE,6BAAyC;EACzC,8BAA2C;ApDsjTnD;;AoDnjTM;EACE,4BAAuC;EACvC,+BAA6C;ApDsjTrD;;AqDjlTI;EACE,0BAA2B;ArDolTjC;;AqDrlTI;EACE,4BAA2B;ArDwlTjC;;AqDzlTI;EACE,0BAA2B;ArD4lTjC;;AqD7lTI;EACE,4BAA2B;ArDgmTjC;;AqDjmTI;EACE,6BAA2B;ArDomTjC;;AqDrmTI;EACE,0BAA2B;ArDwmTjC;;AqDzmTI;EACE,6BAA2B;ArD4mTjC;;AC/hTE;EoD9EE;IACE,0BAA2B;ErDinT/B;EqDlnTE;IACE,4BAA2B;ErDonT/B;EqDrnTE;IACE,0BAA2B;ErDunT/B;EqDxnTE;IACE,4BAA2B;ErD0nT/B;EqD3nTE;IACE,6BAA2B;ErD6nT/B;EqD9nTE;IACE,0BAA2B;ErDgoT/B;EqDjoTE;IACE,6BAA2B;ErDmoT/B;AACF;;ACnjTE;EoDlFE;IACE,0BAA2B;ErDyoT/B;EqD1oTE;IACE,4BAA2B;ErD4oT/B;EqD7oTE;IACE,0BAA2B;ErD+oT/B;EqDhpTE;IACE,4BAA2B;ErDkpT/B;EqDnpTE;IACE,6BAA2B;ErDqpT/B;EqDtpTE;IACE,0BAA2B;ErDwpT/B;EqDzpTE;IACE,6BAA2B;ErD2pT/B;AACF;;ACnkTE;EoD1FE;IACE,0BAA2B;ErDiqT/B;EqDlqTE;IACE,4BAA2B;ErDoqT/B;EqDrqTE;IACE,0BAA2B;ErDuqT/B;EqDxqTE;IACE,4BAA2B;ErD0qT/B;EqD3qTE;IACE,6BAA2B;ErD6qT/B;EqD9qTE;IACE,0BAA2B;ErDgrT/B;EqDjrTE;IACE,6BAA2B;ErDmrT/B;AACF;;ACvlTE;EoD9FE;IACE,0BAA2B;ErDyrT/B;EqD1rTE;IACE,4BAA2B;ErD4rT/B;EqD7rTE;IACE,0BAA2B;ErD+rT/B;EqDhsTE;IACE,4BAA2B;ErDksT/B;EqDnsTE;IACE,6BAA2B;ErDqsT/B;EqDtsTE;IACE,0BAA2B;ErDwsT/B;EqDzsTE;IACE,6BAA2B;ErD2sT/B;AACF;;AChmTI;EoD7GA;IACE,0BAA2B;ErDitT/B;EqDltTE;IACE,4BAA2B;ErDotT/B;EqDrtTE;IACE,0BAA2B;ErDutT/B;EqDxtTE;IACE,4BAA2B;ErD0tT/B;EqD3tTE;IACE,6BAA2B;ErD6tT/B;EqD9tTE;IACE,0BAA2B;ErDguT/B;EqDjuTE;IACE,6BAA2B;ErDmuT/B;AACF;;ACzmTI;EoD5HA;IACE,0BAA2B;ErDyuT/B;EqD1uTE;IACE,4BAA2B;ErD4uT/B;EqD7uTE;IACE,0BAA2B;ErD+uT/B;EqDhvTE;IACE,4BAA2B;ErDkvT/B;EqDnvTE;IACE,6BAA2B;ErDqvT/B;EqDtvTE;IACE,0BAA2B;ErDwvT/B;EqDzvTE;IACE,6BAA2B;ErD2vT/B;AACF;;AqDnuTE;EACE,6BAAqC;ArDsuTzC;;AqDvuTE;EACE,8BAAqC;ArD0uTzC;;AqD3uTE;EACE,2BAAqC;ArD8uTzC;;AqD/uTE;EACE,4BAAqC;ArDkvTzC;;AC/rTE;EoD/CE;IACE,6BAAqC;ErDkvTzC;AACF;;ACjsTE;EoDhDE;IACE,6BAAqC;ErDqvTzC;AACF;;ACnsTE;EoDjDE;IACE,6BAAqC;ErDwvTzC;AACF;;ACrsTE;EoDlDE;IACE,6BAAqC;ErD2vTzC;AACF;;ACvsTE;EoDnDE;IACE,6BAAqC;ErD8vTzC;AACF;;ACxsTI;EoDrDA;IACE,6BAAqC;ErDiwTzC;AACF;;ACpsTI;EoD5DA;IACE,6BAAqC;ErDowTzC;AACF;;ACrsTI;EoD9DA;IACE,6BAAqC;ErDuwTzC;AACF;;ACjsTI;EoDrEA;IACE,6BAAqC;ErD0wTzC;AACF;;ACrvTE;EoD/CE;IACE,8BAAqC;ErDwyTzC;AACF;;ACvvTE;EoDhDE;IACE,8BAAqC;ErD2yTzC;AACF;;ACzvTE;EoDjDE;IACE,8BAAqC;ErD8yTzC;AACF;;AC3vTE;EoDlDE;IACE,8BAAqC;ErDizTzC;AACF;;AC7vTE;EoDnDE;IACE,8BAAqC;ErDozTzC;AACF;;AC9vTI;EoDrDA;IACE,8BAAqC;ErDuzTzC;AACF;;AC1vTI;EoD5DA;IACE,8BAAqC;ErD0zTzC;AACF;;AC3vTI;EoD9DA;IACE,8BAAqC;ErD6zTzC;AACF;;ACvvTI;EoDrEA;IACE,8BAAqC;ErDg0TzC;AACF;;AC3yTE;EoD/CE;IACE,2BAAqC;ErD81TzC;AACF;;AC7yTE;EoDhDE;IACE,2BAAqC;ErDi2TzC;AACF;;AC/yTE;EoDjDE;IACE,2BAAqC;ErDo2TzC;AACF;;ACjzTE;EoDlDE;IACE,2BAAqC;ErDu2TzC;AACF;;ACnzTE;EoDnDE;IACE,2BAAqC;ErD02TzC;AACF;;ACpzTI;EoDrDA;IACE,2BAAqC;ErD62TzC;AACF;;AChzTI;EoD5DA;IACE,2BAAqC;ErDg3TzC;AACF;;ACjzTI;EoD9DA;IACE,2BAAqC;ErDm3TzC;AACF;;AC7yTI;EoDrEA;IACE,2BAAqC;ErDs3TzC;AACF;;ACj2TE;EoD/CE;IACE,4BAAqC;ErDo5TzC;AACF;;ACn2TE;EoDhDE;IACE,4BAAqC;ErDu5TzC;AACF;;ACr2TE;EoDjDE;IACE,4BAAqC;ErD05TzC;AACF;;ACv2TE;EoDlDE;IACE,4BAAqC;ErD65TzC;AACF;;ACz2TE;EoDnDE;IACE,4BAAqC;ErDg6TzC;AACF;;AC12TI;EoDrDA;IACE,4BAAqC;ErDm6TzC;AACF;;ACt2TI;EoD5DA;IACE,4BAAqC;ErDs6TzC;AACF;;ACv2TI;EoD9DA;IACE,4BAAqC;ErDy6TzC;AACF;;ACn2TI;EoDrEA;IACE,4BAAqC;ErD46TzC;AACF;;AqD36TA;EACE,qCAAqC;ArD86TvC;;AqD56TA;EACE,oCAAoC;ArD+6TtC;;AqD76TA;EACE,oCAAoC;ArDg7TtC;;AqD96TA;EACE,6BAA6B;ArDi7T/B;;AqD/6TA;EACE,2BAAqC;ArDk7TvC;;AqDj7TA;EACE,2BAAsC;ArDo7TxC;;AqDn7TA;EACE,2BAAsC;ArDs7TxC;;AqDr7TA;EACE,2BAAwC;ArDw7T1C;;AqDv7TA;EACE,2BAAoC;ArD07TtC;;AqDx7TA;EACE,+LAAuC;ArD27TzC;;AqDz7TA;EACE,+LAAyC;ArD47T3C;;AqD17TA;EACE,+LAA0C;ArD67T5C;;AqD37TA;EACE,iCAAyC;ArD87T3C;;AqD57TA;EACE,iCAAoC;ArD+7TtC;;AsD3hUE;EACE,yBAA+B;AtD8hUnC;;ACn9TE;EqDzEE;IACE,yBAA+B;EtDgiUnC;AACF;;ACr9TE;EqD1EE;IACE,yBAA+B;EtDmiUnC;AACF;;ACv9TE;EqD3EE;IACE,yBAA+B;EtDsiUnC;AACF;;ACz9TE;EqD5EE;IACE,yBAA+B;EtDyiUnC;AACF;;AC39TE;EqD7EE;IACE,yBAA+B;EtD4iUnC;AACF;;AC59TI;EqD/EA;IACE,yBAA+B;EtD+iUnC;AACF;;ACx9TI;EqDtFA;IACE,yBAA+B;EtDkjUnC;AACF;;ACz9TI;EqDxFA;IACE,yBAA+B;EtDqjUnC;AACF;;ACr9TI;EqD/FA;IACE,yBAA+B;EtDwjUnC;AACF;;AsDrlUE;EACE,wBAA+B;AtDwlUnC;;AC7gUE;EqDzEE;IACE,wBAA+B;EtD0lUnC;AACF;;AC/gUE;EqD1EE;IACE,wBAA+B;EtD6lUnC;AACF;;ACjhUE;EqD3EE;IACE,wBAA+B;EtDgmUnC;AACF;;ACnhUE;EqD5EE;IACE,wBAA+B;EtDmmUnC;AACF;;ACrhUE;EqD7EE;IACE,wBAA+B;EtDsmUnC;AACF;;ACthUI;EqD/EA;IACE,wBAA+B;EtDymUnC;AACF;;AClhUI;EqDtFA;IACE,wBAA+B;EtD4mUnC;AACF;;ACnhUI;EqDxFA;IACE,wBAA+B;EtD+mUnC;AACF;;AC/gUI;EqD/FA;IACE,wBAA+B;EtDknUnC;AACF;;AsD/oUE;EACE,0BAA+B;AtDkpUnC;;ACvkUE;EqDzEE;IACE,0BAA+B;EtDopUnC;AACF;;ACzkUE;EqD1EE;IACE,0BAA+B;EtDupUnC;AACF;;AC3kUE;EqD3EE;IACE,0BAA+B;EtD0pUnC;AACF;;AC7kUE;EqD5EE;IACE,0BAA+B;EtD6pUnC;AACF;;AC/kUE;EqD7EE;IACE,0BAA+B;EtDgqUnC;AACF;;AChlUI;EqD/EA;IACE,0BAA+B;EtDmqUnC;AACF;;AC5kUI;EqDtFA;IACE,0BAA+B;EtDsqUnC;AACF;;AC7kUI;EqDxFA;IACE,0BAA+B;EtDyqUnC;AACF;;ACzkUI;EqD/FA;IACE,0BAA+B;EtD4qUnC;AACF;;AsDzsUE;EACE,gCAA+B;AtD4sUnC;;ACjoUE;EqDzEE;IACE,gCAA+B;EtD8sUnC;AACF;;ACnoUE;EqD1EE;IACE,gCAA+B;EtDitUnC;AACF;;ACroUE;EqD3EE;IACE,gCAA+B;EtDotUnC;AACF;;ACvoUE;EqD5EE;IACE,gCAA+B;EtDutUnC;AACF;;ACzoUE;EqD7EE;IACE,gCAA+B;EtD0tUnC;AACF;;AC1oUI;EqD/EA;IACE,gCAA+B;EtD6tUnC;AACF;;ACtoUI;EqDtFA;IACE,gCAA+B;EtDguUnC;AACF;;ACvoUI;EqDxFA;IACE,gCAA+B;EtDmuUnC;AACF;;ACnoUI;EqD/FA;IACE,gCAA+B;EtDsuUnC;AACF;;AsDnwUE;EACE,+BAA+B;AtDswUnC;;AC3rUE;EqDzEE;IACE,+BAA+B;EtDwwUnC;AACF;;AC7rUE;EqD1EE;IACE,+BAA+B;EtD2wUnC;AACF;;AC/rUE;EqD3EE;IACE,+BAA+B;EtD8wUnC;AACF;;ACjsUE;EqD5EE;IACE,+BAA+B;EtDixUnC;AACF;;ACnsUE;EqD7EE;IACE,+BAA+B;EtDoxUnC;AACF;;ACpsUI;EqD/EA;IACE,+BAA+B;EtDuxUnC;AACF;;AChsUI;EqDtFA;IACE,+BAA+B;EtD0xUnC;AACF;;ACjsUI;EqDxFA;IACE,+BAA+B;EtD6xUnC;AACF;;AC7rUI;EqD/FA;IACE,+BAA+B;EtDgyUnC;AACF;;AsD/xUA;EACE,wBAAwB;AtDkyU1B;;AsDhyUA;EACE,uBAAuB;EACvB,iCAAiC;EACjC,yBAAyB;EACzB,2BAA2B;EAC3B,qBAAqB;EACrB,6BAA6B;EAC7B,8BAA8B;EAC9B,wBAAwB;AtDmyU1B;;AChwUE;EqDhCA;IACE,wBAAwB;EtDoyU1B;AACF;;AClwUE;EqDhCA;IACE,wBAAwB;EtDsyU1B;AACF;;ACpwUE;EqDhCA;IACE,wBAAwB;EtDwyU1B;AACF;;ACtwUE;EqDhCA;IACE,wBAAwB;EtD0yU1B;AACF;;ACxwUE;EqDhCA;IACE,wBAAwB;EtD4yU1B;AACF;;ACzwUI;EqDjCF;IACE,wBAAwB;EtD8yU1B;AACF;;ACrwUI;EqDvCF;IACE,wBAAwB;EtDgzU1B;AACF;;ACtwUI;EqDxCF;IACE,wBAAwB;EtDkzU1B;AACF;;AClwUI;EqD9CF;IACE,wBAAwB;EtDozU1B;AACF;;AsDnzUA;EACE,6BAA6B;AtDszU/B;;AC1zUE;EqDOA;IACE,6BAA6B;EtDuzU/B;AACF;;AC5zUE;EqDOA;IACE,6BAA6B;EtDyzU/B;AACF;;AC9zUE;EqDOA;IACE,6BAA6B;EtD2zU/B;AACF;;ACh0UE;EqDOA;IACE,6BAA6B;EtD6zU/B;AACF;;ACl0UE;EqDOA;IACE,6BAA6B;EtD+zU/B;AACF;;ACn0UI;EqDMF;IACE,6BAA6B;EtDi0U/B;AACF;;AC/zUI;EqDAF;IACE,6BAA6B;EtDm0U/B;AACF;;ACh0UI;EqDDF;IACE,6BAA6B;EtDq0U/B;AACF;;AC5zUI;EqDPF;IACE,6BAA6B;EtDu0U/B;AACF;;AuDj8UA,iBAAA;ACQA;EACE,oBAAoB;EACpB,aAAa;EACb,sBAAsB;EACtB,8BAA8B;AxD67UhC;;AwDj8UA;EAMI,gBAAgB;AxD+7UpB;;AwDr8UA;EASM,mBAAmB;AxDg8UzB;;AwDz8UA;EAeM,uBtDRyB;EsDSzB,ctDtBuB;AFo9U7B;;AwD98UA;;EAmBQ,cAAc;AxDg8UtB;;AwDn9UA;EAqBQ,ctD3BqB;AF69U7B;;AwDv9UA;EAuBQ,4BtD7BqB;AFi+U7B;;AwD39UA;;EA0BU,ctDhCmB;AFs+U7B;;AC34UE;EuDrFF;IA6BU,uBtDtBqB;EF89U7B;AACF;;AwDt+UA;;EAgCQ,4BtDtCqB;AFi/U7B;;AwD3+UA;;;EAqCU,yB7CgEuB;E6C/DvB,ctD5CmB;AFw/U7B;;AwDl/UA;EAyCU,ctD/CmB;EsDgDnB,YAAY;AxD68UtB;;AwDv/UA;EA4CY,UAAU;AxD+8UtB;;AwD3/UA;EA+CY,UAAU;AxDg9UtB;;AwD//UA;EAmDY,ctDzDiB;AFygV7B;;AwDngVA;EAqDc,uCtD3De;AF6gV7B;;AwDvgVA;EAyDc,yBtD/De;EsDgEf,qBtDhEe;EsDiEf,YtDpDiB;AFsgV/B;;AwD7gVA;EAiEU,4EAAyG;AxDg9UnH;;ACx8UE;EuDzEF;IAoEc,4EAAyG;ExDk9UrH;AACF;;AwDvhVA;EAeM,yBtDrBuB;EsDsBvB,YtDTyB;AFqhV/B;;AwD5hVA;;EAmBQ,cAAc;AxD8gVtB;;AwDjiVA;EAqBQ,YtDduB;AF8hV/B;;AwDriVA;EAuBQ,+BtDhBuB;AFkiV/B;;AwDziVA;;EA0BU,YtDnBqB;AFuiV/B;;ACz9UE;EuDrFF;IA6BU,yBtDnCmB;EFyjV3B;AACF;;AwDpjVA;;EAgCQ,+BtDzBuB;AFkjV/B;;AwDzjVA;;;EAqCU,uB7CgEuB;E6C/DvB,YtD/BqB;AFyjV/B;;AwDhkVA;EAyCU,YtDlCqB;EsDmCrB,YAAY;AxD2hVtB;;AwDrkVA;EA4CY,UAAU;AxD6hVtB;;AwDzkVA;EA+CY,UAAU;AxD8hVtB;;AwD7kVA;EAmDY,YtD5CmB;AF0kV/B;;AwDjlVA;EAqDc,uCtD3De;AF2lV7B;;AwDrlVA;EAyDc,uBtDlDiB;EsDmDjB,mBtDnDiB;EsDoDjB,ctDjEe;AFimV7B;;AwD3lVA;EAiEU,8EAAyG;AxD8hVnH;;ACthVE;EuDzEF;IAoEc,8EAAyG;ExDgiVrH;AACF;;AwDrmVA;EAeM,4BtDVwB;EsDWxB,yB7CwDe;AXkiVrB;;AwD1mVA;;EAmBQ,cAAc;AxD4lVtB;;AwD/mVA;EAqBQ,yB7CmDa;AX2iVrB;;AwDnnVA;EAuBQ,yB7CiDa;AX+iVrB;;AwDvnVA;;EA0BU,yB7C8CW;AXojVrB;;ACviVE;EuDrFF;IA6BU,4BtDxBoB;EF4nV5B;AACF;;AwDloVA;;EAgCQ,yB7CwCa;AX+jVrB;;AwDvoVA;;;EAqCU,yB7CgEuB;E6C/DvB,yB7CkCW;AXskVrB;;AwD9oVA;EAyCU,yB7C+BW;E6C9BX,YAAY;AxDymVtB;;AwDnpVA;EA4CY,UAAU;AxD2mVtB;;AwDvpVA;EA+CY,UAAU;AxD4mVtB;;AwD3pVA;EAmDY,yB7CqBS;AXulVrB;;AwD/pVA;EAqDc,uCtD3De;AFyqV7B;;AwDnqVA;EAyDc,oC7CeO;E6CdP,gC7CcO;E6CbP,iBtDtDgB;AFoqV9B;;AwDzqVA;EAiEU,iFAAyG;AxD4mVnH;;ACpmVE;EuDzEF;IAoEc,iFAAyG;ExD8mVrH;AACF;;AwDnrVA;EAeM,yBtDjBwB;EsDkBxB,W7C0DU;AX8mVhB;;AwDxrVA;;EAmBQ,cAAc;AxD0qVtB;;AwD7rVA;EAqBQ,W7CqDQ;AXunVhB;;AwDjsVA;EAuBQ,+B7CmDQ;AX2nVhB;;AwDrsVA;;EA0BU,W7CgDM;AXgoVhB;;ACrnVE;EuDrFF;IA6BU,yBtD/BoB;EFitV5B;AACF;;AwDhtVA;;EAgCQ,+B7C0CQ;AX2oVhB;;AwDrtVA;;;EAqCU,yB7CgEuB;E6C/DvB,W7CoCM;AXkpVhB;;AwD5tVA;EAyCU,W7CiCM;E6ChCN,YAAY;AxDurVtB;;AwDjuVA;EA4CY,UAAU;AxDyrVtB;;AwDruVA;EA+CY,UAAU;AxD0rVtB;;AwDzuVA;EAmDY,W7CuBI;AXmqVhB;;AwD7uVA;EAqDc,uCtD3De;AFuvV7B;;AwDjvVA;EAyDc,sB7CiBE;E6ChBF,kB7CgBE;E6CfF,ctD7DgB;AFyvV9B;;AwDvvVA;EAiEU,gFAAyG;AxD0rVnH;;AClrVE;EuDzEF;IAoEc,gFAAyG;ExD4rVrH;AACF;;AwDjwVA;EAeM,yBtDH4B;EsDI5B,W7C0DU;AX4rVhB;;AwDtwVA;;EAmBQ,cAAc;AxDwvVtB;;AwD3wVA;EAqBQ,W7CqDQ;AXqsVhB;;AwD/wVA;EAuBQ,+B7CmDQ;AXysVhB;;AwDnxVA;;EA0BU,W7CgDM;AX8sVhB;;ACnsVE;EuDrFF;IA6BU,yBtDjBwB;EFixVhC;AACF;;AwD9xVA;;EAgCQ,+B7C0CQ;AXytVhB;;AwDnyVA;;;EAqCU,yB7CgEuB;E6C/DvB,W7CoCM;AXguVhB;;AwD1yVA;EAyCU,W7CiCM;E6ChCN,YAAY;AxDqwVtB;;AwD/yVA;EA4CY,UAAU;AxDuwVtB;;AwDnzVA;EA+CY,UAAU;AxDwwVtB;;AwDvzVA;EAmDY,W7CuBI;AXivVhB;;AwD3zVA;EAqDc,uCtD3De;AFq0V7B;;AwD/zVA;EAyDc,sB7CiBE;E6ChBF,kB7CgBE;E6CfF,ctD/CoB;AFyzVlC;;AwDr0VA;EAiEU,gFAAyG;AxDwwVnH;;AChwVE;EuDzEF;IAoEc,gFAAyG;ExD0wVrH;AACF;;AwD/0VA;EAeM,yBtDD4B;EsDE5B,W7C0DU;AX0wVhB;;AwDp1VA;;EAmBQ,cAAc;AxDs0VtB;;AwDz1VA;EAqBQ,W7CqDQ;AXmxVhB;;AwD71VA;EAuBQ,+B7CmDQ;AXuxVhB;;AwDj2VA;;EA0BU,W7CgDM;AX4xVhB;;ACjxVE;EuDrFF;IA6BU,yBtDfwB;EF61VhC;AACF;;AwD52VA;;EAgCQ,+B7C0CQ;AXuyVhB;;AwDj3VA;;;EAqCU,yB7CgEuB;E6C/DvB,W7CoCM;AX8yVhB;;AwDx3VA;EAyCU,W7CiCM;E6ChCN,YAAY;AxDm1VtB;;AwD73VA;EA4CY,UAAU;AxDq1VtB;;AwDj4VA;EA+CY,UAAU;AxDs1VtB;;AwDr4VA;EAmDY,W7CuBI;AX+zVhB;;AwDz4VA;EAqDc,uCtD3De;AFm5V7B;;AwD74VA;EAyDc,sB7CiBE;E6ChBF,kB7CgBE;E6CfF,ctD7CoB;AFq4VlC;;AwDn5VA;EAiEU,gFAAyG;AxDs1VnH;;AC90VE;EuDzEF;IAoEc,gFAAyG;ExDw1VrH;AACF;;AwD75VA;EAeM,yBtDF4B;EsDG5B,W7C0DU;AXw1VhB;;AwDl6VA;;EAmBQ,cAAc;AxDo5VtB;;AwDv6VA;EAqBQ,W7CqDQ;AXi2VhB;;AwD36VA;EAuBQ,+B7CmDQ;AXq2VhB;;AwD/6VA;;EA0BU,W7CgDM;AX02VhB;;AC/1VE;EuDrFF;IA6BU,yBtDhBwB;EF46VhC;AACF;;AwD17VA;;EAgCQ,+B7C0CQ;AXq3VhB;;AwD/7VA;;;EAqCU,yB7CgEuB;E6C/DvB,W7CoCM;AX43VhB;;AwDt8VA;EAyCU,W7CiCM;E6ChCN,YAAY;AxDi6VtB;;AwD38VA;EA4CY,UAAU;AxDm6VtB;;AwD/8VA;EA+CY,UAAU;AxDo6VtB;;AwDn9VA;EAmDY,W7CuBI;AX64VhB;;AwDv9VA;EAqDc,uCtD3De;AFi+V7B;;AwD39VA;EAyDc,sB7CiBE;E6ChBF,kB7CgBE;E6CfF,ctD9CoB;AFo9VlC;;AwDj+VA;EAiEU,gFAAyG;AxDo6VnH;;AC55VE;EuDzEF;IAoEc,gFAAyG;ExDs6VrH;AACF;;AwD3+VA;EAeM,yBtDJ4B;EsDK5B,W7C0DU;AXs6VhB;;AwDh/VA;;EAmBQ,cAAc;AxDk+VtB;;AwDr/VA;EAqBQ,W7CqDQ;AX+6VhB;;AwDz/VA;EAuBQ,+B7CmDQ;AXm7VhB;;AwD7/VA;;EA0BU,W7CgDM;AXw7VhB;;AC76VE;EuDrFF;IA6BU,yBtDlBwB;EF4/VhC;AACF;;AwDxgWA;;EAgCQ,+B7C0CQ;AXm8VhB;;AwD7gWA;;;EAqCU,yB7CgEuB;E6C/DvB,W7CoCM;AX08VhB;;AwDphWA;EAyCU,W7CiCM;E6ChCN,YAAY;AxD++VtB;;AwDzhWA;EA4CY,UAAU;AxDi/VtB;;AwD7hWA;EA+CY,UAAU;AxDk/VtB;;AwDjiWA;EAmDY,W7CuBI;AX29VhB;;AwDriWA;EAqDc,uCtD3De;AF+iW7B;;AwDziWA;EAyDc,sB7CiBE;E6ChBF,kB7CgBE;E6CfF,ctDhDoB;AFoiWlC;;AwD/iWA;EAiEU,gFAAyG;AxDk/VnH;;AC1+VE;EuDzEF;IAoEc,gFAAyG;ExDo/VrH;AACF;;AwDzjWA;EAeM,yBtDL4B;EsDM5B,yB7CwDe;AXs/VrB;;AwD9jWA;;EAmBQ,cAAc;AxDgjWtB;;AwDnkWA;EAqBQ,yB7CmDa;AX+/VrB;;AwDvkWA;EAuBQ,yB7CiDa;AXmgWrB;;AwD3kWA;;EA0BU,yB7C8CW;AXwgWrB;;AC3/VE;EuDrFF;IA6BU,yBtDnBwB;EF2kWhC;AACF;;AwDtlWA;;EAgCQ,yB7CwCa;AXmhWrB;;AwD3lWA;;;EAqCU,yB7CgEuB;E6C/DvB,yB7CkCW;AX0hWrB;;AwDlmWA;EAyCU,yB7C+BW;E6C9BX,YAAY;AxD6jWtB;;AwDvmWA;EA4CY,UAAU;AxD+jWtB;;AwD3mWA;EA+CY,UAAU;AxDgkWtB;;AwD/mWA;EAmDY,yB7CqBS;AX2iWrB;;AwDnnWA;EAqDc,uCtD3De;AF6nW7B;;AwDvnWA;EAyDc,oC7CeO;E6CdP,gC7CcO;E6CbP,ctDjDoB;AFmnWlC;;AwD7nWA;EAiEU,gFAAyG;AxDgkWnH;;ACxjWE;EuDzEF;IAoEc,gFAAyG;ExDkkWrH;AACF;;AwDvoWA;EAeM,yBtDC2B;EsDA3B,W7C0DU;AXkkWhB;;AwD5oWA;;EAmBQ,cAAc;AxD8nWtB;;AwDjpWA;EAqBQ,W7CqDQ;AX2kWhB;;AwDrpWA;EAuBQ,+B7CmDQ;AX+kWhB;;AwDzpWA;;EA0BU,W7CgDM;AXolWhB;;ACzkWE;EuDrFF;IA6BU,yBtDbuB;EFmpW/B;AACF;;AwDpqWA;;EAgCQ,+B7C0CQ;AX+lWhB;;AwDzqWA;;;EAqCU,yB7CgEuB;E6C/DvB,W7CoCM;AXsmWhB;;AwDhrWA;EAyCU,W7CiCM;E6ChCN,YAAY;AxD2oWtB;;AwDrrWA;EA4CY,UAAU;AxD6oWtB;;AwDzrWA;EA+CY,UAAU;AxD8oWtB;;AwD7rWA;EAmDY,W7CuBI;AXunWhB;;AwDjsWA;EAqDc,uCtD3De;AF2sW7B;;AwDrsWA;EAyDc,sB7CiBE;E6ChBF,kB7CgBE;E6CfF,ctD3CmB;AF2rWjC;;AwD3sWA;EAiEU,gFAAyG;AxD8oWnH;;ACtoWE;EuDzEF;IAoEc,gFAAyG;ExDgpWrH;AACF;;AwDrtWA;EAwEM,eA/E0B;AxDguWhC;;AC5oWE;EuD7EF;IA4EQ,oBAlF8B;ExDouWpC;AACF;;AClpWE;EuD7EF;IAgFQ,qBArF8B;ExDyuWpC;AACF;;AwDruWA;EAqFM,mBAAmB;EACnB,aAAa;AxDopWnB;;AwD1uWA;EAwFQ,YAAY;EACZ,cAAc;AxDspWtB;;AwD/uWA;EA2FI,gBAAgB;AxDwpWpB;;AwDnvWA;EA6FI,iBAAiB;AxD0pWrB;;AwDtpWA;EAEE,gBAAgB;AxDwpWlB;;AwD1pWA;EAII,SAAS;EACT,gBAAgB;EAChB,eAAe;EACf,kBAAkB;EAClB,QAAQ;EACR,qCAAqC;AxD0pWzC;;AwDnqWA;EAYI,YAAY;AxD2pWhB;;AC/rWE;EuDwBF;IAeI,aAAa;ExD6pWf;AACF;;AwD5pWA;EACE,kBAAkB;AxD+pWpB;;ACzsWE;EuDyCF;IAKM,aAAa;ExDgqWjB;EwDrqWF;IAOQ,sBAAsB;ExDiqW5B;AACF;;AC9sWE;EuDqCF;IASI,aAAa;IACb,uBAAuB;ExDqqWzB;EwD/qWF;IvDsBI,oBuDVwC;ExDsqW1C;AACF;;AwDnqWA;;EAEE,YAAY;EACZ,cAAc;AxDsqWhB;;AwDpqWA;EACE,YAAY;EACZ,cAAc;EACd,oBAlJ6B;AxDyzW/B;;AyDrzWA;EACE,oBAL2B;AzD6zW7B;;AC5tWE;EwD7FF;IAMM,oBAT8B;EzDi0WlC;EyD9zWF;IAQM,qBAV8B;EzDm0WlC;AACF;;A0Dl0WA;EACE,yBxDS4B;EwDR5B,yBAJ+B;A1Dy0WjC","file":"bulma.css"}
diff --git a/docs/project_page/static/css/bulma.min.css b/docs/project_page/static/css/bulma.min.css
new file mode 100644
index 0000000..08d8f10
--- /dev/null
+++ b/docs/project_page/static/css/bulma.min.css
@@ -0,0 +1 @@
+/*! bulma.io v0.9.1 | MIT License | github.com/jgthms/bulma */@-webkit-keyframes spinAround{from{transform:rotate(0)}to{transform:rotate(359deg)}}@keyframes spinAround{from{transform:rotate(0)}to{transform:rotate(359deg)}}.breadcrumb,.button,.delete,.file,.is-unselectable,.modal-close,.pagination-ellipsis,.pagination-link,.pagination-next,.pagination-previous,.tabs{-webkit-touch-callout:none;-webkit-user-select:none;-moz-user-select:none;-ms-user-select:none;user-select:none}.navbar-link:not(.is-arrowless)::after,.select:not(.is-multiple):not(.is-loading)::after{border:3px solid transparent;border-radius:2px;border-right:0;border-top:0;content:" ";display:block;height:.625em;margin-top:-.4375em;pointer-events:none;position:absolute;top:50%;transform:rotate(-45deg);transform-origin:center;width:.625em}.block:not(:last-child),.box:not(:last-child),.breadcrumb:not(:last-child),.content:not(:last-child),.highlight:not(:last-child),.level:not(:last-child),.message:not(:last-child),.notification:not(:last-child),.pagination:not(:last-child),.progress:not(:last-child),.subtitle:not(:last-child),.table-container:not(:last-child),.table:not(:last-child),.tabs:not(:last-child),.title:not(:last-child){margin-bottom:1.5rem}.delete,.modal-close{-moz-appearance:none;-webkit-appearance:none;background-color:rgba(10,10,10,.2);border:none;border-radius:290486px;cursor:pointer;pointer-events:auto;display:inline-block;flex-grow:0;flex-shrink:0;font-size:0;height:20px;max-height:20px;max-width:20px;min-height:20px;min-width:20px;outline:0;position:relative;vertical-align:top;width:20px}.delete::after,.delete::before,.modal-close::after,.modal-close::before{background-color:#fff;content:"";display:block;left:50%;position:absolute;top:50%;transform:translateX(-50%) translateY(-50%) rotate(45deg);transform-origin:center center}.delete::before,.modal-close::before{height:2px;width:50%}.delete::after,.modal-close::after{height:50%;width:2px}.delete:focus,.delete:hover,.modal-close:focus,.modal-close:hover{background-color:rgba(10,10,10,.3)}.delete:active,.modal-close:active{background-color:rgba(10,10,10,.4)}.is-small.delete,.is-small.modal-close{height:16px;max-height:16px;max-width:16px;min-height:16px;min-width:16px;width:16px}.is-medium.delete,.is-medium.modal-close{height:24px;max-height:24px;max-width:24px;min-height:24px;min-width:24px;width:24px}.is-large.delete,.is-large.modal-close{height:32px;max-height:32px;max-width:32px;min-height:32px;min-width:32px;width:32px}.button.is-loading::after,.control.is-loading::after,.loader,.select.is-loading::after{-webkit-animation:spinAround .5s infinite linear;animation:spinAround .5s infinite linear;border:2px solid #dbdbdb;border-radius:290486px;border-right-color:transparent;border-top-color:transparent;content:"";display:block;height:1em;position:relative;width:1em}.hero-video,.image.is-16by9 .has-ratio,.image.is-16by9 img,.image.is-1by1 .has-ratio,.image.is-1by1 img,.image.is-1by2 .has-ratio,.image.is-1by2 img,.image.is-1by3 .has-ratio,.image.is-1by3 img,.image.is-2by1 .has-ratio,.image.is-2by1 img,.image.is-2by3 .has-ratio,.image.is-2by3 img,.image.is-3by1 .has-ratio,.image.is-3by1 img,.image.is-3by2 .has-ratio,.image.is-3by2 img,.image.is-3by4 .has-ratio,.image.is-3by4 img,.image.is-3by5 .has-ratio,.image.is-3by5 img,.image.is-4by3 .has-ratio,.image.is-4by3 img,.image.is-4by5 .has-ratio,.image.is-4by5 img,.image.is-5by3 .has-ratio,.image.is-5by3 img,.image.is-5by4 .has-ratio,.image.is-5by4 img,.image.is-9by16 .has-ratio,.image.is-9by16 img,.image.is-square .has-ratio,.image.is-square img,.is-overlay,.modal,.modal-background{bottom:0;left:0;position:absolute;right:0;top:0}.button,.file-cta,.file-name,.input,.pagination-ellipsis,.pagination-link,.pagination-next,.pagination-previous,.select select,.textarea{-moz-appearance:none;-webkit-appearance:none;align-items:center;border:1px solid transparent;border-radius:4px;box-shadow:none;display:inline-flex;font-size:1rem;height:2.5em;justify-content:flex-start;line-height:1.5;padding-bottom:calc(.5em - 1px);padding-left:calc(.75em - 1px);padding-right:calc(.75em - 1px);padding-top:calc(.5em - 1px);position:relative;vertical-align:top}.button:active,.button:focus,.file-cta:active,.file-cta:focus,.file-name:active,.file-name:focus,.input:active,.input:focus,.is-active.button,.is-active.file-cta,.is-active.file-name,.is-active.input,.is-active.pagination-ellipsis,.is-active.pagination-link,.is-active.pagination-next,.is-active.pagination-previous,.is-active.textarea,.is-focused.button,.is-focused.file-cta,.is-focused.file-name,.is-focused.input,.is-focused.pagination-ellipsis,.is-focused.pagination-link,.is-focused.pagination-next,.is-focused.pagination-previous,.is-focused.textarea,.pagination-ellipsis:active,.pagination-ellipsis:focus,.pagination-link:active,.pagination-link:focus,.pagination-next:active,.pagination-next:focus,.pagination-previous:active,.pagination-previous:focus,.select select.is-active,.select select.is-focused,.select select:active,.select select:focus,.textarea:active,.textarea:focus{outline:0}.button[disabled],.file-cta[disabled],.file-name[disabled],.input[disabled],.pagination-ellipsis[disabled],.pagination-link[disabled],.pagination-next[disabled],.pagination-previous[disabled],.select fieldset[disabled] select,.select select[disabled],.textarea[disabled],fieldset[disabled] .button,fieldset[disabled] .file-cta,fieldset[disabled] .file-name,fieldset[disabled] .input,fieldset[disabled] .pagination-ellipsis,fieldset[disabled] .pagination-link,fieldset[disabled] .pagination-next,fieldset[disabled] .pagination-previous,fieldset[disabled] .select select,fieldset[disabled] .textarea{cursor:not-allowed}/*! minireset.css v0.0.6 | MIT License | github.com/jgthms/minireset.css */blockquote,body,dd,dl,dt,fieldset,figure,h1,h2,h3,h4,h5,h6,hr,html,iframe,legend,li,ol,p,pre,textarea,ul{margin:0;padding:0}h1,h2,h3,h4,h5,h6{font-size:100%;font-weight:400}ul{list-style:none}button,input,select,textarea{margin:0}html{box-sizing:border-box}*,::after,::before{box-sizing:inherit}img,video{height:auto;max-width:100%}iframe{border:0}table{border-collapse:collapse;border-spacing:0}td,th{padding:0}td:not([align]),th:not([align]){text-align:inherit}html{background-color:#fff;font-size:16px;-moz-osx-font-smoothing:grayscale;-webkit-font-smoothing:antialiased;min-width:300px;overflow-x:hidden;overflow-y:scroll;text-rendering:optimizeLegibility;-webkit-text-size-adjust:100%;-moz-text-size-adjust:100%;-ms-text-size-adjust:100%;text-size-adjust:100%}article,aside,figure,footer,header,hgroup,section{display:block}body,button,input,optgroup,select,textarea{font-family:BlinkMacSystemFont,-apple-system,"Segoe UI",Roboto,Oxygen,Ubuntu,Cantarell,"Fira Sans","Droid Sans","Helvetica Neue",Helvetica,Arial,sans-serif}code,pre{-moz-osx-font-smoothing:auto;-webkit-font-smoothing:auto;font-family:monospace}body{color:#4a4a4a;font-size:1em;font-weight:400;line-height:1.5}a{color:#3273dc;cursor:pointer;text-decoration:none}a strong{color:currentColor}a:hover{color:#363636}code{background-color:#f5f5f5;color:#da1039;font-size:.875em;font-weight:400;padding:.25em .5em .25em}hr{background-color:#f5f5f5;border:none;display:block;height:2px;margin:1.5rem 0}img{height:auto;max-width:100%}input[type=checkbox],input[type=radio]{vertical-align:baseline}small{font-size:.875em}span{font-style:inherit;font-weight:inherit}strong{color:#363636;font-weight:700}fieldset{border:none}pre{-webkit-overflow-scrolling:touch;background-color:#f5f5f5;color:#4a4a4a;font-size:.875em;overflow-x:auto;padding:1.25rem 1.5rem;white-space:pre;word-wrap:normal}pre code{background-color:transparent;color:currentColor;font-size:1em;padding:0}table td,table th{vertical-align:top}table td:not([align]),table th:not([align]){text-align:inherit}table th{color:#363636}.box{background-color:#fff;border-radius:6px;box-shadow:0 .5em 1em -.125em rgba(10,10,10,.1),0 0 0 1px rgba(10,10,10,.02);color:#4a4a4a;display:block;padding:1.25rem}a.box:focus,a.box:hover{box-shadow:0 .5em 1em -.125em rgba(10,10,10,.1),0 0 0 1px #3273dc}a.box:active{box-shadow:inset 0 1px 2px rgba(10,10,10,.2),0 0 0 1px #3273dc}.button{background-color:#fff;border-color:#dbdbdb;border-width:1px;color:#363636;cursor:pointer;justify-content:center;padding-bottom:calc(.5em - 1px);padding-left:1em;padding-right:1em;padding-top:calc(.5em - 1px);text-align:center;white-space:nowrap}.button strong{color:inherit}.button .icon,.button .icon.is-large,.button .icon.is-medium,.button .icon.is-small{height:1.5em;width:1.5em}.button .icon:first-child:not(:last-child){margin-left:calc(-.5em - 1px);margin-right:.25em}.button .icon:last-child:not(:first-child){margin-left:.25em;margin-right:calc(-.5em - 1px)}.button .icon:first-child:last-child{margin-left:calc(-.5em - 1px);margin-right:calc(-.5em - 1px)}.button.is-hovered,.button:hover{border-color:#b5b5b5;color:#363636}.button.is-focused,.button:focus{border-color:#3273dc;color:#363636}.button.is-focused:not(:active),.button:focus:not(:active){box-shadow:0 0 0 .125em rgba(50,115,220,.25)}.button.is-active,.button:active{border-color:#4a4a4a;color:#363636}.button.is-text{background-color:transparent;border-color:transparent;color:#4a4a4a;text-decoration:underline}.button.is-text.is-focused,.button.is-text.is-hovered,.button.is-text:focus,.button.is-text:hover{background-color:#f5f5f5;color:#363636}.button.is-text.is-active,.button.is-text:active{background-color:#e8e8e8;color:#363636}.button.is-text[disabled],fieldset[disabled] .button.is-text{background-color:transparent;border-color:transparent;box-shadow:none}.button.is-white{background-color:#fff;border-color:transparent;color:#0a0a0a}.button.is-white.is-hovered,.button.is-white:hover{background-color:#f9f9f9;border-color:transparent;color:#0a0a0a}.button.is-white.is-focused,.button.is-white:focus{border-color:transparent;color:#0a0a0a}.button.is-white.is-focused:not(:active),.button.is-white:focus:not(:active){box-shadow:0 0 0 .125em rgba(255,255,255,.25)}.button.is-white.is-active,.button.is-white:active{background-color:#f2f2f2;border-color:transparent;color:#0a0a0a}.button.is-white[disabled],fieldset[disabled] .button.is-white{background-color:#fff;border-color:transparent;box-shadow:none}.button.is-white.is-inverted{background-color:#0a0a0a;color:#fff}.button.is-white.is-inverted.is-hovered,.button.is-white.is-inverted:hover{background-color:#000}.button.is-white.is-inverted[disabled],fieldset[disabled] .button.is-white.is-inverted{background-color:#0a0a0a;border-color:transparent;box-shadow:none;color:#fff}.button.is-white.is-loading::after{border-color:transparent transparent #0a0a0a #0a0a0a!important}.button.is-white.is-outlined{background-color:transparent;border-color:#fff;color:#fff}.button.is-white.is-outlined.is-focused,.button.is-white.is-outlined.is-hovered,.button.is-white.is-outlined:focus,.button.is-white.is-outlined:hover{background-color:#fff;border-color:#fff;color:#0a0a0a}.button.is-white.is-outlined.is-loading::after{border-color:transparent transparent #fff #fff!important}.button.is-white.is-outlined.is-loading.is-focused::after,.button.is-white.is-outlined.is-loading.is-hovered::after,.button.is-white.is-outlined.is-loading:focus::after,.button.is-white.is-outlined.is-loading:hover::after{border-color:transparent transparent #0a0a0a #0a0a0a!important}.button.is-white.is-outlined[disabled],fieldset[disabled] .button.is-white.is-outlined{background-color:transparent;border-color:#fff;box-shadow:none;color:#fff}.button.is-white.is-inverted.is-outlined{background-color:transparent;border-color:#0a0a0a;color:#0a0a0a}.button.is-white.is-inverted.is-outlined.is-focused,.button.is-white.is-inverted.is-outlined.is-hovered,.button.is-white.is-inverted.is-outlined:focus,.button.is-white.is-inverted.is-outlined:hover{background-color:#0a0a0a;color:#fff}.button.is-white.is-inverted.is-outlined.is-loading.is-focused::after,.button.is-white.is-inverted.is-outlined.is-loading.is-hovered::after,.button.is-white.is-inverted.is-outlined.is-loading:focus::after,.button.is-white.is-inverted.is-outlined.is-loading:hover::after{border-color:transparent transparent #fff #fff!important}.button.is-white.is-inverted.is-outlined[disabled],fieldset[disabled] .button.is-white.is-inverted.is-outlined{background-color:transparent;border-color:#0a0a0a;box-shadow:none;color:#0a0a0a}.button.is-black{background-color:#0a0a0a;border-color:transparent;color:#fff}.button.is-black.is-hovered,.button.is-black:hover{background-color:#040404;border-color:transparent;color:#fff}.button.is-black.is-focused,.button.is-black:focus{border-color:transparent;color:#fff}.button.is-black.is-focused:not(:active),.button.is-black:focus:not(:active){box-shadow:0 0 0 .125em rgba(10,10,10,.25)}.button.is-black.is-active,.button.is-black:active{background-color:#000;border-color:transparent;color:#fff}.button.is-black[disabled],fieldset[disabled] .button.is-black{background-color:#0a0a0a;border-color:transparent;box-shadow:none}.button.is-black.is-inverted{background-color:#fff;color:#0a0a0a}.button.is-black.is-inverted.is-hovered,.button.is-black.is-inverted:hover{background-color:#f2f2f2}.button.is-black.is-inverted[disabled],fieldset[disabled] .button.is-black.is-inverted{background-color:#fff;border-color:transparent;box-shadow:none;color:#0a0a0a}.button.is-black.is-loading::after{border-color:transparent transparent #fff #fff!important}.button.is-black.is-outlined{background-color:transparent;border-color:#0a0a0a;color:#0a0a0a}.button.is-black.is-outlined.is-focused,.button.is-black.is-outlined.is-hovered,.button.is-black.is-outlined:focus,.button.is-black.is-outlined:hover{background-color:#0a0a0a;border-color:#0a0a0a;color:#fff}.button.is-black.is-outlined.is-loading::after{border-color:transparent transparent #0a0a0a #0a0a0a!important}.button.is-black.is-outlined.is-loading.is-focused::after,.button.is-black.is-outlined.is-loading.is-hovered::after,.button.is-black.is-outlined.is-loading:focus::after,.button.is-black.is-outlined.is-loading:hover::after{border-color:transparent transparent #fff #fff!important}.button.is-black.is-outlined[disabled],fieldset[disabled] .button.is-black.is-outlined{background-color:transparent;border-color:#0a0a0a;box-shadow:none;color:#0a0a0a}.button.is-black.is-inverted.is-outlined{background-color:transparent;border-color:#fff;color:#fff}.button.is-black.is-inverted.is-outlined.is-focused,.button.is-black.is-inverted.is-outlined.is-hovered,.button.is-black.is-inverted.is-outlined:focus,.button.is-black.is-inverted.is-outlined:hover{background-color:#fff;color:#0a0a0a}.button.is-black.is-inverted.is-outlined.is-loading.is-focused::after,.button.is-black.is-inverted.is-outlined.is-loading.is-hovered::after,.button.is-black.is-inverted.is-outlined.is-loading:focus::after,.button.is-black.is-inverted.is-outlined.is-loading:hover::after{border-color:transparent transparent #0a0a0a #0a0a0a!important}.button.is-black.is-inverted.is-outlined[disabled],fieldset[disabled] .button.is-black.is-inverted.is-outlined{background-color:transparent;border-color:#fff;box-shadow:none;color:#fff}.button.is-light{background-color:#f5f5f5;border-color:transparent;color:rgba(0,0,0,.7)}.button.is-light.is-hovered,.button.is-light:hover{background-color:#eee;border-color:transparent;color:rgba(0,0,0,.7)}.button.is-light.is-focused,.button.is-light:focus{border-color:transparent;color:rgba(0,0,0,.7)}.button.is-light.is-focused:not(:active),.button.is-light:focus:not(:active){box-shadow:0 0 0 .125em rgba(245,245,245,.25)}.button.is-light.is-active,.button.is-light:active{background-color:#e8e8e8;border-color:transparent;color:rgba(0,0,0,.7)}.button.is-light[disabled],fieldset[disabled] .button.is-light{background-color:#f5f5f5;border-color:transparent;box-shadow:none}.button.is-light.is-inverted{background-color:rgba(0,0,0,.7);color:#f5f5f5}.button.is-light.is-inverted.is-hovered,.button.is-light.is-inverted:hover{background-color:rgba(0,0,0,.7)}.button.is-light.is-inverted[disabled],fieldset[disabled] .button.is-light.is-inverted{background-color:rgba(0,0,0,.7);border-color:transparent;box-shadow:none;color:#f5f5f5}.button.is-light.is-loading::after{border-color:transparent transparent rgba(0,0,0,.7) rgba(0,0,0,.7)!important}.button.is-light.is-outlined{background-color:transparent;border-color:#f5f5f5;color:#f5f5f5}.button.is-light.is-outlined.is-focused,.button.is-light.is-outlined.is-hovered,.button.is-light.is-outlined:focus,.button.is-light.is-outlined:hover{background-color:#f5f5f5;border-color:#f5f5f5;color:rgba(0,0,0,.7)}.button.is-light.is-outlined.is-loading::after{border-color:transparent transparent #f5f5f5 #f5f5f5!important}.button.is-light.is-outlined.is-loading.is-focused::after,.button.is-light.is-outlined.is-loading.is-hovered::after,.button.is-light.is-outlined.is-loading:focus::after,.button.is-light.is-outlined.is-loading:hover::after{border-color:transparent transparent rgba(0,0,0,.7) rgba(0,0,0,.7)!important}.button.is-light.is-outlined[disabled],fieldset[disabled] .button.is-light.is-outlined{background-color:transparent;border-color:#f5f5f5;box-shadow:none;color:#f5f5f5}.button.is-light.is-inverted.is-outlined{background-color:transparent;border-color:rgba(0,0,0,.7);color:rgba(0,0,0,.7)}.button.is-light.is-inverted.is-outlined.is-focused,.button.is-light.is-inverted.is-outlined.is-hovered,.button.is-light.is-inverted.is-outlined:focus,.button.is-light.is-inverted.is-outlined:hover{background-color:rgba(0,0,0,.7);color:#f5f5f5}.button.is-light.is-inverted.is-outlined.is-loading.is-focused::after,.button.is-light.is-inverted.is-outlined.is-loading.is-hovered::after,.button.is-light.is-inverted.is-outlined.is-loading:focus::after,.button.is-light.is-inverted.is-outlined.is-loading:hover::after{border-color:transparent transparent #f5f5f5 #f5f5f5!important}.button.is-light.is-inverted.is-outlined[disabled],fieldset[disabled] .button.is-light.is-inverted.is-outlined{background-color:transparent;border-color:rgba(0,0,0,.7);box-shadow:none;color:rgba(0,0,0,.7)}.button.is-dark{background-color:#363636;border-color:transparent;color:#fff}.button.is-dark.is-hovered,.button.is-dark:hover{background-color:#2f2f2f;border-color:transparent;color:#fff}.button.is-dark.is-focused,.button.is-dark:focus{border-color:transparent;color:#fff}.button.is-dark.is-focused:not(:active),.button.is-dark:focus:not(:active){box-shadow:0 0 0 .125em rgba(54,54,54,.25)}.button.is-dark.is-active,.button.is-dark:active{background-color:#292929;border-color:transparent;color:#fff}.button.is-dark[disabled],fieldset[disabled] .button.is-dark{background-color:#363636;border-color:transparent;box-shadow:none}.button.is-dark.is-inverted{background-color:#fff;color:#363636}.button.is-dark.is-inverted.is-hovered,.button.is-dark.is-inverted:hover{background-color:#f2f2f2}.button.is-dark.is-inverted[disabled],fieldset[disabled] .button.is-dark.is-inverted{background-color:#fff;border-color:transparent;box-shadow:none;color:#363636}.button.is-dark.is-loading::after{border-color:transparent transparent #fff #fff!important}.button.is-dark.is-outlined{background-color:transparent;border-color:#363636;color:#363636}.button.is-dark.is-outlined.is-focused,.button.is-dark.is-outlined.is-hovered,.button.is-dark.is-outlined:focus,.button.is-dark.is-outlined:hover{background-color:#363636;border-color:#363636;color:#fff}.button.is-dark.is-outlined.is-loading::after{border-color:transparent transparent #363636 #363636!important}.button.is-dark.is-outlined.is-loading.is-focused::after,.button.is-dark.is-outlined.is-loading.is-hovered::after,.button.is-dark.is-outlined.is-loading:focus::after,.button.is-dark.is-outlined.is-loading:hover::after{border-color:transparent transparent #fff #fff!important}.button.is-dark.is-outlined[disabled],fieldset[disabled] .button.is-dark.is-outlined{background-color:transparent;border-color:#363636;box-shadow:none;color:#363636}.button.is-dark.is-inverted.is-outlined{background-color:transparent;border-color:#fff;color:#fff}.button.is-dark.is-inverted.is-outlined.is-focused,.button.is-dark.is-inverted.is-outlined.is-hovered,.button.is-dark.is-inverted.is-outlined:focus,.button.is-dark.is-inverted.is-outlined:hover{background-color:#fff;color:#363636}.button.is-dark.is-inverted.is-outlined.is-loading.is-focused::after,.button.is-dark.is-inverted.is-outlined.is-loading.is-hovered::after,.button.is-dark.is-inverted.is-outlined.is-loading:focus::after,.button.is-dark.is-inverted.is-outlined.is-loading:hover::after{border-color:transparent transparent #363636 #363636!important}.button.is-dark.is-inverted.is-outlined[disabled],fieldset[disabled] .button.is-dark.is-inverted.is-outlined{background-color:transparent;border-color:#fff;box-shadow:none;color:#fff}.button.is-primary{background-color:#00d1b2;border-color:transparent;color:#fff}.button.is-primary.is-hovered,.button.is-primary:hover{background-color:#00c4a7;border-color:transparent;color:#fff}.button.is-primary.is-focused,.button.is-primary:focus{border-color:transparent;color:#fff}.button.is-primary.is-focused:not(:active),.button.is-primary:focus:not(:active){box-shadow:0 0 0 .125em rgba(0,209,178,.25)}.button.is-primary.is-active,.button.is-primary:active{background-color:#00b89c;border-color:transparent;color:#fff}.button.is-primary[disabled],fieldset[disabled] .button.is-primary{background-color:#00d1b2;border-color:transparent;box-shadow:none}.button.is-primary.is-inverted{background-color:#fff;color:#00d1b2}.button.is-primary.is-inverted.is-hovered,.button.is-primary.is-inverted:hover{background-color:#f2f2f2}.button.is-primary.is-inverted[disabled],fieldset[disabled] .button.is-primary.is-inverted{background-color:#fff;border-color:transparent;box-shadow:none;color:#00d1b2}.button.is-primary.is-loading::after{border-color:transparent transparent #fff #fff!important}.button.is-primary.is-outlined{background-color:transparent;border-color:#00d1b2;color:#00d1b2}.button.is-primary.is-outlined.is-focused,.button.is-primary.is-outlined.is-hovered,.button.is-primary.is-outlined:focus,.button.is-primary.is-outlined:hover{background-color:#00d1b2;border-color:#00d1b2;color:#fff}.button.is-primary.is-outlined.is-loading::after{border-color:transparent transparent #00d1b2 #00d1b2!important}.button.is-primary.is-outlined.is-loading.is-focused::after,.button.is-primary.is-outlined.is-loading.is-hovered::after,.button.is-primary.is-outlined.is-loading:focus::after,.button.is-primary.is-outlined.is-loading:hover::after{border-color:transparent transparent #fff #fff!important}.button.is-primary.is-outlined[disabled],fieldset[disabled] .button.is-primary.is-outlined{background-color:transparent;border-color:#00d1b2;box-shadow:none;color:#00d1b2}.button.is-primary.is-inverted.is-outlined{background-color:transparent;border-color:#fff;color:#fff}.button.is-primary.is-inverted.is-outlined.is-focused,.button.is-primary.is-inverted.is-outlined.is-hovered,.button.is-primary.is-inverted.is-outlined:focus,.button.is-primary.is-inverted.is-outlined:hover{background-color:#fff;color:#00d1b2}.button.is-primary.is-inverted.is-outlined.is-loading.is-focused::after,.button.is-primary.is-inverted.is-outlined.is-loading.is-hovered::after,.button.is-primary.is-inverted.is-outlined.is-loading:focus::after,.button.is-primary.is-inverted.is-outlined.is-loading:hover::after{border-color:transparent transparent #00d1b2 #00d1b2!important}.button.is-primary.is-inverted.is-outlined[disabled],fieldset[disabled] .button.is-primary.is-inverted.is-outlined{background-color:transparent;border-color:#fff;box-shadow:none;color:#fff}.button.is-primary.is-light{background-color:#ebfffc;color:#00947e}.button.is-primary.is-light.is-hovered,.button.is-primary.is-light:hover{background-color:#defffa;border-color:transparent;color:#00947e}.button.is-primary.is-light.is-active,.button.is-primary.is-light:active{background-color:#d1fff8;border-color:transparent;color:#00947e}.button.is-link{background-color:#3273dc;border-color:transparent;color:#fff}.button.is-link.is-hovered,.button.is-link:hover{background-color:#276cda;border-color:transparent;color:#fff}.button.is-link.is-focused,.button.is-link:focus{border-color:transparent;color:#fff}.button.is-link.is-focused:not(:active),.button.is-link:focus:not(:active){box-shadow:0 0 0 .125em rgba(50,115,220,.25)}.button.is-link.is-active,.button.is-link:active{background-color:#2366d1;border-color:transparent;color:#fff}.button.is-link[disabled],fieldset[disabled] .button.is-link{background-color:#3273dc;border-color:transparent;box-shadow:none}.button.is-link.is-inverted{background-color:#fff;color:#3273dc}.button.is-link.is-inverted.is-hovered,.button.is-link.is-inverted:hover{background-color:#f2f2f2}.button.is-link.is-inverted[disabled],fieldset[disabled] .button.is-link.is-inverted{background-color:#fff;border-color:transparent;box-shadow:none;color:#3273dc}.button.is-link.is-loading::after{border-color:transparent transparent #fff #fff!important}.button.is-link.is-outlined{background-color:transparent;border-color:#3273dc;color:#3273dc}.button.is-link.is-outlined.is-focused,.button.is-link.is-outlined.is-hovered,.button.is-link.is-outlined:focus,.button.is-link.is-outlined:hover{background-color:#3273dc;border-color:#3273dc;color:#fff}.button.is-link.is-outlined.is-loading::after{border-color:transparent transparent #3273dc #3273dc!important}.button.is-link.is-outlined.is-loading.is-focused::after,.button.is-link.is-outlined.is-loading.is-hovered::after,.button.is-link.is-outlined.is-loading:focus::after,.button.is-link.is-outlined.is-loading:hover::after{border-color:transparent transparent #fff #fff!important}.button.is-link.is-outlined[disabled],fieldset[disabled] .button.is-link.is-outlined{background-color:transparent;border-color:#3273dc;box-shadow:none;color:#3273dc}.button.is-link.is-inverted.is-outlined{background-color:transparent;border-color:#fff;color:#fff}.button.is-link.is-inverted.is-outlined.is-focused,.button.is-link.is-inverted.is-outlined.is-hovered,.button.is-link.is-inverted.is-outlined:focus,.button.is-link.is-inverted.is-outlined:hover{background-color:#fff;color:#3273dc}.button.is-link.is-inverted.is-outlined.is-loading.is-focused::after,.button.is-link.is-inverted.is-outlined.is-loading.is-hovered::after,.button.is-link.is-inverted.is-outlined.is-loading:focus::after,.button.is-link.is-inverted.is-outlined.is-loading:hover::after{border-color:transparent transparent #3273dc #3273dc!important}.button.is-link.is-inverted.is-outlined[disabled],fieldset[disabled] .button.is-link.is-inverted.is-outlined{background-color:transparent;border-color:#fff;box-shadow:none;color:#fff}.button.is-link.is-light{background-color:#eef3fc;color:#2160c4}.button.is-link.is-light.is-hovered,.button.is-link.is-light:hover{background-color:#e3ecfa;border-color:transparent;color:#2160c4}.button.is-link.is-light.is-active,.button.is-link.is-light:active{background-color:#d8e4f8;border-color:transparent;color:#2160c4}.button.is-info{background-color:#3298dc;border-color:transparent;color:#fff}.button.is-info.is-hovered,.button.is-info:hover{background-color:#2793da;border-color:transparent;color:#fff}.button.is-info.is-focused,.button.is-info:focus{border-color:transparent;color:#fff}.button.is-info.is-focused:not(:active),.button.is-info:focus:not(:active){box-shadow:0 0 0 .125em rgba(50,152,220,.25)}.button.is-info.is-active,.button.is-info:active{background-color:#238cd1;border-color:transparent;color:#fff}.button.is-info[disabled],fieldset[disabled] .button.is-info{background-color:#3298dc;border-color:transparent;box-shadow:none}.button.is-info.is-inverted{background-color:#fff;color:#3298dc}.button.is-info.is-inverted.is-hovered,.button.is-info.is-inverted:hover{background-color:#f2f2f2}.button.is-info.is-inverted[disabled],fieldset[disabled] .button.is-info.is-inverted{background-color:#fff;border-color:transparent;box-shadow:none;color:#3298dc}.button.is-info.is-loading::after{border-color:transparent transparent #fff #fff!important}.button.is-info.is-outlined{background-color:transparent;border-color:#3298dc;color:#3298dc}.button.is-info.is-outlined.is-focused,.button.is-info.is-outlined.is-hovered,.button.is-info.is-outlined:focus,.button.is-info.is-outlined:hover{background-color:#3298dc;border-color:#3298dc;color:#fff}.button.is-info.is-outlined.is-loading::after{border-color:transparent transparent #3298dc #3298dc!important}.button.is-info.is-outlined.is-loading.is-focused::after,.button.is-info.is-outlined.is-loading.is-hovered::after,.button.is-info.is-outlined.is-loading:focus::after,.button.is-info.is-outlined.is-loading:hover::after{border-color:transparent transparent #fff #fff!important}.button.is-info.is-outlined[disabled],fieldset[disabled] .button.is-info.is-outlined{background-color:transparent;border-color:#3298dc;box-shadow:none;color:#3298dc}.button.is-info.is-inverted.is-outlined{background-color:transparent;border-color:#fff;color:#fff}.button.is-info.is-inverted.is-outlined.is-focused,.button.is-info.is-inverted.is-outlined.is-hovered,.button.is-info.is-inverted.is-outlined:focus,.button.is-info.is-inverted.is-outlined:hover{background-color:#fff;color:#3298dc}.button.is-info.is-inverted.is-outlined.is-loading.is-focused::after,.button.is-info.is-inverted.is-outlined.is-loading.is-hovered::after,.button.is-info.is-inverted.is-outlined.is-loading:focus::after,.button.is-info.is-inverted.is-outlined.is-loading:hover::after{border-color:transparent transparent #3298dc #3298dc!important}.button.is-info.is-inverted.is-outlined[disabled],fieldset[disabled] .button.is-info.is-inverted.is-outlined{background-color:transparent;border-color:#fff;box-shadow:none;color:#fff}.button.is-info.is-light{background-color:#eef6fc;color:#1d72aa}.button.is-info.is-light.is-hovered,.button.is-info.is-light:hover{background-color:#e3f1fa;border-color:transparent;color:#1d72aa}.button.is-info.is-light.is-active,.button.is-info.is-light:active{background-color:#d8ebf8;border-color:transparent;color:#1d72aa}.button.is-success{background-color:#48c774;border-color:transparent;color:#fff}.button.is-success.is-hovered,.button.is-success:hover{background-color:#3ec46d;border-color:transparent;color:#fff}.button.is-success.is-focused,.button.is-success:focus{border-color:transparent;color:#fff}.button.is-success.is-focused:not(:active),.button.is-success:focus:not(:active){box-shadow:0 0 0 .125em rgba(72,199,116,.25)}.button.is-success.is-active,.button.is-success:active{background-color:#3abb67;border-color:transparent;color:#fff}.button.is-success[disabled],fieldset[disabled] .button.is-success{background-color:#48c774;border-color:transparent;box-shadow:none}.button.is-success.is-inverted{background-color:#fff;color:#48c774}.button.is-success.is-inverted.is-hovered,.button.is-success.is-inverted:hover{background-color:#f2f2f2}.button.is-success.is-inverted[disabled],fieldset[disabled] .button.is-success.is-inverted{background-color:#fff;border-color:transparent;box-shadow:none;color:#48c774}.button.is-success.is-loading::after{border-color:transparent transparent #fff #fff!important}.button.is-success.is-outlined{background-color:transparent;border-color:#48c774;color:#48c774}.button.is-success.is-outlined.is-focused,.button.is-success.is-outlined.is-hovered,.button.is-success.is-outlined:focus,.button.is-success.is-outlined:hover{background-color:#48c774;border-color:#48c774;color:#fff}.button.is-success.is-outlined.is-loading::after{border-color:transparent transparent #48c774 #48c774!important}.button.is-success.is-outlined.is-loading.is-focused::after,.button.is-success.is-outlined.is-loading.is-hovered::after,.button.is-success.is-outlined.is-loading:focus::after,.button.is-success.is-outlined.is-loading:hover::after{border-color:transparent transparent #fff #fff!important}.button.is-success.is-outlined[disabled],fieldset[disabled] .button.is-success.is-outlined{background-color:transparent;border-color:#48c774;box-shadow:none;color:#48c774}.button.is-success.is-inverted.is-outlined{background-color:transparent;border-color:#fff;color:#fff}.button.is-success.is-inverted.is-outlined.is-focused,.button.is-success.is-inverted.is-outlined.is-hovered,.button.is-success.is-inverted.is-outlined:focus,.button.is-success.is-inverted.is-outlined:hover{background-color:#fff;color:#48c774}.button.is-success.is-inverted.is-outlined.is-loading.is-focused::after,.button.is-success.is-inverted.is-outlined.is-loading.is-hovered::after,.button.is-success.is-inverted.is-outlined.is-loading:focus::after,.button.is-success.is-inverted.is-outlined.is-loading:hover::after{border-color:transparent transparent #48c774 #48c774!important}.button.is-success.is-inverted.is-outlined[disabled],fieldset[disabled] .button.is-success.is-inverted.is-outlined{background-color:transparent;border-color:#fff;box-shadow:none;color:#fff}.button.is-success.is-light{background-color:#effaf3;color:#257942}.button.is-success.is-light.is-hovered,.button.is-success.is-light:hover{background-color:#e6f7ec;border-color:transparent;color:#257942}.button.is-success.is-light.is-active,.button.is-success.is-light:active{background-color:#dcf4e4;border-color:transparent;color:#257942}.button.is-warning{background-color:#ffdd57;border-color:transparent;color:rgba(0,0,0,.7)}.button.is-warning.is-hovered,.button.is-warning:hover{background-color:#ffdb4a;border-color:transparent;color:rgba(0,0,0,.7)}.button.is-warning.is-focused,.button.is-warning:focus{border-color:transparent;color:rgba(0,0,0,.7)}.button.is-warning.is-focused:not(:active),.button.is-warning:focus:not(:active){box-shadow:0 0 0 .125em rgba(255,221,87,.25)}.button.is-warning.is-active,.button.is-warning:active{background-color:#ffd83d;border-color:transparent;color:rgba(0,0,0,.7)}.button.is-warning[disabled],fieldset[disabled] .button.is-warning{background-color:#ffdd57;border-color:transparent;box-shadow:none}.button.is-warning.is-inverted{background-color:rgba(0,0,0,.7);color:#ffdd57}.button.is-warning.is-inverted.is-hovered,.button.is-warning.is-inverted:hover{background-color:rgba(0,0,0,.7)}.button.is-warning.is-inverted[disabled],fieldset[disabled] .button.is-warning.is-inverted{background-color:rgba(0,0,0,.7);border-color:transparent;box-shadow:none;color:#ffdd57}.button.is-warning.is-loading::after{border-color:transparent transparent rgba(0,0,0,.7) rgba(0,0,0,.7)!important}.button.is-warning.is-outlined{background-color:transparent;border-color:#ffdd57;color:#ffdd57}.button.is-warning.is-outlined.is-focused,.button.is-warning.is-outlined.is-hovered,.button.is-warning.is-outlined:focus,.button.is-warning.is-outlined:hover{background-color:#ffdd57;border-color:#ffdd57;color:rgba(0,0,0,.7)}.button.is-warning.is-outlined.is-loading::after{border-color:transparent transparent #ffdd57 #ffdd57!important}.button.is-warning.is-outlined.is-loading.is-focused::after,.button.is-warning.is-outlined.is-loading.is-hovered::after,.button.is-warning.is-outlined.is-loading:focus::after,.button.is-warning.is-outlined.is-loading:hover::after{border-color:transparent transparent rgba(0,0,0,.7) rgba(0,0,0,.7)!important}.button.is-warning.is-outlined[disabled],fieldset[disabled] .button.is-warning.is-outlined{background-color:transparent;border-color:#ffdd57;box-shadow:none;color:#ffdd57}.button.is-warning.is-inverted.is-outlined{background-color:transparent;border-color:rgba(0,0,0,.7);color:rgba(0,0,0,.7)}.button.is-warning.is-inverted.is-outlined.is-focused,.button.is-warning.is-inverted.is-outlined.is-hovered,.button.is-warning.is-inverted.is-outlined:focus,.button.is-warning.is-inverted.is-outlined:hover{background-color:rgba(0,0,0,.7);color:#ffdd57}.button.is-warning.is-inverted.is-outlined.is-loading.is-focused::after,.button.is-warning.is-inverted.is-outlined.is-loading.is-hovered::after,.button.is-warning.is-inverted.is-outlined.is-loading:focus::after,.button.is-warning.is-inverted.is-outlined.is-loading:hover::after{border-color:transparent transparent #ffdd57 #ffdd57!important}.button.is-warning.is-inverted.is-outlined[disabled],fieldset[disabled] .button.is-warning.is-inverted.is-outlined{background-color:transparent;border-color:rgba(0,0,0,.7);box-shadow:none;color:rgba(0,0,0,.7)}.button.is-warning.is-light{background-color:#fffbeb;color:#947600}.button.is-warning.is-light.is-hovered,.button.is-warning.is-light:hover{background-color:#fff8de;border-color:transparent;color:#947600}.button.is-warning.is-light.is-active,.button.is-warning.is-light:active{background-color:#fff6d1;border-color:transparent;color:#947600}.button.is-danger{background-color:#f14668;border-color:transparent;color:#fff}.button.is-danger.is-hovered,.button.is-danger:hover{background-color:#f03a5f;border-color:transparent;color:#fff}.button.is-danger.is-focused,.button.is-danger:focus{border-color:transparent;color:#fff}.button.is-danger.is-focused:not(:active),.button.is-danger:focus:not(:active){box-shadow:0 0 0 .125em rgba(241,70,104,.25)}.button.is-danger.is-active,.button.is-danger:active{background-color:#ef2e55;border-color:transparent;color:#fff}.button.is-danger[disabled],fieldset[disabled] .button.is-danger{background-color:#f14668;border-color:transparent;box-shadow:none}.button.is-danger.is-inverted{background-color:#fff;color:#f14668}.button.is-danger.is-inverted.is-hovered,.button.is-danger.is-inverted:hover{background-color:#f2f2f2}.button.is-danger.is-inverted[disabled],fieldset[disabled] .button.is-danger.is-inverted{background-color:#fff;border-color:transparent;box-shadow:none;color:#f14668}.button.is-danger.is-loading::after{border-color:transparent transparent #fff #fff!important}.button.is-danger.is-outlined{background-color:transparent;border-color:#f14668;color:#f14668}.button.is-danger.is-outlined.is-focused,.button.is-danger.is-outlined.is-hovered,.button.is-danger.is-outlined:focus,.button.is-danger.is-outlined:hover{background-color:#f14668;border-color:#f14668;color:#fff}.button.is-danger.is-outlined.is-loading::after{border-color:transparent transparent #f14668 #f14668!important}.button.is-danger.is-outlined.is-loading.is-focused::after,.button.is-danger.is-outlined.is-loading.is-hovered::after,.button.is-danger.is-outlined.is-loading:focus::after,.button.is-danger.is-outlined.is-loading:hover::after{border-color:transparent transparent #fff #fff!important}.button.is-danger.is-outlined[disabled],fieldset[disabled] .button.is-danger.is-outlined{background-color:transparent;border-color:#f14668;box-shadow:none;color:#f14668}.button.is-danger.is-inverted.is-outlined{background-color:transparent;border-color:#fff;color:#fff}.button.is-danger.is-inverted.is-outlined.is-focused,.button.is-danger.is-inverted.is-outlined.is-hovered,.button.is-danger.is-inverted.is-outlined:focus,.button.is-danger.is-inverted.is-outlined:hover{background-color:#fff;color:#f14668}.button.is-danger.is-inverted.is-outlined.is-loading.is-focused::after,.button.is-danger.is-inverted.is-outlined.is-loading.is-hovered::after,.button.is-danger.is-inverted.is-outlined.is-loading:focus::after,.button.is-danger.is-inverted.is-outlined.is-loading:hover::after{border-color:transparent transparent #f14668 #f14668!important}.button.is-danger.is-inverted.is-outlined[disabled],fieldset[disabled] .button.is-danger.is-inverted.is-outlined{background-color:transparent;border-color:#fff;box-shadow:none;color:#fff}.button.is-danger.is-light{background-color:#feecf0;color:#cc0f35}.button.is-danger.is-light.is-hovered,.button.is-danger.is-light:hover{background-color:#fde0e6;border-color:transparent;color:#cc0f35}.button.is-danger.is-light.is-active,.button.is-danger.is-light:active{background-color:#fcd4dc;border-color:transparent;color:#cc0f35}.button.is-small{border-radius:2px;font-size:.75rem}.button.is-normal{font-size:1rem}.button.is-medium{font-size:1.25rem}.button.is-large{font-size:1.5rem}.button[disabled],fieldset[disabled] .button{background-color:#fff;border-color:#dbdbdb;box-shadow:none;opacity:.5}.button.is-fullwidth{display:flex;width:100%}.button.is-loading{color:transparent!important;pointer-events:none}.button.is-loading::after{position:absolute;left:calc(50% - (1em / 2));top:calc(50% - (1em / 2));position:absolute!important}.button.is-static{background-color:#f5f5f5;border-color:#dbdbdb;color:#7a7a7a;box-shadow:none;pointer-events:none}.button.is-rounded{border-radius:290486px;padding-left:calc(1em + .25em);padding-right:calc(1em + .25em)}.buttons{align-items:center;display:flex;flex-wrap:wrap;justify-content:flex-start}.buttons .button{margin-bottom:.5rem}.buttons .button:not(:last-child):not(.is-fullwidth){margin-right:.5rem}.buttons:last-child{margin-bottom:-.5rem}.buttons:not(:last-child){margin-bottom:1rem}.buttons.are-small .button:not(.is-normal):not(.is-medium):not(.is-large){border-radius:2px;font-size:.75rem}.buttons.are-medium .button:not(.is-small):not(.is-normal):not(.is-large){font-size:1.25rem}.buttons.are-large .button:not(.is-small):not(.is-normal):not(.is-medium){font-size:1.5rem}.buttons.has-addons .button:not(:first-child){border-bottom-left-radius:0;border-top-left-radius:0}.buttons.has-addons .button:not(:last-child){border-bottom-right-radius:0;border-top-right-radius:0;margin-right:-1px}.buttons.has-addons .button:last-child{margin-right:0}.buttons.has-addons .button.is-hovered,.buttons.has-addons .button:hover{z-index:2}.buttons.has-addons .button.is-active,.buttons.has-addons .button.is-focused,.buttons.has-addons .button.is-selected,.buttons.has-addons .button:active,.buttons.has-addons .button:focus{z-index:3}.buttons.has-addons .button.is-active:hover,.buttons.has-addons .button.is-focused:hover,.buttons.has-addons .button.is-selected:hover,.buttons.has-addons .button:active:hover,.buttons.has-addons .button:focus:hover{z-index:4}.buttons.has-addons .button.is-expanded{flex-grow:1;flex-shrink:1}.buttons.is-centered{justify-content:center}.buttons.is-centered:not(.has-addons) .button:not(.is-fullwidth){margin-left:.25rem;margin-right:.25rem}.buttons.is-right{justify-content:flex-end}.buttons.is-right:not(.has-addons) .button:not(.is-fullwidth){margin-left:.25rem;margin-right:.25rem}.container{flex-grow:1;margin:0 auto;position:relative;width:auto}.container.is-fluid{max-width:none!important;padding-left:32px;padding-right:32px;width:100%}@media screen and (min-width:1024px){.container{max-width:960px}}@media screen and (max-width:1215px){.container.is-widescreen:not(.is-max-desktop){max-width:1152px}}@media screen and (max-width:1407px){.container.is-fullhd:not(.is-max-desktop):not(.is-max-widescreen){max-width:1344px}}@media screen and (min-width:1216px){.container:not(.is-max-desktop){max-width:1152px}}@media screen and (min-width:1408px){.container:not(.is-max-desktop):not(.is-max-widescreen){max-width:1344px}}.content li+li{margin-top:.25em}.content blockquote:not(:last-child),.content dl:not(:last-child),.content ol:not(:last-child),.content p:not(:last-child),.content pre:not(:last-child),.content table:not(:last-child),.content ul:not(:last-child){margin-bottom:1em}.content h1,.content h2,.content h3,.content h4,.content h5,.content h6{color:#363636;font-weight:600;line-height:1.125}.content h1{font-size:2em;margin-bottom:.5em}.content h1:not(:first-child){margin-top:1em}.content h2{font-size:1.75em;margin-bottom:.5714em}.content h2:not(:first-child){margin-top:1.1428em}.content h3{font-size:1.5em;margin-bottom:.6666em}.content h3:not(:first-child){margin-top:1.3333em}.content h4{font-size:1.25em;margin-bottom:.8em}.content h5{font-size:1.125em;margin-bottom:.8888em}.content h6{font-size:1em;margin-bottom:1em}.content blockquote{background-color:#f5f5f5;border-left:5px solid #dbdbdb;padding:1.25em 1.5em}.content ol{list-style-position:outside;margin-left:2em;margin-top:1em}.content ol:not([type]){list-style-type:decimal}.content ol:not([type]).is-lower-alpha{list-style-type:lower-alpha}.content ol:not([type]).is-lower-roman{list-style-type:lower-roman}.content ol:not([type]).is-upper-alpha{list-style-type:upper-alpha}.content ol:not([type]).is-upper-roman{list-style-type:upper-roman}.content ul{list-style:disc outside;margin-left:2em;margin-top:1em}.content ul ul{list-style-type:circle;margin-top:.5em}.content ul ul ul{list-style-type:square}.content dd{margin-left:2em}.content figure{margin-left:2em;margin-right:2em;text-align:center}.content figure:not(:first-child){margin-top:2em}.content figure:not(:last-child){margin-bottom:2em}.content figure img{display:inline-block}.content figure figcaption{font-style:italic}.content pre{-webkit-overflow-scrolling:touch;overflow-x:auto;padding:1.25em 1.5em;white-space:pre;word-wrap:normal}.content sub,.content sup{font-size:75%}.content table{width:100%}.content table td,.content table th{border:1px solid #dbdbdb;border-width:0 0 1px;padding:.5em .75em;vertical-align:top}.content table th{color:#363636}.content table th:not([align]){text-align:inherit}.content table thead td,.content table thead th{border-width:0 0 2px;color:#363636}.content table tfoot td,.content table tfoot th{border-width:2px 0 0;color:#363636}.content table tbody tr:last-child td,.content table tbody tr:last-child th{border-bottom-width:0}.content .tabs li+li{margin-top:0}.content.is-small{font-size:.75rem}.content.is-medium{font-size:1.25rem}.content.is-large{font-size:1.5rem}.icon{align-items:center;display:inline-flex;justify-content:center;height:1.5rem;width:1.5rem}.icon.is-small{height:1rem;width:1rem}.icon.is-medium{height:2rem;width:2rem}.icon.is-large{height:3rem;width:3rem}.image{display:block;position:relative}.image img{display:block;height:auto;width:100%}.image img.is-rounded{border-radius:290486px}.image.is-fullwidth{width:100%}.image.is-16by9 .has-ratio,.image.is-16by9 img,.image.is-1by1 .has-ratio,.image.is-1by1 img,.image.is-1by2 .has-ratio,.image.is-1by2 img,.image.is-1by3 .has-ratio,.image.is-1by3 img,.image.is-2by1 .has-ratio,.image.is-2by1 img,.image.is-2by3 .has-ratio,.image.is-2by3 img,.image.is-3by1 .has-ratio,.image.is-3by1 img,.image.is-3by2 .has-ratio,.image.is-3by2 img,.image.is-3by4 .has-ratio,.image.is-3by4 img,.image.is-3by5 .has-ratio,.image.is-3by5 img,.image.is-4by3 .has-ratio,.image.is-4by3 img,.image.is-4by5 .has-ratio,.image.is-4by5 img,.image.is-5by3 .has-ratio,.image.is-5by3 img,.image.is-5by4 .has-ratio,.image.is-5by4 img,.image.is-9by16 .has-ratio,.image.is-9by16 img,.image.is-square .has-ratio,.image.is-square img{height:100%;width:100%}.image.is-1by1,.image.is-square{padding-top:100%}.image.is-5by4{padding-top:80%}.image.is-4by3{padding-top:75%}.image.is-3by2{padding-top:66.6666%}.image.is-5by3{padding-top:60%}.image.is-16by9{padding-top:56.25%}.image.is-2by1{padding-top:50%}.image.is-3by1{padding-top:33.3333%}.image.is-4by5{padding-top:125%}.image.is-3by4{padding-top:133.3333%}.image.is-2by3{padding-top:150%}.image.is-3by5{padding-top:166.6666%}.image.is-9by16{padding-top:177.7777%}.image.is-1by2{padding-top:200%}.image.is-1by3{padding-top:300%}.image.is-16x16{height:16px;width:16px}.image.is-24x24{height:24px;width:24px}.image.is-32x32{height:32px;width:32px}.image.is-48x48{height:48px;width:48px}.image.is-64x64{height:64px;width:64px}.image.is-96x96{height:96px;width:96px}.image.is-128x128{height:128px;width:128px}.notification{background-color:#f5f5f5;border-radius:4px;position:relative;padding:1.25rem 2.5rem 1.25rem 1.5rem}.notification a:not(.button):not(.dropdown-item){color:currentColor;text-decoration:underline}.notification strong{color:currentColor}.notification code,.notification pre{background:#fff}.notification pre code{background:0 0}.notification>.delete{right:.5rem;position:absolute;top:.5rem}.notification .content,.notification .subtitle,.notification .title{color:currentColor}.notification.is-white{background-color:#fff;color:#0a0a0a}.notification.is-black{background-color:#0a0a0a;color:#fff}.notification.is-light{background-color:#f5f5f5;color:rgba(0,0,0,.7)}.notification.is-dark{background-color:#363636;color:#fff}.notification.is-primary{background-color:#00d1b2;color:#fff}.notification.is-primary.is-light{background-color:#ebfffc;color:#00947e}.notification.is-link{background-color:#3273dc;color:#fff}.notification.is-link.is-light{background-color:#eef3fc;color:#2160c4}.notification.is-info{background-color:#3298dc;color:#fff}.notification.is-info.is-light{background-color:#eef6fc;color:#1d72aa}.notification.is-success{background-color:#48c774;color:#fff}.notification.is-success.is-light{background-color:#effaf3;color:#257942}.notification.is-warning{background-color:#ffdd57;color:rgba(0,0,0,.7)}.notification.is-warning.is-light{background-color:#fffbeb;color:#947600}.notification.is-danger{background-color:#f14668;color:#fff}.notification.is-danger.is-light{background-color:#feecf0;color:#cc0f35}.progress{-moz-appearance:none;-webkit-appearance:none;border:none;border-radius:290486px;display:block;height:1rem;overflow:hidden;padding:0;width:100%}.progress::-webkit-progress-bar{background-color:#ededed}.progress::-webkit-progress-value{background-color:#4a4a4a}.progress::-moz-progress-bar{background-color:#4a4a4a}.progress::-ms-fill{background-color:#4a4a4a;border:none}.progress.is-white::-webkit-progress-value{background-color:#fff}.progress.is-white::-moz-progress-bar{background-color:#fff}.progress.is-white::-ms-fill{background-color:#fff}.progress.is-white:indeterminate{background-image:linear-gradient(to right,#fff 30%,#ededed 30%)}.progress.is-black::-webkit-progress-value{background-color:#0a0a0a}.progress.is-black::-moz-progress-bar{background-color:#0a0a0a}.progress.is-black::-ms-fill{background-color:#0a0a0a}.progress.is-black:indeterminate{background-image:linear-gradient(to right,#0a0a0a 30%,#ededed 30%)}.progress.is-light::-webkit-progress-value{background-color:#f5f5f5}.progress.is-light::-moz-progress-bar{background-color:#f5f5f5}.progress.is-light::-ms-fill{background-color:#f5f5f5}.progress.is-light:indeterminate{background-image:linear-gradient(to right,#f5f5f5 30%,#ededed 30%)}.progress.is-dark::-webkit-progress-value{background-color:#363636}.progress.is-dark::-moz-progress-bar{background-color:#363636}.progress.is-dark::-ms-fill{background-color:#363636}.progress.is-dark:indeterminate{background-image:linear-gradient(to right,#363636 30%,#ededed 30%)}.progress.is-primary::-webkit-progress-value{background-color:#00d1b2}.progress.is-primary::-moz-progress-bar{background-color:#00d1b2}.progress.is-primary::-ms-fill{background-color:#00d1b2}.progress.is-primary:indeterminate{background-image:linear-gradient(to right,#00d1b2 30%,#ededed 30%)}.progress.is-link::-webkit-progress-value{background-color:#3273dc}.progress.is-link::-moz-progress-bar{background-color:#3273dc}.progress.is-link::-ms-fill{background-color:#3273dc}.progress.is-link:indeterminate{background-image:linear-gradient(to right,#3273dc 30%,#ededed 30%)}.progress.is-info::-webkit-progress-value{background-color:#3298dc}.progress.is-info::-moz-progress-bar{background-color:#3298dc}.progress.is-info::-ms-fill{background-color:#3298dc}.progress.is-info:indeterminate{background-image:linear-gradient(to right,#3298dc 30%,#ededed 30%)}.progress.is-success::-webkit-progress-value{background-color:#48c774}.progress.is-success::-moz-progress-bar{background-color:#48c774}.progress.is-success::-ms-fill{background-color:#48c774}.progress.is-success:indeterminate{background-image:linear-gradient(to right,#48c774 30%,#ededed 30%)}.progress.is-warning::-webkit-progress-value{background-color:#ffdd57}.progress.is-warning::-moz-progress-bar{background-color:#ffdd57}.progress.is-warning::-ms-fill{background-color:#ffdd57}.progress.is-warning:indeterminate{background-image:linear-gradient(to right,#ffdd57 30%,#ededed 30%)}.progress.is-danger::-webkit-progress-value{background-color:#f14668}.progress.is-danger::-moz-progress-bar{background-color:#f14668}.progress.is-danger::-ms-fill{background-color:#f14668}.progress.is-danger:indeterminate{background-image:linear-gradient(to right,#f14668 30%,#ededed 30%)}.progress:indeterminate{-webkit-animation-duration:1.5s;animation-duration:1.5s;-webkit-animation-iteration-count:infinite;animation-iteration-count:infinite;-webkit-animation-name:moveIndeterminate;animation-name:moveIndeterminate;-webkit-animation-timing-function:linear;animation-timing-function:linear;background-color:#ededed;background-image:linear-gradient(to right,#4a4a4a 30%,#ededed 30%);background-position:top left;background-repeat:no-repeat;background-size:150% 150%}.progress:indeterminate::-webkit-progress-bar{background-color:transparent}.progress:indeterminate::-moz-progress-bar{background-color:transparent}.progress:indeterminate::-ms-fill{animation-name:none}.progress.is-small{height:.75rem}.progress.is-medium{height:1.25rem}.progress.is-large{height:1.5rem}@-webkit-keyframes moveIndeterminate{from{background-position:200% 0}to{background-position:-200% 0}}@keyframes moveIndeterminate{from{background-position:200% 0}to{background-position:-200% 0}}.table{background-color:#fff;color:#363636}.table td,.table th{border:1px solid #dbdbdb;border-width:0 0 1px;padding:.5em .75em;vertical-align:top}.table td.is-white,.table th.is-white{background-color:#fff;border-color:#fff;color:#0a0a0a}.table td.is-black,.table th.is-black{background-color:#0a0a0a;border-color:#0a0a0a;color:#fff}.table td.is-light,.table th.is-light{background-color:#f5f5f5;border-color:#f5f5f5;color:rgba(0,0,0,.7)}.table td.is-dark,.table th.is-dark{background-color:#363636;border-color:#363636;color:#fff}.table td.is-primary,.table th.is-primary{background-color:#00d1b2;border-color:#00d1b2;color:#fff}.table td.is-link,.table th.is-link{background-color:#3273dc;border-color:#3273dc;color:#fff}.table td.is-info,.table th.is-info{background-color:#3298dc;border-color:#3298dc;color:#fff}.table td.is-success,.table th.is-success{background-color:#48c774;border-color:#48c774;color:#fff}.table td.is-warning,.table th.is-warning{background-color:#ffdd57;border-color:#ffdd57;color:rgba(0,0,0,.7)}.table td.is-danger,.table th.is-danger{background-color:#f14668;border-color:#f14668;color:#fff}.table td.is-narrow,.table th.is-narrow{white-space:nowrap;width:1%}.table td.is-selected,.table th.is-selected{background-color:#00d1b2;color:#fff}.table td.is-selected a,.table td.is-selected strong,.table th.is-selected a,.table th.is-selected strong{color:currentColor}.table td.is-vcentered,.table th.is-vcentered{vertical-align:middle}.table th{color:#363636}.table th:not([align]){text-align:inherit}.table tr.is-selected{background-color:#00d1b2;color:#fff}.table tr.is-selected a,.table tr.is-selected strong{color:currentColor}.table tr.is-selected td,.table tr.is-selected th{border-color:#fff;color:currentColor}.table thead{background-color:transparent}.table thead td,.table thead th{border-width:0 0 2px;color:#363636}.table tfoot{background-color:transparent}.table tfoot td,.table tfoot th{border-width:2px 0 0;color:#363636}.table tbody{background-color:transparent}.table tbody tr:last-child td,.table tbody tr:last-child th{border-bottom-width:0}.table.is-bordered td,.table.is-bordered th{border-width:1px}.table.is-bordered tr:last-child td,.table.is-bordered tr:last-child th{border-bottom-width:1px}.table.is-fullwidth{width:100%}.table.is-hoverable tbody tr:not(.is-selected):hover{background-color:#fafafa}.table.is-hoverable.is-striped tbody tr:not(.is-selected):hover{background-color:#fafafa}.table.is-hoverable.is-striped tbody tr:not(.is-selected):hover:nth-child(even){background-color:#f5f5f5}.table.is-narrow td,.table.is-narrow th{padding:.25em .5em}.table.is-striped tbody tr:not(.is-selected):nth-child(even){background-color:#fafafa}.table-container{-webkit-overflow-scrolling:touch;overflow:auto;overflow-y:hidden;max-width:100%}.tags{align-items:center;display:flex;flex-wrap:wrap;justify-content:flex-start}.tags .tag{margin-bottom:.5rem}.tags .tag:not(:last-child){margin-right:.5rem}.tags:last-child{margin-bottom:-.5rem}.tags:not(:last-child){margin-bottom:1rem}.tags.are-medium .tag:not(.is-normal):not(.is-large){font-size:1rem}.tags.are-large .tag:not(.is-normal):not(.is-medium){font-size:1.25rem}.tags.is-centered{justify-content:center}.tags.is-centered .tag{margin-right:.25rem;margin-left:.25rem}.tags.is-right{justify-content:flex-end}.tags.is-right .tag:not(:first-child){margin-left:.5rem}.tags.is-right .tag:not(:last-child){margin-right:0}.tags.has-addons .tag{margin-right:0}.tags.has-addons .tag:not(:first-child){margin-left:0;border-top-left-radius:0;border-bottom-left-radius:0}.tags.has-addons .tag:not(:last-child){border-top-right-radius:0;border-bottom-right-radius:0}.tag:not(body){align-items:center;background-color:#f5f5f5;border-radius:4px;color:#4a4a4a;display:inline-flex;font-size:.75rem;height:2em;justify-content:center;line-height:1.5;padding-left:.75em;padding-right:.75em;white-space:nowrap}.tag:not(body) .delete{margin-left:.25rem;margin-right:-.375rem}.tag:not(body).is-white{background-color:#fff;color:#0a0a0a}.tag:not(body).is-black{background-color:#0a0a0a;color:#fff}.tag:not(body).is-light{background-color:#f5f5f5;color:rgba(0,0,0,.7)}.tag:not(body).is-dark{background-color:#363636;color:#fff}.tag:not(body).is-primary{background-color:#00d1b2;color:#fff}.tag:not(body).is-primary.is-light{background-color:#ebfffc;color:#00947e}.tag:not(body).is-link{background-color:#3273dc;color:#fff}.tag:not(body).is-link.is-light{background-color:#eef3fc;color:#2160c4}.tag:not(body).is-info{background-color:#3298dc;color:#fff}.tag:not(body).is-info.is-light{background-color:#eef6fc;color:#1d72aa}.tag:not(body).is-success{background-color:#48c774;color:#fff}.tag:not(body).is-success.is-light{background-color:#effaf3;color:#257942}.tag:not(body).is-warning{background-color:#ffdd57;color:rgba(0,0,0,.7)}.tag:not(body).is-warning.is-light{background-color:#fffbeb;color:#947600}.tag:not(body).is-danger{background-color:#f14668;color:#fff}.tag:not(body).is-danger.is-light{background-color:#feecf0;color:#cc0f35}.tag:not(body).is-normal{font-size:.75rem}.tag:not(body).is-medium{font-size:1rem}.tag:not(body).is-large{font-size:1.25rem}.tag:not(body) .icon:first-child:not(:last-child){margin-left:-.375em;margin-right:.1875em}.tag:not(body) .icon:last-child:not(:first-child){margin-left:.1875em;margin-right:-.375em}.tag:not(body) .icon:first-child:last-child{margin-left:-.375em;margin-right:-.375em}.tag:not(body).is-delete{margin-left:1px;padding:0;position:relative;width:2em}.tag:not(body).is-delete::after,.tag:not(body).is-delete::before{background-color:currentColor;content:"";display:block;left:50%;position:absolute;top:50%;transform:translateX(-50%) translateY(-50%) rotate(45deg);transform-origin:center center}.tag:not(body).is-delete::before{height:1px;width:50%}.tag:not(body).is-delete::after{height:50%;width:1px}.tag:not(body).is-delete:focus,.tag:not(body).is-delete:hover{background-color:#e8e8e8}.tag:not(body).is-delete:active{background-color:#dbdbdb}.tag:not(body).is-rounded{border-radius:290486px}a.tag:hover{text-decoration:underline}.subtitle,.title{word-break:break-word}.subtitle em,.subtitle span,.title em,.title span{font-weight:inherit}.subtitle sub,.title sub{font-size:.75em}.subtitle sup,.title sup{font-size:.75em}.subtitle .tag,.title .tag{vertical-align:middle}.title{color:#363636;font-size:2rem;font-weight:600;line-height:1.125}.title strong{color:inherit;font-weight:inherit}.title+.highlight{margin-top:-.75rem}.title:not(.is-spaced)+.subtitle{margin-top:-1.25rem}.title.is-1{font-size:3rem}.title.is-2{font-size:2.5rem}.title.is-3{font-size:2rem}.title.is-4{font-size:1.5rem}.title.is-5{font-size:1.25rem}.title.is-6{font-size:1rem}.title.is-7{font-size:.75rem}.subtitle{color:#4a4a4a;font-size:1.25rem;font-weight:400;line-height:1.25}.subtitle strong{color:#363636;font-weight:600}.subtitle:not(.is-spaced)+.title{margin-top:-1.25rem}.subtitle.is-1{font-size:3rem}.subtitle.is-2{font-size:2.5rem}.subtitle.is-3{font-size:2rem}.subtitle.is-4{font-size:1.5rem}.subtitle.is-5{font-size:1.25rem}.subtitle.is-6{font-size:1rem}.subtitle.is-7{font-size:.75rem}.heading{display:block;font-size:11px;letter-spacing:1px;margin-bottom:5px;text-transform:uppercase}.highlight{font-weight:400;max-width:100%;overflow:hidden;padding:0}.highlight pre{overflow:auto;max-width:100%}.number{align-items:center;background-color:#f5f5f5;border-radius:290486px;display:inline-flex;font-size:1.25rem;height:2em;justify-content:center;margin-right:1.5rem;min-width:2.5em;padding:.25rem .5rem;text-align:center;vertical-align:top}.input,.select select,.textarea{background-color:#fff;border-color:#dbdbdb;border-radius:4px;color:#363636}.input::-moz-placeholder,.select select::-moz-placeholder,.textarea::-moz-placeholder{color:rgba(54,54,54,.3)}.input::-webkit-input-placeholder,.select select::-webkit-input-placeholder,.textarea::-webkit-input-placeholder{color:rgba(54,54,54,.3)}.input:-moz-placeholder,.select select:-moz-placeholder,.textarea:-moz-placeholder{color:rgba(54,54,54,.3)}.input:-ms-input-placeholder,.select select:-ms-input-placeholder,.textarea:-ms-input-placeholder{color:rgba(54,54,54,.3)}.input:hover,.is-hovered.input,.is-hovered.textarea,.select select.is-hovered,.select select:hover,.textarea:hover{border-color:#b5b5b5}.input:active,.input:focus,.is-active.input,.is-active.textarea,.is-focused.input,.is-focused.textarea,.select select.is-active,.select select.is-focused,.select select:active,.select select:focus,.textarea:active,.textarea:focus{border-color:#3273dc;box-shadow:0 0 0 .125em rgba(50,115,220,.25)}.input[disabled],.select fieldset[disabled] select,.select select[disabled],.textarea[disabled],fieldset[disabled] .input,fieldset[disabled] .select select,fieldset[disabled] .textarea{background-color:#f5f5f5;border-color:#f5f5f5;box-shadow:none;color:#7a7a7a}.input[disabled]::-moz-placeholder,.select fieldset[disabled] select::-moz-placeholder,.select select[disabled]::-moz-placeholder,.textarea[disabled]::-moz-placeholder,fieldset[disabled] .input::-moz-placeholder,fieldset[disabled] .select select::-moz-placeholder,fieldset[disabled] .textarea::-moz-placeholder{color:rgba(122,122,122,.3)}.input[disabled]::-webkit-input-placeholder,.select fieldset[disabled] select::-webkit-input-placeholder,.select select[disabled]::-webkit-input-placeholder,.textarea[disabled]::-webkit-input-placeholder,fieldset[disabled] .input::-webkit-input-placeholder,fieldset[disabled] .select select::-webkit-input-placeholder,fieldset[disabled] .textarea::-webkit-input-placeholder{color:rgba(122,122,122,.3)}.input[disabled]:-moz-placeholder,.select fieldset[disabled] select:-moz-placeholder,.select select[disabled]:-moz-placeholder,.textarea[disabled]:-moz-placeholder,fieldset[disabled] .input:-moz-placeholder,fieldset[disabled] .select select:-moz-placeholder,fieldset[disabled] .textarea:-moz-placeholder{color:rgba(122,122,122,.3)}.input[disabled]:-ms-input-placeholder,.select fieldset[disabled] select:-ms-input-placeholder,.select select[disabled]:-ms-input-placeholder,.textarea[disabled]:-ms-input-placeholder,fieldset[disabled] .input:-ms-input-placeholder,fieldset[disabled] .select select:-ms-input-placeholder,fieldset[disabled] .textarea:-ms-input-placeholder{color:rgba(122,122,122,.3)}.input,.textarea{box-shadow:inset 0 .0625em .125em rgba(10,10,10,.05);max-width:100%;width:100%}.input[readonly],.textarea[readonly]{box-shadow:none}.is-white.input,.is-white.textarea{border-color:#fff}.is-white.input:active,.is-white.input:focus,.is-white.is-active.input,.is-white.is-active.textarea,.is-white.is-focused.input,.is-white.is-focused.textarea,.is-white.textarea:active,.is-white.textarea:focus{box-shadow:0 0 0 .125em rgba(255,255,255,.25)}.is-black.input,.is-black.textarea{border-color:#0a0a0a}.is-black.input:active,.is-black.input:focus,.is-black.is-active.input,.is-black.is-active.textarea,.is-black.is-focused.input,.is-black.is-focused.textarea,.is-black.textarea:active,.is-black.textarea:focus{box-shadow:0 0 0 .125em rgba(10,10,10,.25)}.is-light.input,.is-light.textarea{border-color:#f5f5f5}.is-light.input:active,.is-light.input:focus,.is-light.is-active.input,.is-light.is-active.textarea,.is-light.is-focused.input,.is-light.is-focused.textarea,.is-light.textarea:active,.is-light.textarea:focus{box-shadow:0 0 0 .125em rgba(245,245,245,.25)}.is-dark.input,.is-dark.textarea{border-color:#363636}.is-dark.input:active,.is-dark.input:focus,.is-dark.is-active.input,.is-dark.is-active.textarea,.is-dark.is-focused.input,.is-dark.is-focused.textarea,.is-dark.textarea:active,.is-dark.textarea:focus{box-shadow:0 0 0 .125em rgba(54,54,54,.25)}.is-primary.input,.is-primary.textarea{border-color:#00d1b2}.is-primary.input:active,.is-primary.input:focus,.is-primary.is-active.input,.is-primary.is-active.textarea,.is-primary.is-focused.input,.is-primary.is-focused.textarea,.is-primary.textarea:active,.is-primary.textarea:focus{box-shadow:0 0 0 .125em rgba(0,209,178,.25)}.is-link.input,.is-link.textarea{border-color:#3273dc}.is-link.input:active,.is-link.input:focus,.is-link.is-active.input,.is-link.is-active.textarea,.is-link.is-focused.input,.is-link.is-focused.textarea,.is-link.textarea:active,.is-link.textarea:focus{box-shadow:0 0 0 .125em rgba(50,115,220,.25)}.is-info.input,.is-info.textarea{border-color:#3298dc}.is-info.input:active,.is-info.input:focus,.is-info.is-active.input,.is-info.is-active.textarea,.is-info.is-focused.input,.is-info.is-focused.textarea,.is-info.textarea:active,.is-info.textarea:focus{box-shadow:0 0 0 .125em rgba(50,152,220,.25)}.is-success.input,.is-success.textarea{border-color:#48c774}.is-success.input:active,.is-success.input:focus,.is-success.is-active.input,.is-success.is-active.textarea,.is-success.is-focused.input,.is-success.is-focused.textarea,.is-success.textarea:active,.is-success.textarea:focus{box-shadow:0 0 0 .125em rgba(72,199,116,.25)}.is-warning.input,.is-warning.textarea{border-color:#ffdd57}.is-warning.input:active,.is-warning.input:focus,.is-warning.is-active.input,.is-warning.is-active.textarea,.is-warning.is-focused.input,.is-warning.is-focused.textarea,.is-warning.textarea:active,.is-warning.textarea:focus{box-shadow:0 0 0 .125em rgba(255,221,87,.25)}.is-danger.input,.is-danger.textarea{border-color:#f14668}.is-danger.input:active,.is-danger.input:focus,.is-danger.is-active.input,.is-danger.is-active.textarea,.is-danger.is-focused.input,.is-danger.is-focused.textarea,.is-danger.textarea:active,.is-danger.textarea:focus{box-shadow:0 0 0 .125em rgba(241,70,104,.25)}.is-small.input,.is-small.textarea{border-radius:2px;font-size:.75rem}.is-medium.input,.is-medium.textarea{font-size:1.25rem}.is-large.input,.is-large.textarea{font-size:1.5rem}.is-fullwidth.input,.is-fullwidth.textarea{display:block;width:100%}.is-inline.input,.is-inline.textarea{display:inline;width:auto}.input.is-rounded{border-radius:290486px;padding-left:calc(calc(.75em - 1px) + .375em);padding-right:calc(calc(.75em - 1px) + .375em)}.input.is-static{background-color:transparent;border-color:transparent;box-shadow:none;padding-left:0;padding-right:0}.textarea{display:block;max-width:100%;min-width:100%;padding:calc(.75em - 1px);resize:vertical}.textarea:not([rows]){max-height:40em;min-height:8em}.textarea[rows]{height:initial}.textarea.has-fixed-size{resize:none}.checkbox,.radio{cursor:pointer;display:inline-block;line-height:1.25;position:relative}.checkbox input,.radio input{cursor:pointer}.checkbox:hover,.radio:hover{color:#363636}.checkbox input[disabled],.checkbox[disabled],.radio input[disabled],.radio[disabled],fieldset[disabled] .checkbox,fieldset[disabled] .radio{color:#7a7a7a;cursor:not-allowed}.radio+.radio{margin-left:.5em}.select{display:inline-block;max-width:100%;position:relative;vertical-align:top}.select:not(.is-multiple){height:2.5em}.select:not(.is-multiple):not(.is-loading)::after{border-color:#3273dc;right:1.125em;z-index:4}.select.is-rounded select{border-radius:290486px;padding-left:1em}.select select{cursor:pointer;display:block;font-size:1em;max-width:100%;outline:0}.select select::-ms-expand{display:none}.select select[disabled]:hover,fieldset[disabled] .select select:hover{border-color:#f5f5f5}.select select:not([multiple]){padding-right:2.5em}.select select[multiple]{height:auto;padding:0}.select select[multiple] option{padding:.5em 1em}.select:not(.is-multiple):not(.is-loading):hover::after{border-color:#363636}.select.is-white:not(:hover)::after{border-color:#fff}.select.is-white select{border-color:#fff}.select.is-white select.is-hovered,.select.is-white select:hover{border-color:#f2f2f2}.select.is-white select.is-active,.select.is-white select.is-focused,.select.is-white select:active,.select.is-white select:focus{box-shadow:0 0 0 .125em rgba(255,255,255,.25)}.select.is-black:not(:hover)::after{border-color:#0a0a0a}.select.is-black select{border-color:#0a0a0a}.select.is-black select.is-hovered,.select.is-black select:hover{border-color:#000}.select.is-black select.is-active,.select.is-black select.is-focused,.select.is-black select:active,.select.is-black select:focus{box-shadow:0 0 0 .125em rgba(10,10,10,.25)}.select.is-light:not(:hover)::after{border-color:#f5f5f5}.select.is-light select{border-color:#f5f5f5}.select.is-light select.is-hovered,.select.is-light select:hover{border-color:#e8e8e8}.select.is-light select.is-active,.select.is-light select.is-focused,.select.is-light select:active,.select.is-light select:focus{box-shadow:0 0 0 .125em rgba(245,245,245,.25)}.select.is-dark:not(:hover)::after{border-color:#363636}.select.is-dark select{border-color:#363636}.select.is-dark select.is-hovered,.select.is-dark select:hover{border-color:#292929}.select.is-dark select.is-active,.select.is-dark select.is-focused,.select.is-dark select:active,.select.is-dark select:focus{box-shadow:0 0 0 .125em rgba(54,54,54,.25)}.select.is-primary:not(:hover)::after{border-color:#00d1b2}.select.is-primary select{border-color:#00d1b2}.select.is-primary select.is-hovered,.select.is-primary select:hover{border-color:#00b89c}.select.is-primary select.is-active,.select.is-primary select.is-focused,.select.is-primary select:active,.select.is-primary select:focus{box-shadow:0 0 0 .125em rgba(0,209,178,.25)}.select.is-link:not(:hover)::after{border-color:#3273dc}.select.is-link select{border-color:#3273dc}.select.is-link select.is-hovered,.select.is-link select:hover{border-color:#2366d1}.select.is-link select.is-active,.select.is-link select.is-focused,.select.is-link select:active,.select.is-link select:focus{box-shadow:0 0 0 .125em rgba(50,115,220,.25)}.select.is-info:not(:hover)::after{border-color:#3298dc}.select.is-info select{border-color:#3298dc}.select.is-info select.is-hovered,.select.is-info select:hover{border-color:#238cd1}.select.is-info select.is-active,.select.is-info select.is-focused,.select.is-info select:active,.select.is-info select:focus{box-shadow:0 0 0 .125em rgba(50,152,220,.25)}.select.is-success:not(:hover)::after{border-color:#48c774}.select.is-success select{border-color:#48c774}.select.is-success select.is-hovered,.select.is-success select:hover{border-color:#3abb67}.select.is-success select.is-active,.select.is-success select.is-focused,.select.is-success select:active,.select.is-success select:focus{box-shadow:0 0 0 .125em rgba(72,199,116,.25)}.select.is-warning:not(:hover)::after{border-color:#ffdd57}.select.is-warning select{border-color:#ffdd57}.select.is-warning select.is-hovered,.select.is-warning select:hover{border-color:#ffd83d}.select.is-warning select.is-active,.select.is-warning select.is-focused,.select.is-warning select:active,.select.is-warning select:focus{box-shadow:0 0 0 .125em rgba(255,221,87,.25)}.select.is-danger:not(:hover)::after{border-color:#f14668}.select.is-danger select{border-color:#f14668}.select.is-danger select.is-hovered,.select.is-danger select:hover{border-color:#ef2e55}.select.is-danger select.is-active,.select.is-danger select.is-focused,.select.is-danger select:active,.select.is-danger select:focus{box-shadow:0 0 0 .125em rgba(241,70,104,.25)}.select.is-small{border-radius:2px;font-size:.75rem}.select.is-medium{font-size:1.25rem}.select.is-large{font-size:1.5rem}.select.is-disabled::after{border-color:#7a7a7a}.select.is-fullwidth{width:100%}.select.is-fullwidth select{width:100%}.select.is-loading::after{margin-top:0;position:absolute;right:.625em;top:.625em;transform:none}.select.is-loading.is-small:after{font-size:.75rem}.select.is-loading.is-medium:after{font-size:1.25rem}.select.is-loading.is-large:after{font-size:1.5rem}.file{align-items:stretch;display:flex;justify-content:flex-start;position:relative}.file.is-white .file-cta{background-color:#fff;border-color:transparent;color:#0a0a0a}.file.is-white.is-hovered .file-cta,.file.is-white:hover .file-cta{background-color:#f9f9f9;border-color:transparent;color:#0a0a0a}.file.is-white.is-focused .file-cta,.file.is-white:focus .file-cta{border-color:transparent;box-shadow:0 0 .5em rgba(255,255,255,.25);color:#0a0a0a}.file.is-white.is-active .file-cta,.file.is-white:active .file-cta{background-color:#f2f2f2;border-color:transparent;color:#0a0a0a}.file.is-black .file-cta{background-color:#0a0a0a;border-color:transparent;color:#fff}.file.is-black.is-hovered .file-cta,.file.is-black:hover .file-cta{background-color:#040404;border-color:transparent;color:#fff}.file.is-black.is-focused .file-cta,.file.is-black:focus .file-cta{border-color:transparent;box-shadow:0 0 .5em rgba(10,10,10,.25);color:#fff}.file.is-black.is-active .file-cta,.file.is-black:active .file-cta{background-color:#000;border-color:transparent;color:#fff}.file.is-light .file-cta{background-color:#f5f5f5;border-color:transparent;color:rgba(0,0,0,.7)}.file.is-light.is-hovered .file-cta,.file.is-light:hover .file-cta{background-color:#eee;border-color:transparent;color:rgba(0,0,0,.7)}.file.is-light.is-focused .file-cta,.file.is-light:focus .file-cta{border-color:transparent;box-shadow:0 0 .5em rgba(245,245,245,.25);color:rgba(0,0,0,.7)}.file.is-light.is-active .file-cta,.file.is-light:active .file-cta{background-color:#e8e8e8;border-color:transparent;color:rgba(0,0,0,.7)}.file.is-dark .file-cta{background-color:#363636;border-color:transparent;color:#fff}.file.is-dark.is-hovered .file-cta,.file.is-dark:hover .file-cta{background-color:#2f2f2f;border-color:transparent;color:#fff}.file.is-dark.is-focused .file-cta,.file.is-dark:focus .file-cta{border-color:transparent;box-shadow:0 0 .5em rgba(54,54,54,.25);color:#fff}.file.is-dark.is-active .file-cta,.file.is-dark:active .file-cta{background-color:#292929;border-color:transparent;color:#fff}.file.is-primary .file-cta{background-color:#00d1b2;border-color:transparent;color:#fff}.file.is-primary.is-hovered .file-cta,.file.is-primary:hover .file-cta{background-color:#00c4a7;border-color:transparent;color:#fff}.file.is-primary.is-focused .file-cta,.file.is-primary:focus .file-cta{border-color:transparent;box-shadow:0 0 .5em rgba(0,209,178,.25);color:#fff}.file.is-primary.is-active .file-cta,.file.is-primary:active .file-cta{background-color:#00b89c;border-color:transparent;color:#fff}.file.is-link .file-cta{background-color:#3273dc;border-color:transparent;color:#fff}.file.is-link.is-hovered .file-cta,.file.is-link:hover .file-cta{background-color:#276cda;border-color:transparent;color:#fff}.file.is-link.is-focused .file-cta,.file.is-link:focus .file-cta{border-color:transparent;box-shadow:0 0 .5em rgba(50,115,220,.25);color:#fff}.file.is-link.is-active .file-cta,.file.is-link:active .file-cta{background-color:#2366d1;border-color:transparent;color:#fff}.file.is-info .file-cta{background-color:#3298dc;border-color:transparent;color:#fff}.file.is-info.is-hovered .file-cta,.file.is-info:hover .file-cta{background-color:#2793da;border-color:transparent;color:#fff}.file.is-info.is-focused .file-cta,.file.is-info:focus .file-cta{border-color:transparent;box-shadow:0 0 .5em rgba(50,152,220,.25);color:#fff}.file.is-info.is-active .file-cta,.file.is-info:active .file-cta{background-color:#238cd1;border-color:transparent;color:#fff}.file.is-success .file-cta{background-color:#48c774;border-color:transparent;color:#fff}.file.is-success.is-hovered .file-cta,.file.is-success:hover .file-cta{background-color:#3ec46d;border-color:transparent;color:#fff}.file.is-success.is-focused .file-cta,.file.is-success:focus .file-cta{border-color:transparent;box-shadow:0 0 .5em rgba(72,199,116,.25);color:#fff}.file.is-success.is-active .file-cta,.file.is-success:active .file-cta{background-color:#3abb67;border-color:transparent;color:#fff}.file.is-warning .file-cta{background-color:#ffdd57;border-color:transparent;color:rgba(0,0,0,.7)}.file.is-warning.is-hovered .file-cta,.file.is-warning:hover .file-cta{background-color:#ffdb4a;border-color:transparent;color:rgba(0,0,0,.7)}.file.is-warning.is-focused .file-cta,.file.is-warning:focus .file-cta{border-color:transparent;box-shadow:0 0 .5em rgba(255,221,87,.25);color:rgba(0,0,0,.7)}.file.is-warning.is-active .file-cta,.file.is-warning:active .file-cta{background-color:#ffd83d;border-color:transparent;color:rgba(0,0,0,.7)}.file.is-danger .file-cta{background-color:#f14668;border-color:transparent;color:#fff}.file.is-danger.is-hovered .file-cta,.file.is-danger:hover .file-cta{background-color:#f03a5f;border-color:transparent;color:#fff}.file.is-danger.is-focused .file-cta,.file.is-danger:focus .file-cta{border-color:transparent;box-shadow:0 0 .5em rgba(241,70,104,.25);color:#fff}.file.is-danger.is-active .file-cta,.file.is-danger:active .file-cta{background-color:#ef2e55;border-color:transparent;color:#fff}.file.is-small{font-size:.75rem}.file.is-medium{font-size:1.25rem}.file.is-medium .file-icon .fa{font-size:21px}.file.is-large{font-size:1.5rem}.file.is-large .file-icon .fa{font-size:28px}.file.has-name .file-cta{border-bottom-right-radius:0;border-top-right-radius:0}.file.has-name .file-name{border-bottom-left-radius:0;border-top-left-radius:0}.file.has-name.is-empty .file-cta{border-radius:4px}.file.has-name.is-empty .file-name{display:none}.file.is-boxed .file-label{flex-direction:column}.file.is-boxed .file-cta{flex-direction:column;height:auto;padding:1em 3em}.file.is-boxed .file-name{border-width:0 1px 1px}.file.is-boxed .file-icon{height:1.5em;width:1.5em}.file.is-boxed .file-icon .fa{font-size:21px}.file.is-boxed.is-small .file-icon .fa{font-size:14px}.file.is-boxed.is-medium .file-icon .fa{font-size:28px}.file.is-boxed.is-large .file-icon .fa{font-size:35px}.file.is-boxed.has-name .file-cta{border-radius:4px 4px 0 0}.file.is-boxed.has-name .file-name{border-radius:0 0 4px 4px;border-width:0 1px 1px}.file.is-centered{justify-content:center}.file.is-fullwidth .file-label{width:100%}.file.is-fullwidth .file-name{flex-grow:1;max-width:none}.file.is-right{justify-content:flex-end}.file.is-right .file-cta{border-radius:0 4px 4px 0}.file.is-right .file-name{border-radius:4px 0 0 4px;border-width:1px 0 1px 1px;order:-1}.file-label{align-items:stretch;display:flex;cursor:pointer;justify-content:flex-start;overflow:hidden;position:relative}.file-label:hover .file-cta{background-color:#eee;color:#363636}.file-label:hover .file-name{border-color:#d5d5d5}.file-label:active .file-cta{background-color:#e8e8e8;color:#363636}.file-label:active .file-name{border-color:#cfcfcf}.file-input{height:100%;left:0;opacity:0;outline:0;position:absolute;top:0;width:100%}.file-cta,.file-name{border-color:#dbdbdb;border-radius:4px;font-size:1em;padding-left:1em;padding-right:1em;white-space:nowrap}.file-cta{background-color:#f5f5f5;color:#4a4a4a}.file-name{border-color:#dbdbdb;border-style:solid;border-width:1px 1px 1px 0;display:block;max-width:16em;overflow:hidden;text-align:inherit;text-overflow:ellipsis}.file-icon{align-items:center;display:flex;height:1em;justify-content:center;margin-right:.5em;width:1em}.file-icon .fa{font-size:14px}.label{color:#363636;display:block;font-size:1rem;font-weight:700}.label:not(:last-child){margin-bottom:.5em}.label.is-small{font-size:.75rem}.label.is-medium{font-size:1.25rem}.label.is-large{font-size:1.5rem}.help{display:block;font-size:.75rem;margin-top:.25rem}.help.is-white{color:#fff}.help.is-black{color:#0a0a0a}.help.is-light{color:#f5f5f5}.help.is-dark{color:#363636}.help.is-primary{color:#00d1b2}.help.is-link{color:#3273dc}.help.is-info{color:#3298dc}.help.is-success{color:#48c774}.help.is-warning{color:#ffdd57}.help.is-danger{color:#f14668}.field:not(:last-child){margin-bottom:.75rem}.field.has-addons{display:flex;justify-content:flex-start}.field.has-addons .control:not(:last-child){margin-right:-1px}.field.has-addons .control:not(:first-child):not(:last-child) .button,.field.has-addons .control:not(:first-child):not(:last-child) .input,.field.has-addons .control:not(:first-child):not(:last-child) .select select{border-radius:0}.field.has-addons .control:first-child:not(:only-child) .button,.field.has-addons .control:first-child:not(:only-child) .input,.field.has-addons .control:first-child:not(:only-child) .select select{border-bottom-right-radius:0;border-top-right-radius:0}.field.has-addons .control:last-child:not(:only-child) .button,.field.has-addons .control:last-child:not(:only-child) .input,.field.has-addons .control:last-child:not(:only-child) .select select{border-bottom-left-radius:0;border-top-left-radius:0}.field.has-addons .control .button:not([disabled]).is-hovered,.field.has-addons .control .button:not([disabled]):hover,.field.has-addons .control .input:not([disabled]).is-hovered,.field.has-addons .control .input:not([disabled]):hover,.field.has-addons .control .select select:not([disabled]).is-hovered,.field.has-addons .control .select select:not([disabled]):hover{z-index:2}.field.has-addons .control .button:not([disabled]).is-active,.field.has-addons .control .button:not([disabled]).is-focused,.field.has-addons .control .button:not([disabled]):active,.field.has-addons .control .button:not([disabled]):focus,.field.has-addons .control .input:not([disabled]).is-active,.field.has-addons .control .input:not([disabled]).is-focused,.field.has-addons .control .input:not([disabled]):active,.field.has-addons .control .input:not([disabled]):focus,.field.has-addons .control .select select:not([disabled]).is-active,.field.has-addons .control .select select:not([disabled]).is-focused,.field.has-addons .control .select select:not([disabled]):active,.field.has-addons .control .select select:not([disabled]):focus{z-index:3}.field.has-addons .control .button:not([disabled]).is-active:hover,.field.has-addons .control .button:not([disabled]).is-focused:hover,.field.has-addons .control .button:not([disabled]):active:hover,.field.has-addons .control .button:not([disabled]):focus:hover,.field.has-addons .control .input:not([disabled]).is-active:hover,.field.has-addons .control .input:not([disabled]).is-focused:hover,.field.has-addons .control .input:not([disabled]):active:hover,.field.has-addons .control .input:not([disabled]):focus:hover,.field.has-addons .control .select select:not([disabled]).is-active:hover,.field.has-addons .control .select select:not([disabled]).is-focused:hover,.field.has-addons .control .select select:not([disabled]):active:hover,.field.has-addons .control .select select:not([disabled]):focus:hover{z-index:4}.field.has-addons .control.is-expanded{flex-grow:1;flex-shrink:1}.field.has-addons.has-addons-centered{justify-content:center}.field.has-addons.has-addons-right{justify-content:flex-end}.field.has-addons.has-addons-fullwidth .control{flex-grow:1;flex-shrink:0}.field.is-grouped{display:flex;justify-content:flex-start}.field.is-grouped>.control{flex-shrink:0}.field.is-grouped>.control:not(:last-child){margin-bottom:0;margin-right:.75rem}.field.is-grouped>.control.is-expanded{flex-grow:1;flex-shrink:1}.field.is-grouped.is-grouped-centered{justify-content:center}.field.is-grouped.is-grouped-right{justify-content:flex-end}.field.is-grouped.is-grouped-multiline{flex-wrap:wrap}.field.is-grouped.is-grouped-multiline>.control:last-child,.field.is-grouped.is-grouped-multiline>.control:not(:last-child){margin-bottom:.75rem}.field.is-grouped.is-grouped-multiline:last-child{margin-bottom:-.75rem}.field.is-grouped.is-grouped-multiline:not(:last-child){margin-bottom:0}@media screen and (min-width:769px),print{.field.is-horizontal{display:flex}}.field-label .label{font-size:inherit}@media screen and (max-width:768px){.field-label{margin-bottom:.5rem}}@media screen and (min-width:769px),print{.field-label{flex-basis:0;flex-grow:1;flex-shrink:0;margin-right:1.5rem;text-align:right}.field-label.is-small{font-size:.75rem;padding-top:.375em}.field-label.is-normal{padding-top:.375em}.field-label.is-medium{font-size:1.25rem;padding-top:.375em}.field-label.is-large{font-size:1.5rem;padding-top:.375em}}.field-body .field .field{margin-bottom:0}@media screen and (min-width:769px),print{.field-body{display:flex;flex-basis:0;flex-grow:5;flex-shrink:1}.field-body .field{margin-bottom:0}.field-body>.field{flex-shrink:1}.field-body>.field:not(.is-narrow){flex-grow:1}.field-body>.field:not(:last-child){margin-right:.75rem}}.control{box-sizing:border-box;clear:both;font-size:1rem;position:relative;text-align:inherit}.control.has-icons-left .input:focus~.icon,.control.has-icons-left .select:focus~.icon,.control.has-icons-right .input:focus~.icon,.control.has-icons-right .select:focus~.icon{color:#4a4a4a}.control.has-icons-left .input.is-small~.icon,.control.has-icons-left .select.is-small~.icon,.control.has-icons-right .input.is-small~.icon,.control.has-icons-right .select.is-small~.icon{font-size:.75rem}.control.has-icons-left .input.is-medium~.icon,.control.has-icons-left .select.is-medium~.icon,.control.has-icons-right .input.is-medium~.icon,.control.has-icons-right .select.is-medium~.icon{font-size:1.25rem}.control.has-icons-left .input.is-large~.icon,.control.has-icons-left .select.is-large~.icon,.control.has-icons-right .input.is-large~.icon,.control.has-icons-right .select.is-large~.icon{font-size:1.5rem}.control.has-icons-left .icon,.control.has-icons-right .icon{color:#dbdbdb;height:2.5em;pointer-events:none;position:absolute;top:0;width:2.5em;z-index:4}.control.has-icons-left .input,.control.has-icons-left .select select{padding-left:2.5em}.control.has-icons-left .icon.is-left{left:0}.control.has-icons-right .input,.control.has-icons-right .select select{padding-right:2.5em}.control.has-icons-right .icon.is-right{right:0}.control.is-loading::after{position:absolute!important;right:.625em;top:.625em;z-index:4}.control.is-loading.is-small:after{font-size:.75rem}.control.is-loading.is-medium:after{font-size:1.25rem}.control.is-loading.is-large:after{font-size:1.5rem}.breadcrumb{font-size:1rem;white-space:nowrap}.breadcrumb a{align-items:center;color:#3273dc;display:flex;justify-content:center;padding:0 .75em}.breadcrumb a:hover{color:#363636}.breadcrumb li{align-items:center;display:flex}.breadcrumb li:first-child a{padding-left:0}.breadcrumb li.is-active a{color:#363636;cursor:default;pointer-events:none}.breadcrumb li+li::before{color:#b5b5b5;content:"\0002f"}.breadcrumb ol,.breadcrumb ul{align-items:flex-start;display:flex;flex-wrap:wrap;justify-content:flex-start}.breadcrumb .icon:first-child{margin-right:.5em}.breadcrumb .icon:last-child{margin-left:.5em}.breadcrumb.is-centered ol,.breadcrumb.is-centered ul{justify-content:center}.breadcrumb.is-right ol,.breadcrumb.is-right ul{justify-content:flex-end}.breadcrumb.is-small{font-size:.75rem}.breadcrumb.is-medium{font-size:1.25rem}.breadcrumb.is-large{font-size:1.5rem}.breadcrumb.has-arrow-separator li+li::before{content:"\02192"}.breadcrumb.has-bullet-separator li+li::before{content:"\02022"}.breadcrumb.has-dot-separator li+li::before{content:"\000b7"}.breadcrumb.has-succeeds-separator li+li::before{content:"\0227B"}.card{background-color:#fff;border-radius:.25rem;box-shadow:0 .5em 1em -.125em rgba(10,10,10,.1),0 0 0 1px rgba(10,10,10,.02);color:#4a4a4a;max-width:100%;overflow:hidden;position:relative}.card-header{background-color:transparent;align-items:stretch;box-shadow:0 .125em .25em rgba(10,10,10,.1);display:flex}.card-header-title{align-items:center;color:#363636;display:flex;flex-grow:1;font-weight:700;padding:.75rem 1rem}.card-header-title.is-centered{justify-content:center}.card-header-icon{align-items:center;cursor:pointer;display:flex;justify-content:center;padding:.75rem 1rem}.card-image{display:block;position:relative}.card-content{background-color:transparent;padding:1.5rem}.card-footer{background-color:transparent;border-top:1px solid #ededed;align-items:stretch;display:flex}.card-footer-item{align-items:center;display:flex;flex-basis:0;flex-grow:1;flex-shrink:0;justify-content:center;padding:.75rem}.card-footer-item:not(:last-child){border-right:1px solid #ededed}.card .media:not(:last-child){margin-bottom:1.5rem}.dropdown{display:inline-flex;position:relative;vertical-align:top}.dropdown.is-active .dropdown-menu,.dropdown.is-hoverable:hover .dropdown-menu{display:block}.dropdown.is-right .dropdown-menu{left:auto;right:0}.dropdown.is-up .dropdown-menu{bottom:100%;padding-bottom:4px;padding-top:initial;top:auto}.dropdown-menu{display:none;left:0;min-width:12rem;padding-top:4px;position:absolute;top:100%;z-index:20}.dropdown-content{background-color:#fff;border-radius:4px;box-shadow:0 .5em 1em -.125em rgba(10,10,10,.1),0 0 0 1px rgba(10,10,10,.02);padding-bottom:.5rem;padding-top:.5rem}.dropdown-item{color:#4a4a4a;display:block;font-size:.875rem;line-height:1.5;padding:.375rem 1rem;position:relative}a.dropdown-item,button.dropdown-item{padding-right:3rem;text-align:inherit;white-space:nowrap;width:100%}a.dropdown-item:hover,button.dropdown-item:hover{background-color:#f5f5f5;color:#0a0a0a}a.dropdown-item.is-active,button.dropdown-item.is-active{background-color:#3273dc;color:#fff}.dropdown-divider{background-color:#ededed;border:none;display:block;height:1px;margin:.5rem 0}.level{align-items:center;justify-content:space-between}.level code{border-radius:4px}.level img{display:inline-block;vertical-align:top}.level.is-mobile{display:flex}.level.is-mobile .level-left,.level.is-mobile .level-right{display:flex}.level.is-mobile .level-left+.level-right{margin-top:0}.level.is-mobile .level-item:not(:last-child){margin-bottom:0;margin-right:.75rem}.level.is-mobile .level-item:not(.is-narrow){flex-grow:1}@media screen and (min-width:769px),print{.level{display:flex}.level>.level-item:not(.is-narrow){flex-grow:1}}.level-item{align-items:center;display:flex;flex-basis:auto;flex-grow:0;flex-shrink:0;justify-content:center}.level-item .subtitle,.level-item .title{margin-bottom:0}@media screen and (max-width:768px){.level-item:not(:last-child){margin-bottom:.75rem}}.level-left,.level-right{flex-basis:auto;flex-grow:0;flex-shrink:0}.level-left .level-item.is-flexible,.level-right .level-item.is-flexible{flex-grow:1}@media screen and (min-width:769px),print{.level-left .level-item:not(:last-child),.level-right .level-item:not(:last-child){margin-right:.75rem}}.level-left{align-items:center;justify-content:flex-start}@media screen and (max-width:768px){.level-left+.level-right{margin-top:1.5rem}}@media screen and (min-width:769px),print{.level-left{display:flex}}.level-right{align-items:center;justify-content:flex-end}@media screen and (min-width:769px),print{.level-right{display:flex}}.media{align-items:flex-start;display:flex;text-align:inherit}.media .content:not(:last-child){margin-bottom:.75rem}.media .media{border-top:1px solid rgba(219,219,219,.5);display:flex;padding-top:.75rem}.media .media .content:not(:last-child),.media .media .control:not(:last-child){margin-bottom:.5rem}.media .media .media{padding-top:.5rem}.media .media .media+.media{margin-top:.5rem}.media+.media{border-top:1px solid rgba(219,219,219,.5);margin-top:1rem;padding-top:1rem}.media.is-large+.media{margin-top:1.5rem;padding-top:1.5rem}.media-left,.media-right{flex-basis:auto;flex-grow:0;flex-shrink:0}.media-left{margin-right:1rem}.media-right{margin-left:1rem}.media-content{flex-basis:auto;flex-grow:1;flex-shrink:1;text-align:inherit}@media screen and (max-width:768px){.media-content{overflow-x:auto}}.menu{font-size:1rem}.menu.is-small{font-size:.75rem}.menu.is-medium{font-size:1.25rem}.menu.is-large{font-size:1.5rem}.menu-list{line-height:1.25}.menu-list a{border-radius:2px;color:#4a4a4a;display:block;padding:.5em .75em}.menu-list a:hover{background-color:#f5f5f5;color:#363636}.menu-list a.is-active{background-color:#3273dc;color:#fff}.menu-list li ul{border-left:1px solid #dbdbdb;margin:.75em;padding-left:.75em}.menu-label{color:#7a7a7a;font-size:.75em;letter-spacing:.1em;text-transform:uppercase}.menu-label:not(:first-child){margin-top:1em}.menu-label:not(:last-child){margin-bottom:1em}.message{background-color:#f5f5f5;border-radius:4px;font-size:1rem}.message strong{color:currentColor}.message a:not(.button):not(.tag):not(.dropdown-item){color:currentColor;text-decoration:underline}.message.is-small{font-size:.75rem}.message.is-medium{font-size:1.25rem}.message.is-large{font-size:1.5rem}.message.is-white{background-color:#fff}.message.is-white .message-header{background-color:#fff;color:#0a0a0a}.message.is-white .message-body{border-color:#fff}.message.is-black{background-color:#fafafa}.message.is-black .message-header{background-color:#0a0a0a;color:#fff}.message.is-black .message-body{border-color:#0a0a0a}.message.is-light{background-color:#fafafa}.message.is-light .message-header{background-color:#f5f5f5;color:rgba(0,0,0,.7)}.message.is-light .message-body{border-color:#f5f5f5}.message.is-dark{background-color:#fafafa}.message.is-dark .message-header{background-color:#363636;color:#fff}.message.is-dark .message-body{border-color:#363636}.message.is-primary{background-color:#ebfffc}.message.is-primary .message-header{background-color:#00d1b2;color:#fff}.message.is-primary .message-body{border-color:#00d1b2;color:#00947e}.message.is-link{background-color:#eef3fc}.message.is-link .message-header{background-color:#3273dc;color:#fff}.message.is-link .message-body{border-color:#3273dc;color:#2160c4}.message.is-info{background-color:#eef6fc}.message.is-info .message-header{background-color:#3298dc;color:#fff}.message.is-info .message-body{border-color:#3298dc;color:#1d72aa}.message.is-success{background-color:#effaf3}.message.is-success .message-header{background-color:#48c774;color:#fff}.message.is-success .message-body{border-color:#48c774;color:#257942}.message.is-warning{background-color:#fffbeb}.message.is-warning .message-header{background-color:#ffdd57;color:rgba(0,0,0,.7)}.message.is-warning .message-body{border-color:#ffdd57;color:#947600}.message.is-danger{background-color:#feecf0}.message.is-danger .message-header{background-color:#f14668;color:#fff}.message.is-danger .message-body{border-color:#f14668;color:#cc0f35}.message-header{align-items:center;background-color:#4a4a4a;border-radius:4px 4px 0 0;color:#fff;display:flex;font-weight:700;justify-content:space-between;line-height:1.25;padding:.75em 1em;position:relative}.message-header .delete{flex-grow:0;flex-shrink:0;margin-left:.75em}.message-header+.message-body{border-width:0;border-top-left-radius:0;border-top-right-radius:0}.message-body{border-color:#dbdbdb;border-radius:4px;border-style:solid;border-width:0 0 0 4px;color:#4a4a4a;padding:1.25em 1.5em}.message-body code,.message-body pre{background-color:#fff}.message-body pre code{background-color:transparent}.modal{align-items:center;display:none;flex-direction:column;justify-content:center;overflow:hidden;position:fixed;z-index:40}.modal.is-active{display:flex}.modal-background{background-color:rgba(10,10,10,.86)}.modal-card,.modal-content{margin:0 20px;max-height:calc(100vh - 160px);overflow:auto;position:relative;width:100%}@media screen and (min-width:769px){.modal-card,.modal-content{margin:0 auto;max-height:calc(100vh - 40px);width:640px}}.modal-close{background:0 0;height:40px;position:fixed;right:20px;top:20px;width:40px}.modal-card{display:flex;flex-direction:column;max-height:calc(100vh - 40px);overflow:hidden;-ms-overflow-y:visible}.modal-card-foot,.modal-card-head{align-items:center;background-color:#f5f5f5;display:flex;flex-shrink:0;justify-content:flex-start;padding:20px;position:relative}.modal-card-head{border-bottom:1px solid #dbdbdb;border-top-left-radius:6px;border-top-right-radius:6px}.modal-card-title{color:#363636;flex-grow:1;flex-shrink:0;font-size:1.5rem;line-height:1}.modal-card-foot{border-bottom-left-radius:6px;border-bottom-right-radius:6px;border-top:1px solid #dbdbdb}.modal-card-foot .button:not(:last-child){margin-right:.5em}.modal-card-body{-webkit-overflow-scrolling:touch;background-color:#fff;flex-grow:1;flex-shrink:1;overflow:auto;padding:20px}.navbar{background-color:#fff;min-height:3.25rem;position:relative;z-index:30}.navbar.is-white{background-color:#fff;color:#0a0a0a}.navbar.is-white .navbar-brand .navbar-link,.navbar.is-white .navbar-brand>.navbar-item{color:#0a0a0a}.navbar.is-white .navbar-brand .navbar-link.is-active,.navbar.is-white .navbar-brand .navbar-link:focus,.navbar.is-white .navbar-brand .navbar-link:hover,.navbar.is-white .navbar-brand>a.navbar-item.is-active,.navbar.is-white .navbar-brand>a.navbar-item:focus,.navbar.is-white .navbar-brand>a.navbar-item:hover{background-color:#f2f2f2;color:#0a0a0a}.navbar.is-white .navbar-brand .navbar-link::after{border-color:#0a0a0a}.navbar.is-white .navbar-burger{color:#0a0a0a}@media screen and (min-width:1024px){.navbar.is-white .navbar-end .navbar-link,.navbar.is-white .navbar-end>.navbar-item,.navbar.is-white .navbar-start .navbar-link,.navbar.is-white .navbar-start>.navbar-item{color:#0a0a0a}.navbar.is-white .navbar-end .navbar-link.is-active,.navbar.is-white .navbar-end .navbar-link:focus,.navbar.is-white .navbar-end .navbar-link:hover,.navbar.is-white .navbar-end>a.navbar-item.is-active,.navbar.is-white .navbar-end>a.navbar-item:focus,.navbar.is-white .navbar-end>a.navbar-item:hover,.navbar.is-white .navbar-start .navbar-link.is-active,.navbar.is-white .navbar-start .navbar-link:focus,.navbar.is-white .navbar-start .navbar-link:hover,.navbar.is-white .navbar-start>a.navbar-item.is-active,.navbar.is-white .navbar-start>a.navbar-item:focus,.navbar.is-white .navbar-start>a.navbar-item:hover{background-color:#f2f2f2;color:#0a0a0a}.navbar.is-white .navbar-end .navbar-link::after,.navbar.is-white .navbar-start .navbar-link::after{border-color:#0a0a0a}.navbar.is-white .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-white .navbar-item.has-dropdown:focus .navbar-link,.navbar.is-white .navbar-item.has-dropdown:hover .navbar-link{background-color:#f2f2f2;color:#0a0a0a}.navbar.is-white .navbar-dropdown a.navbar-item.is-active{background-color:#fff;color:#0a0a0a}}.navbar.is-black{background-color:#0a0a0a;color:#fff}.navbar.is-black .navbar-brand .navbar-link,.navbar.is-black .navbar-brand>.navbar-item{color:#fff}.navbar.is-black .navbar-brand .navbar-link.is-active,.navbar.is-black .navbar-brand .navbar-link:focus,.navbar.is-black .navbar-brand .navbar-link:hover,.navbar.is-black .navbar-brand>a.navbar-item.is-active,.navbar.is-black .navbar-brand>a.navbar-item:focus,.navbar.is-black .navbar-brand>a.navbar-item:hover{background-color:#000;color:#fff}.navbar.is-black .navbar-brand .navbar-link::after{border-color:#fff}.navbar.is-black .navbar-burger{color:#fff}@media screen and (min-width:1024px){.navbar.is-black .navbar-end .navbar-link,.navbar.is-black .navbar-end>.navbar-item,.navbar.is-black .navbar-start .navbar-link,.navbar.is-black .navbar-start>.navbar-item{color:#fff}.navbar.is-black .navbar-end .navbar-link.is-active,.navbar.is-black .navbar-end .navbar-link:focus,.navbar.is-black .navbar-end .navbar-link:hover,.navbar.is-black .navbar-end>a.navbar-item.is-active,.navbar.is-black .navbar-end>a.navbar-item:focus,.navbar.is-black .navbar-end>a.navbar-item:hover,.navbar.is-black .navbar-start .navbar-link.is-active,.navbar.is-black .navbar-start .navbar-link:focus,.navbar.is-black .navbar-start .navbar-link:hover,.navbar.is-black .navbar-start>a.navbar-item.is-active,.navbar.is-black .navbar-start>a.navbar-item:focus,.navbar.is-black .navbar-start>a.navbar-item:hover{background-color:#000;color:#fff}.navbar.is-black .navbar-end .navbar-link::after,.navbar.is-black .navbar-start .navbar-link::after{border-color:#fff}.navbar.is-black .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-black .navbar-item.has-dropdown:focus .navbar-link,.navbar.is-black .navbar-item.has-dropdown:hover .navbar-link{background-color:#000;color:#fff}.navbar.is-black .navbar-dropdown a.navbar-item.is-active{background-color:#0a0a0a;color:#fff}}.navbar.is-light{background-color:#f5f5f5;color:rgba(0,0,0,.7)}.navbar.is-light .navbar-brand .navbar-link,.navbar.is-light .navbar-brand>.navbar-item{color:rgba(0,0,0,.7)}.navbar.is-light .navbar-brand .navbar-link.is-active,.navbar.is-light .navbar-brand .navbar-link:focus,.navbar.is-light .navbar-brand .navbar-link:hover,.navbar.is-light .navbar-brand>a.navbar-item.is-active,.navbar.is-light .navbar-brand>a.navbar-item:focus,.navbar.is-light .navbar-brand>a.navbar-item:hover{background-color:#e8e8e8;color:rgba(0,0,0,.7)}.navbar.is-light .navbar-brand .navbar-link::after{border-color:rgba(0,0,0,.7)}.navbar.is-light .navbar-burger{color:rgba(0,0,0,.7)}@media screen and (min-width:1024px){.navbar.is-light .navbar-end .navbar-link,.navbar.is-light .navbar-end>.navbar-item,.navbar.is-light .navbar-start .navbar-link,.navbar.is-light .navbar-start>.navbar-item{color:rgba(0,0,0,.7)}.navbar.is-light .navbar-end .navbar-link.is-active,.navbar.is-light .navbar-end .navbar-link:focus,.navbar.is-light .navbar-end .navbar-link:hover,.navbar.is-light .navbar-end>a.navbar-item.is-active,.navbar.is-light .navbar-end>a.navbar-item:focus,.navbar.is-light .navbar-end>a.navbar-item:hover,.navbar.is-light .navbar-start .navbar-link.is-active,.navbar.is-light .navbar-start .navbar-link:focus,.navbar.is-light .navbar-start .navbar-link:hover,.navbar.is-light .navbar-start>a.navbar-item.is-active,.navbar.is-light .navbar-start>a.navbar-item:focus,.navbar.is-light .navbar-start>a.navbar-item:hover{background-color:#e8e8e8;color:rgba(0,0,0,.7)}.navbar.is-light .navbar-end .navbar-link::after,.navbar.is-light .navbar-start .navbar-link::after{border-color:rgba(0,0,0,.7)}.navbar.is-light .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-light .navbar-item.has-dropdown:focus .navbar-link,.navbar.is-light .navbar-item.has-dropdown:hover .navbar-link{background-color:#e8e8e8;color:rgba(0,0,0,.7)}.navbar.is-light .navbar-dropdown a.navbar-item.is-active{background-color:#f5f5f5;color:rgba(0,0,0,.7)}}.navbar.is-dark{background-color:#363636;color:#fff}.navbar.is-dark .navbar-brand .navbar-link,.navbar.is-dark .navbar-brand>.navbar-item{color:#fff}.navbar.is-dark .navbar-brand .navbar-link.is-active,.navbar.is-dark .navbar-brand .navbar-link:focus,.navbar.is-dark .navbar-brand .navbar-link:hover,.navbar.is-dark .navbar-brand>a.navbar-item.is-active,.navbar.is-dark .navbar-brand>a.navbar-item:focus,.navbar.is-dark .navbar-brand>a.navbar-item:hover{background-color:#292929;color:#fff}.navbar.is-dark .navbar-brand .navbar-link::after{border-color:#fff}.navbar.is-dark .navbar-burger{color:#fff}@media screen and (min-width:1024px){.navbar.is-dark .navbar-end .navbar-link,.navbar.is-dark .navbar-end>.navbar-item,.navbar.is-dark .navbar-start .navbar-link,.navbar.is-dark .navbar-start>.navbar-item{color:#fff}.navbar.is-dark .navbar-end .navbar-link.is-active,.navbar.is-dark .navbar-end .navbar-link:focus,.navbar.is-dark .navbar-end .navbar-link:hover,.navbar.is-dark .navbar-end>a.navbar-item.is-active,.navbar.is-dark .navbar-end>a.navbar-item:focus,.navbar.is-dark .navbar-end>a.navbar-item:hover,.navbar.is-dark .navbar-start .navbar-link.is-active,.navbar.is-dark .navbar-start .navbar-link:focus,.navbar.is-dark .navbar-start .navbar-link:hover,.navbar.is-dark .navbar-start>a.navbar-item.is-active,.navbar.is-dark .navbar-start>a.navbar-item:focus,.navbar.is-dark .navbar-start>a.navbar-item:hover{background-color:#292929;color:#fff}.navbar.is-dark .navbar-end .navbar-link::after,.navbar.is-dark .navbar-start .navbar-link::after{border-color:#fff}.navbar.is-dark .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-dark .navbar-item.has-dropdown:focus .navbar-link,.navbar.is-dark .navbar-item.has-dropdown:hover .navbar-link{background-color:#292929;color:#fff}.navbar.is-dark .navbar-dropdown a.navbar-item.is-active{background-color:#363636;color:#fff}}.navbar.is-primary{background-color:#00d1b2;color:#fff}.navbar.is-primary .navbar-brand .navbar-link,.navbar.is-primary .navbar-brand>.navbar-item{color:#fff}.navbar.is-primary .navbar-brand .navbar-link.is-active,.navbar.is-primary .navbar-brand .navbar-link:focus,.navbar.is-primary .navbar-brand .navbar-link:hover,.navbar.is-primary .navbar-brand>a.navbar-item.is-active,.navbar.is-primary .navbar-brand>a.navbar-item:focus,.navbar.is-primary .navbar-brand>a.navbar-item:hover{background-color:#00b89c;color:#fff}.navbar.is-primary .navbar-brand .navbar-link::after{border-color:#fff}.navbar.is-primary .navbar-burger{color:#fff}@media screen and (min-width:1024px){.navbar.is-primary .navbar-end .navbar-link,.navbar.is-primary .navbar-end>.navbar-item,.navbar.is-primary .navbar-start .navbar-link,.navbar.is-primary .navbar-start>.navbar-item{color:#fff}.navbar.is-primary .navbar-end .navbar-link.is-active,.navbar.is-primary .navbar-end .navbar-link:focus,.navbar.is-primary .navbar-end .navbar-link:hover,.navbar.is-primary .navbar-end>a.navbar-item.is-active,.navbar.is-primary .navbar-end>a.navbar-item:focus,.navbar.is-primary .navbar-end>a.navbar-item:hover,.navbar.is-primary .navbar-start .navbar-link.is-active,.navbar.is-primary .navbar-start .navbar-link:focus,.navbar.is-primary .navbar-start .navbar-link:hover,.navbar.is-primary .navbar-start>a.navbar-item.is-active,.navbar.is-primary .navbar-start>a.navbar-item:focus,.navbar.is-primary .navbar-start>a.navbar-item:hover{background-color:#00b89c;color:#fff}.navbar.is-primary .navbar-end .navbar-link::after,.navbar.is-primary .navbar-start .navbar-link::after{border-color:#fff}.navbar.is-primary .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-primary .navbar-item.has-dropdown:focus .navbar-link,.navbar.is-primary .navbar-item.has-dropdown:hover .navbar-link{background-color:#00b89c;color:#fff}.navbar.is-primary .navbar-dropdown a.navbar-item.is-active{background-color:#00d1b2;color:#fff}}.navbar.is-link{background-color:#3273dc;color:#fff}.navbar.is-link .navbar-brand .navbar-link,.navbar.is-link .navbar-brand>.navbar-item{color:#fff}.navbar.is-link .navbar-brand .navbar-link.is-active,.navbar.is-link .navbar-brand .navbar-link:focus,.navbar.is-link .navbar-brand .navbar-link:hover,.navbar.is-link .navbar-brand>a.navbar-item.is-active,.navbar.is-link .navbar-brand>a.navbar-item:focus,.navbar.is-link .navbar-brand>a.navbar-item:hover{background-color:#2366d1;color:#fff}.navbar.is-link .navbar-brand .navbar-link::after{border-color:#fff}.navbar.is-link .navbar-burger{color:#fff}@media screen and (min-width:1024px){.navbar.is-link .navbar-end .navbar-link,.navbar.is-link .navbar-end>.navbar-item,.navbar.is-link .navbar-start .navbar-link,.navbar.is-link .navbar-start>.navbar-item{color:#fff}.navbar.is-link .navbar-end .navbar-link.is-active,.navbar.is-link .navbar-end .navbar-link:focus,.navbar.is-link .navbar-end .navbar-link:hover,.navbar.is-link .navbar-end>a.navbar-item.is-active,.navbar.is-link .navbar-end>a.navbar-item:focus,.navbar.is-link .navbar-end>a.navbar-item:hover,.navbar.is-link .navbar-start .navbar-link.is-active,.navbar.is-link .navbar-start .navbar-link:focus,.navbar.is-link .navbar-start .navbar-link:hover,.navbar.is-link .navbar-start>a.navbar-item.is-active,.navbar.is-link .navbar-start>a.navbar-item:focus,.navbar.is-link .navbar-start>a.navbar-item:hover{background-color:#2366d1;color:#fff}.navbar.is-link .navbar-end .navbar-link::after,.navbar.is-link .navbar-start .navbar-link::after{border-color:#fff}.navbar.is-link .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-link .navbar-item.has-dropdown:focus .navbar-link,.navbar.is-link .navbar-item.has-dropdown:hover .navbar-link{background-color:#2366d1;color:#fff}.navbar.is-link .navbar-dropdown a.navbar-item.is-active{background-color:#3273dc;color:#fff}}.navbar.is-info{background-color:#3298dc;color:#fff}.navbar.is-info .navbar-brand .navbar-link,.navbar.is-info .navbar-brand>.navbar-item{color:#fff}.navbar.is-info .navbar-brand .navbar-link.is-active,.navbar.is-info .navbar-brand .navbar-link:focus,.navbar.is-info .navbar-brand .navbar-link:hover,.navbar.is-info .navbar-brand>a.navbar-item.is-active,.navbar.is-info .navbar-brand>a.navbar-item:focus,.navbar.is-info .navbar-brand>a.navbar-item:hover{background-color:#238cd1;color:#fff}.navbar.is-info .navbar-brand .navbar-link::after{border-color:#fff}.navbar.is-info .navbar-burger{color:#fff}@media screen and (min-width:1024px){.navbar.is-info .navbar-end .navbar-link,.navbar.is-info .navbar-end>.navbar-item,.navbar.is-info .navbar-start .navbar-link,.navbar.is-info .navbar-start>.navbar-item{color:#fff}.navbar.is-info .navbar-end .navbar-link.is-active,.navbar.is-info .navbar-end .navbar-link:focus,.navbar.is-info .navbar-end .navbar-link:hover,.navbar.is-info .navbar-end>a.navbar-item.is-active,.navbar.is-info .navbar-end>a.navbar-item:focus,.navbar.is-info .navbar-end>a.navbar-item:hover,.navbar.is-info .navbar-start .navbar-link.is-active,.navbar.is-info .navbar-start .navbar-link:focus,.navbar.is-info .navbar-start .navbar-link:hover,.navbar.is-info .navbar-start>a.navbar-item.is-active,.navbar.is-info .navbar-start>a.navbar-item:focus,.navbar.is-info .navbar-start>a.navbar-item:hover{background-color:#238cd1;color:#fff}.navbar.is-info .navbar-end .navbar-link::after,.navbar.is-info .navbar-start .navbar-link::after{border-color:#fff}.navbar.is-info .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-info .navbar-item.has-dropdown:focus .navbar-link,.navbar.is-info .navbar-item.has-dropdown:hover .navbar-link{background-color:#238cd1;color:#fff}.navbar.is-info .navbar-dropdown a.navbar-item.is-active{background-color:#3298dc;color:#fff}}.navbar.is-success{background-color:#48c774;color:#fff}.navbar.is-success .navbar-brand .navbar-link,.navbar.is-success .navbar-brand>.navbar-item{color:#fff}.navbar.is-success .navbar-brand .navbar-link.is-active,.navbar.is-success .navbar-brand .navbar-link:focus,.navbar.is-success .navbar-brand .navbar-link:hover,.navbar.is-success .navbar-brand>a.navbar-item.is-active,.navbar.is-success .navbar-brand>a.navbar-item:focus,.navbar.is-success .navbar-brand>a.navbar-item:hover{background-color:#3abb67;color:#fff}.navbar.is-success .navbar-brand .navbar-link::after{border-color:#fff}.navbar.is-success .navbar-burger{color:#fff}@media screen and (min-width:1024px){.navbar.is-success .navbar-end .navbar-link,.navbar.is-success .navbar-end>.navbar-item,.navbar.is-success .navbar-start .navbar-link,.navbar.is-success .navbar-start>.navbar-item{color:#fff}.navbar.is-success .navbar-end .navbar-link.is-active,.navbar.is-success .navbar-end .navbar-link:focus,.navbar.is-success .navbar-end .navbar-link:hover,.navbar.is-success .navbar-end>a.navbar-item.is-active,.navbar.is-success .navbar-end>a.navbar-item:focus,.navbar.is-success .navbar-end>a.navbar-item:hover,.navbar.is-success .navbar-start .navbar-link.is-active,.navbar.is-success .navbar-start .navbar-link:focus,.navbar.is-success .navbar-start .navbar-link:hover,.navbar.is-success .navbar-start>a.navbar-item.is-active,.navbar.is-success .navbar-start>a.navbar-item:focus,.navbar.is-success .navbar-start>a.navbar-item:hover{background-color:#3abb67;color:#fff}.navbar.is-success .navbar-end .navbar-link::after,.navbar.is-success .navbar-start .navbar-link::after{border-color:#fff}.navbar.is-success .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-success .navbar-item.has-dropdown:focus .navbar-link,.navbar.is-success .navbar-item.has-dropdown:hover .navbar-link{background-color:#3abb67;color:#fff}.navbar.is-success .navbar-dropdown a.navbar-item.is-active{background-color:#48c774;color:#fff}}.navbar.is-warning{background-color:#ffdd57;color:rgba(0,0,0,.7)}.navbar.is-warning .navbar-brand .navbar-link,.navbar.is-warning .navbar-brand>.navbar-item{color:rgba(0,0,0,.7)}.navbar.is-warning .navbar-brand .navbar-link.is-active,.navbar.is-warning .navbar-brand .navbar-link:focus,.navbar.is-warning .navbar-brand .navbar-link:hover,.navbar.is-warning .navbar-brand>a.navbar-item.is-active,.navbar.is-warning .navbar-brand>a.navbar-item:focus,.navbar.is-warning .navbar-brand>a.navbar-item:hover{background-color:#ffd83d;color:rgba(0,0,0,.7)}.navbar.is-warning .navbar-brand .navbar-link::after{border-color:rgba(0,0,0,.7)}.navbar.is-warning .navbar-burger{color:rgba(0,0,0,.7)}@media screen and (min-width:1024px){.navbar.is-warning .navbar-end .navbar-link,.navbar.is-warning .navbar-end>.navbar-item,.navbar.is-warning .navbar-start .navbar-link,.navbar.is-warning .navbar-start>.navbar-item{color:rgba(0,0,0,.7)}.navbar.is-warning .navbar-end .navbar-link.is-active,.navbar.is-warning .navbar-end .navbar-link:focus,.navbar.is-warning .navbar-end .navbar-link:hover,.navbar.is-warning .navbar-end>a.navbar-item.is-active,.navbar.is-warning .navbar-end>a.navbar-item:focus,.navbar.is-warning .navbar-end>a.navbar-item:hover,.navbar.is-warning .navbar-start .navbar-link.is-active,.navbar.is-warning .navbar-start .navbar-link:focus,.navbar.is-warning .navbar-start .navbar-link:hover,.navbar.is-warning .navbar-start>a.navbar-item.is-active,.navbar.is-warning .navbar-start>a.navbar-item:focus,.navbar.is-warning .navbar-start>a.navbar-item:hover{background-color:#ffd83d;color:rgba(0,0,0,.7)}.navbar.is-warning .navbar-end .navbar-link::after,.navbar.is-warning .navbar-start .navbar-link::after{border-color:rgba(0,0,0,.7)}.navbar.is-warning .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-warning .navbar-item.has-dropdown:focus .navbar-link,.navbar.is-warning .navbar-item.has-dropdown:hover .navbar-link{background-color:#ffd83d;color:rgba(0,0,0,.7)}.navbar.is-warning .navbar-dropdown a.navbar-item.is-active{background-color:#ffdd57;color:rgba(0,0,0,.7)}}.navbar.is-danger{background-color:#f14668;color:#fff}.navbar.is-danger .navbar-brand .navbar-link,.navbar.is-danger .navbar-brand>.navbar-item{color:#fff}.navbar.is-danger .navbar-brand .navbar-link.is-active,.navbar.is-danger .navbar-brand .navbar-link:focus,.navbar.is-danger .navbar-brand .navbar-link:hover,.navbar.is-danger .navbar-brand>a.navbar-item.is-active,.navbar.is-danger .navbar-brand>a.navbar-item:focus,.navbar.is-danger .navbar-brand>a.navbar-item:hover{background-color:#ef2e55;color:#fff}.navbar.is-danger .navbar-brand .navbar-link::after{border-color:#fff}.navbar.is-danger .navbar-burger{color:#fff}@media screen and (min-width:1024px){.navbar.is-danger .navbar-end .navbar-link,.navbar.is-danger .navbar-end>.navbar-item,.navbar.is-danger .navbar-start .navbar-link,.navbar.is-danger .navbar-start>.navbar-item{color:#fff}.navbar.is-danger .navbar-end .navbar-link.is-active,.navbar.is-danger .navbar-end .navbar-link:focus,.navbar.is-danger .navbar-end .navbar-link:hover,.navbar.is-danger .navbar-end>a.navbar-item.is-active,.navbar.is-danger .navbar-end>a.navbar-item:focus,.navbar.is-danger .navbar-end>a.navbar-item:hover,.navbar.is-danger .navbar-start .navbar-link.is-active,.navbar.is-danger .navbar-start .navbar-link:focus,.navbar.is-danger .navbar-start .navbar-link:hover,.navbar.is-danger .navbar-start>a.navbar-item.is-active,.navbar.is-danger .navbar-start>a.navbar-item:focus,.navbar.is-danger .navbar-start>a.navbar-item:hover{background-color:#ef2e55;color:#fff}.navbar.is-danger .navbar-end .navbar-link::after,.navbar.is-danger .navbar-start .navbar-link::after{border-color:#fff}.navbar.is-danger .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-danger .navbar-item.has-dropdown:focus .navbar-link,.navbar.is-danger .navbar-item.has-dropdown:hover .navbar-link{background-color:#ef2e55;color:#fff}.navbar.is-danger .navbar-dropdown a.navbar-item.is-active{background-color:#f14668;color:#fff}}.navbar>.container{align-items:stretch;display:flex;min-height:3.25rem;width:100%}.navbar.has-shadow{box-shadow:0 2px 0 0 #f5f5f5}.navbar.is-fixed-bottom,.navbar.is-fixed-top{left:0;position:fixed;right:0;z-index:30}.navbar.is-fixed-bottom{bottom:0}.navbar.is-fixed-bottom.has-shadow{box-shadow:0 -2px 0 0 #f5f5f5}.navbar.is-fixed-top{top:0}body.has-navbar-fixed-top,html.has-navbar-fixed-top{padding-top:3.25rem}body.has-navbar-fixed-bottom,html.has-navbar-fixed-bottom{padding-bottom:3.25rem}.navbar-brand,.navbar-tabs{align-items:stretch;display:flex;flex-shrink:0;min-height:3.25rem}.navbar-brand a.navbar-item:focus,.navbar-brand a.navbar-item:hover{background-color:transparent}.navbar-tabs{-webkit-overflow-scrolling:touch;max-width:100vw;overflow-x:auto;overflow-y:hidden}.navbar-burger{color:#4a4a4a;cursor:pointer;display:block;height:3.25rem;position:relative;width:3.25rem;margin-left:auto}.navbar-burger span{background-color:currentColor;display:block;height:1px;left:calc(50% - 8px);position:absolute;transform-origin:center;transition-duration:86ms;transition-property:background-color,opacity,transform;transition-timing-function:ease-out;width:16px}.navbar-burger span:nth-child(1){top:calc(50% - 6px)}.navbar-burger span:nth-child(2){top:calc(50% - 1px)}.navbar-burger span:nth-child(3){top:calc(50% + 4px)}.navbar-burger:hover{background-color:rgba(0,0,0,.05)}.navbar-burger.is-active span:nth-child(1){transform:translateY(5px) rotate(45deg)}.navbar-burger.is-active span:nth-child(2){opacity:0}.navbar-burger.is-active span:nth-child(3){transform:translateY(-5px) rotate(-45deg)}.navbar-menu{display:none}.navbar-item,.navbar-link{color:#4a4a4a;display:block;line-height:1.5;padding:.5rem .75rem;position:relative}.navbar-item .icon:only-child,.navbar-link .icon:only-child{margin-left:-.25rem;margin-right:-.25rem}.navbar-link,a.navbar-item{cursor:pointer}.navbar-link.is-active,.navbar-link:focus,.navbar-link:focus-within,.navbar-link:hover,a.navbar-item.is-active,a.navbar-item:focus,a.navbar-item:focus-within,a.navbar-item:hover{background-color:#fafafa;color:#3273dc}.navbar-item{flex-grow:0;flex-shrink:0}.navbar-item img{max-height:1.75rem}.navbar-item.has-dropdown{padding:0}.navbar-item.is-expanded{flex-grow:1;flex-shrink:1}.navbar-item.is-tab{border-bottom:1px solid transparent;min-height:3.25rem;padding-bottom:calc(.5rem - 1px)}.navbar-item.is-tab:focus,.navbar-item.is-tab:hover{background-color:transparent;border-bottom-color:#3273dc}.navbar-item.is-tab.is-active{background-color:transparent;border-bottom-color:#3273dc;border-bottom-style:solid;border-bottom-width:3px;color:#3273dc;padding-bottom:calc(.5rem - 3px)}.navbar-content{flex-grow:1;flex-shrink:1}.navbar-link:not(.is-arrowless){padding-right:2.5em}.navbar-link:not(.is-arrowless)::after{border-color:#3273dc;margin-top:-.375em;right:1.125em}.navbar-dropdown{font-size:.875rem;padding-bottom:.5rem;padding-top:.5rem}.navbar-dropdown .navbar-item{padding-left:1.5rem;padding-right:1.5rem}.navbar-divider{background-color:#f5f5f5;border:none;display:none;height:2px;margin:.5rem 0}@media screen and (max-width:1023px){.navbar>.container{display:block}.navbar-brand .navbar-item,.navbar-tabs .navbar-item{align-items:center;display:flex}.navbar-link::after{display:none}.navbar-menu{background-color:#fff;box-shadow:0 8px 16px rgba(10,10,10,.1);padding:.5rem 0}.navbar-menu.is-active{display:block}.navbar.is-fixed-bottom-touch,.navbar.is-fixed-top-touch{left:0;position:fixed;right:0;z-index:30}.navbar.is-fixed-bottom-touch{bottom:0}.navbar.is-fixed-bottom-touch.has-shadow{box-shadow:0 -2px 3px rgba(10,10,10,.1)}.navbar.is-fixed-top-touch{top:0}.navbar.is-fixed-top .navbar-menu,.navbar.is-fixed-top-touch .navbar-menu{-webkit-overflow-scrolling:touch;max-height:calc(100vh - 3.25rem);overflow:auto}body.has-navbar-fixed-top-touch,html.has-navbar-fixed-top-touch{padding-top:3.25rem}body.has-navbar-fixed-bottom-touch,html.has-navbar-fixed-bottom-touch{padding-bottom:3.25rem}}@media screen and (min-width:1024px){.navbar,.navbar-end,.navbar-menu,.navbar-start{align-items:stretch;display:flex}.navbar{min-height:3.25rem}.navbar.is-spaced{padding:1rem 2rem}.navbar.is-spaced .navbar-end,.navbar.is-spaced .navbar-start{align-items:center}.navbar.is-spaced .navbar-link,.navbar.is-spaced a.navbar-item{border-radius:4px}.navbar.is-transparent .navbar-link.is-active,.navbar.is-transparent .navbar-link:focus,.navbar.is-transparent .navbar-link:hover,.navbar.is-transparent a.navbar-item.is-active,.navbar.is-transparent a.navbar-item:focus,.navbar.is-transparent a.navbar-item:hover{background-color:transparent!important}.navbar.is-transparent .navbar-item.has-dropdown.is-active .navbar-link,.navbar.is-transparent .navbar-item.has-dropdown.is-hoverable:focus .navbar-link,.navbar.is-transparent .navbar-item.has-dropdown.is-hoverable:focus-within .navbar-link,.navbar.is-transparent .navbar-item.has-dropdown.is-hoverable:hover .navbar-link{background-color:transparent!important}.navbar.is-transparent .navbar-dropdown a.navbar-item:focus,.navbar.is-transparent .navbar-dropdown a.navbar-item:hover{background-color:#f5f5f5;color:#0a0a0a}.navbar.is-transparent .navbar-dropdown a.navbar-item.is-active{background-color:#f5f5f5;color:#3273dc}.navbar-burger{display:none}.navbar-item,.navbar-link{align-items:center;display:flex}.navbar-item.has-dropdown{align-items:stretch}.navbar-item.has-dropdown-up .navbar-link::after{transform:rotate(135deg) translate(.25em,-.25em)}.navbar-item.has-dropdown-up .navbar-dropdown{border-bottom:2px solid #dbdbdb;border-radius:6px 6px 0 0;border-top:none;bottom:100%;box-shadow:0 -8px 8px rgba(10,10,10,.1);top:auto}.navbar-item.is-active .navbar-dropdown,.navbar-item.is-hoverable:focus .navbar-dropdown,.navbar-item.is-hoverable:focus-within .navbar-dropdown,.navbar-item.is-hoverable:hover .navbar-dropdown{display:block}.navbar-item.is-active .navbar-dropdown.is-boxed,.navbar-item.is-hoverable:focus .navbar-dropdown.is-boxed,.navbar-item.is-hoverable:focus-within .navbar-dropdown.is-boxed,.navbar-item.is-hoverable:hover .navbar-dropdown.is-boxed,.navbar.is-spaced .navbar-item.is-active .navbar-dropdown,.navbar.is-spaced .navbar-item.is-hoverable:focus .navbar-dropdown,.navbar.is-spaced .navbar-item.is-hoverable:focus-within .navbar-dropdown,.navbar.is-spaced .navbar-item.is-hoverable:hover .navbar-dropdown{opacity:1;pointer-events:auto;transform:translateY(0)}.navbar-menu{flex-grow:1;flex-shrink:0}.navbar-start{justify-content:flex-start;margin-right:auto}.navbar-end{justify-content:flex-end;margin-left:auto}.navbar-dropdown{background-color:#fff;border-bottom-left-radius:6px;border-bottom-right-radius:6px;border-top:2px solid #dbdbdb;box-shadow:0 8px 8px rgba(10,10,10,.1);display:none;font-size:.875rem;left:0;min-width:100%;position:absolute;top:100%;z-index:20}.navbar-dropdown .navbar-item{padding:.375rem 1rem;white-space:nowrap}.navbar-dropdown a.navbar-item{padding-right:3rem}.navbar-dropdown a.navbar-item:focus,.navbar-dropdown a.navbar-item:hover{background-color:#f5f5f5;color:#0a0a0a}.navbar-dropdown a.navbar-item.is-active{background-color:#f5f5f5;color:#3273dc}.navbar-dropdown.is-boxed,.navbar.is-spaced .navbar-dropdown{border-radius:6px;border-top:none;box-shadow:0 8px 8px rgba(10,10,10,.1),0 0 0 1px rgba(10,10,10,.1);display:block;opacity:0;pointer-events:none;top:calc(100% + (-4px));transform:translateY(-5px);transition-duration:86ms;transition-property:opacity,transform}.navbar-dropdown.is-right{left:auto;right:0}.navbar-divider{display:block}.container>.navbar .navbar-brand,.navbar>.container .navbar-brand{margin-left:-.75rem}.container>.navbar .navbar-menu,.navbar>.container .navbar-menu{margin-right:-.75rem}.navbar.is-fixed-bottom-desktop,.navbar.is-fixed-top-desktop{left:0;position:fixed;right:0;z-index:30}.navbar.is-fixed-bottom-desktop{bottom:0}.navbar.is-fixed-bottom-desktop.has-shadow{box-shadow:0 -2px 3px rgba(10,10,10,.1)}.navbar.is-fixed-top-desktop{top:0}body.has-navbar-fixed-top-desktop,html.has-navbar-fixed-top-desktop{padding-top:3.25rem}body.has-navbar-fixed-bottom-desktop,html.has-navbar-fixed-bottom-desktop{padding-bottom:3.25rem}body.has-spaced-navbar-fixed-top,html.has-spaced-navbar-fixed-top{padding-top:5.25rem}body.has-spaced-navbar-fixed-bottom,html.has-spaced-navbar-fixed-bottom{padding-bottom:5.25rem}.navbar-link.is-active,a.navbar-item.is-active{color:#0a0a0a}.navbar-link.is-active:not(:focus):not(:hover),a.navbar-item.is-active:not(:focus):not(:hover){background-color:transparent}.navbar-item.has-dropdown.is-active .navbar-link,.navbar-item.has-dropdown:focus .navbar-link,.navbar-item.has-dropdown:hover .navbar-link{background-color:#fafafa}}.hero.is-fullheight-with-navbar{min-height:calc(100vh - 3.25rem)}.pagination{font-size:1rem;margin:-.25rem}.pagination.is-small{font-size:.75rem}.pagination.is-medium{font-size:1.25rem}.pagination.is-large{font-size:1.5rem}.pagination.is-rounded .pagination-next,.pagination.is-rounded .pagination-previous{padding-left:1em;padding-right:1em;border-radius:290486px}.pagination.is-rounded .pagination-link{border-radius:290486px}.pagination,.pagination-list{align-items:center;display:flex;justify-content:center;text-align:center}.pagination-ellipsis,.pagination-link,.pagination-next,.pagination-previous{font-size:1em;justify-content:center;margin:.25rem;padding-left:.5em;padding-right:.5em;text-align:center}.pagination-link,.pagination-next,.pagination-previous{border-color:#dbdbdb;color:#363636;min-width:2.5em}.pagination-link:hover,.pagination-next:hover,.pagination-previous:hover{border-color:#b5b5b5;color:#363636}.pagination-link:focus,.pagination-next:focus,.pagination-previous:focus{border-color:#3273dc}.pagination-link:active,.pagination-next:active,.pagination-previous:active{box-shadow:inset 0 1px 2px rgba(10,10,10,.2)}.pagination-link[disabled],.pagination-next[disabled],.pagination-previous[disabled]{background-color:#dbdbdb;border-color:#dbdbdb;box-shadow:none;color:#7a7a7a;opacity:.5}.pagination-next,.pagination-previous{padding-left:.75em;padding-right:.75em;white-space:nowrap}.pagination-link.is-current{background-color:#3273dc;border-color:#3273dc;color:#fff}.pagination-ellipsis{color:#b5b5b5;pointer-events:none}.pagination-list{flex-wrap:wrap}@media screen and (max-width:768px){.pagination{flex-wrap:wrap}.pagination-next,.pagination-previous{flex-grow:1;flex-shrink:1}.pagination-list li{flex-grow:1;flex-shrink:1}}@media screen and (min-width:769px),print{.pagination-list{flex-grow:1;flex-shrink:1;justify-content:flex-start;order:1}.pagination-previous{order:2}.pagination-next{order:3}.pagination{justify-content:space-between}.pagination.is-centered .pagination-previous{order:1}.pagination.is-centered .pagination-list{justify-content:center;order:2}.pagination.is-centered .pagination-next{order:3}.pagination.is-right .pagination-previous{order:1}.pagination.is-right .pagination-next{order:2}.pagination.is-right .pagination-list{justify-content:flex-end;order:3}}.panel{border-radius:6px;box-shadow:0 .5em 1em -.125em rgba(10,10,10,.1),0 0 0 1px rgba(10,10,10,.02);font-size:1rem}.panel:not(:last-child){margin-bottom:1.5rem}.panel.is-white .panel-heading{background-color:#fff;color:#0a0a0a}.panel.is-white .panel-tabs a.is-active{border-bottom-color:#fff}.panel.is-white .panel-block.is-active .panel-icon{color:#fff}.panel.is-black .panel-heading{background-color:#0a0a0a;color:#fff}.panel.is-black .panel-tabs a.is-active{border-bottom-color:#0a0a0a}.panel.is-black .panel-block.is-active .panel-icon{color:#0a0a0a}.panel.is-light .panel-heading{background-color:#f5f5f5;color:rgba(0,0,0,.7)}.panel.is-light .panel-tabs a.is-active{border-bottom-color:#f5f5f5}.panel.is-light .panel-block.is-active .panel-icon{color:#f5f5f5}.panel.is-dark .panel-heading{background-color:#363636;color:#fff}.panel.is-dark .panel-tabs a.is-active{border-bottom-color:#363636}.panel.is-dark .panel-block.is-active .panel-icon{color:#363636}.panel.is-primary .panel-heading{background-color:#00d1b2;color:#fff}.panel.is-primary .panel-tabs a.is-active{border-bottom-color:#00d1b2}.panel.is-primary .panel-block.is-active .panel-icon{color:#00d1b2}.panel.is-link .panel-heading{background-color:#3273dc;color:#fff}.panel.is-link .panel-tabs a.is-active{border-bottom-color:#3273dc}.panel.is-link .panel-block.is-active .panel-icon{color:#3273dc}.panel.is-info .panel-heading{background-color:#3298dc;color:#fff}.panel.is-info .panel-tabs a.is-active{border-bottom-color:#3298dc}.panel.is-info .panel-block.is-active .panel-icon{color:#3298dc}.panel.is-success .panel-heading{background-color:#48c774;color:#fff}.panel.is-success .panel-tabs a.is-active{border-bottom-color:#48c774}.panel.is-success .panel-block.is-active .panel-icon{color:#48c774}.panel.is-warning .panel-heading{background-color:#ffdd57;color:rgba(0,0,0,.7)}.panel.is-warning .panel-tabs a.is-active{border-bottom-color:#ffdd57}.panel.is-warning .panel-block.is-active .panel-icon{color:#ffdd57}.panel.is-danger .panel-heading{background-color:#f14668;color:#fff}.panel.is-danger .panel-tabs a.is-active{border-bottom-color:#f14668}.panel.is-danger .panel-block.is-active .panel-icon{color:#f14668}.panel-block:not(:last-child),.panel-tabs:not(:last-child){border-bottom:1px solid #ededed}.panel-heading{background-color:#ededed;border-radius:6px 6px 0 0;color:#363636;font-size:1.25em;font-weight:700;line-height:1.25;padding:.75em 1em}.panel-tabs{align-items:flex-end;display:flex;font-size:.875em;justify-content:center}.panel-tabs a{border-bottom:1px solid #dbdbdb;margin-bottom:-1px;padding:.5em}.panel-tabs a.is-active{border-bottom-color:#4a4a4a;color:#363636}.panel-list a{color:#4a4a4a}.panel-list a:hover{color:#3273dc}.panel-block{align-items:center;color:#363636;display:flex;justify-content:flex-start;padding:.5em .75em}.panel-block input[type=checkbox]{margin-right:.75em}.panel-block>.control{flex-grow:1;flex-shrink:1;width:100%}.panel-block.is-wrapped{flex-wrap:wrap}.panel-block.is-active{border-left-color:#3273dc;color:#363636}.panel-block.is-active .panel-icon{color:#3273dc}.panel-block:last-child{border-bottom-left-radius:6px;border-bottom-right-radius:6px}a.panel-block,label.panel-block{cursor:pointer}a.panel-block:hover,label.panel-block:hover{background-color:#f5f5f5}.panel-icon{display:inline-block;font-size:14px;height:1em;line-height:1em;text-align:center;vertical-align:top;width:1em;color:#7a7a7a;margin-right:.75em}.panel-icon .fa{font-size:inherit;line-height:inherit}.tabs{-webkit-overflow-scrolling:touch;align-items:stretch;display:flex;font-size:1rem;justify-content:space-between;overflow:hidden;overflow-x:auto;white-space:nowrap}.tabs a{align-items:center;border-bottom-color:#dbdbdb;border-bottom-style:solid;border-bottom-width:1px;color:#4a4a4a;display:flex;justify-content:center;margin-bottom:-1px;padding:.5em 1em;vertical-align:top}.tabs a:hover{border-bottom-color:#363636;color:#363636}.tabs li{display:block}.tabs li.is-active a{border-bottom-color:#3273dc;color:#3273dc}.tabs ul{align-items:center;border-bottom-color:#dbdbdb;border-bottom-style:solid;border-bottom-width:1px;display:flex;flex-grow:1;flex-shrink:0;justify-content:flex-start}.tabs ul.is-left{padding-right:.75em}.tabs ul.is-center{flex:none;justify-content:center;padding-left:.75em;padding-right:.75em}.tabs ul.is-right{justify-content:flex-end;padding-left:.75em}.tabs .icon:first-child{margin-right:.5em}.tabs .icon:last-child{margin-left:.5em}.tabs.is-centered ul{justify-content:center}.tabs.is-right ul{justify-content:flex-end}.tabs.is-boxed a{border:1px solid transparent;border-radius:4px 4px 0 0}.tabs.is-boxed a:hover{background-color:#f5f5f5;border-bottom-color:#dbdbdb}.tabs.is-boxed li.is-active a{background-color:#fff;border-color:#dbdbdb;border-bottom-color:transparent!important}.tabs.is-fullwidth li{flex-grow:1;flex-shrink:0}.tabs.is-toggle a{border-color:#dbdbdb;border-style:solid;border-width:1px;margin-bottom:0;position:relative}.tabs.is-toggle a:hover{background-color:#f5f5f5;border-color:#b5b5b5;z-index:2}.tabs.is-toggle li+li{margin-left:-1px}.tabs.is-toggle li:first-child a{border-top-left-radius:4px;border-bottom-left-radius:4px}.tabs.is-toggle li:last-child a{border-top-right-radius:4px;border-bottom-right-radius:4px}.tabs.is-toggle li.is-active a{background-color:#3273dc;border-color:#3273dc;color:#fff;z-index:1}.tabs.is-toggle ul{border-bottom:none}.tabs.is-toggle.is-toggle-rounded li:first-child a{border-bottom-left-radius:290486px;border-top-left-radius:290486px;padding-left:1.25em}.tabs.is-toggle.is-toggle-rounded li:last-child a{border-bottom-right-radius:290486px;border-top-right-radius:290486px;padding-right:1.25em}.tabs.is-small{font-size:.75rem}.tabs.is-medium{font-size:1.25rem}.tabs.is-large{font-size:1.5rem}.column{display:block;flex-basis:0;flex-grow:1;flex-shrink:1;padding:.75rem}.columns.is-mobile>.column.is-narrow{flex:none}.columns.is-mobile>.column.is-full{flex:none;width:100%}.columns.is-mobile>.column.is-three-quarters{flex:none;width:75%}.columns.is-mobile>.column.is-two-thirds{flex:none;width:66.6666%}.columns.is-mobile>.column.is-half{flex:none;width:50%}.columns.is-mobile>.column.is-one-third{flex:none;width:33.3333%}.columns.is-mobile>.column.is-one-quarter{flex:none;width:25%}.columns.is-mobile>.column.is-one-fifth{flex:none;width:20%}.columns.is-mobile>.column.is-two-fifths{flex:none;width:40%}.columns.is-mobile>.column.is-three-fifths{flex:none;width:60%}.columns.is-mobile>.column.is-four-fifths{flex:none;width:80%}.columns.is-mobile>.column.is-offset-three-quarters{margin-left:75%}.columns.is-mobile>.column.is-offset-two-thirds{margin-left:66.6666%}.columns.is-mobile>.column.is-offset-half{margin-left:50%}.columns.is-mobile>.column.is-offset-one-third{margin-left:33.3333%}.columns.is-mobile>.column.is-offset-one-quarter{margin-left:25%}.columns.is-mobile>.column.is-offset-one-fifth{margin-left:20%}.columns.is-mobile>.column.is-offset-two-fifths{margin-left:40%}.columns.is-mobile>.column.is-offset-three-fifths{margin-left:60%}.columns.is-mobile>.column.is-offset-four-fifths{margin-left:80%}.columns.is-mobile>.column.is-0{flex:none;width:0%}.columns.is-mobile>.column.is-offset-0{margin-left:0}.columns.is-mobile>.column.is-1{flex:none;width:8.33333%}.columns.is-mobile>.column.is-offset-1{margin-left:8.33333%}.columns.is-mobile>.column.is-2{flex:none;width:16.66667%}.columns.is-mobile>.column.is-offset-2{margin-left:16.66667%}.columns.is-mobile>.column.is-3{flex:none;width:25%}.columns.is-mobile>.column.is-offset-3{margin-left:25%}.columns.is-mobile>.column.is-4{flex:none;width:33.33333%}.columns.is-mobile>.column.is-offset-4{margin-left:33.33333%}.columns.is-mobile>.column.is-5{flex:none;width:41.66667%}.columns.is-mobile>.column.is-offset-5{margin-left:41.66667%}.columns.is-mobile>.column.is-6{flex:none;width:50%}.columns.is-mobile>.column.is-offset-6{margin-left:50%}.columns.is-mobile>.column.is-7{flex:none;width:58.33333%}.columns.is-mobile>.column.is-offset-7{margin-left:58.33333%}.columns.is-mobile>.column.is-8{flex:none;width:66.66667%}.columns.is-mobile>.column.is-offset-8{margin-left:66.66667%}.columns.is-mobile>.column.is-9{flex:none;width:75%}.columns.is-mobile>.column.is-offset-9{margin-left:75%}.columns.is-mobile>.column.is-10{flex:none;width:83.33333%}.columns.is-mobile>.column.is-offset-10{margin-left:83.33333%}.columns.is-mobile>.column.is-11{flex:none;width:91.66667%}.columns.is-mobile>.column.is-offset-11{margin-left:91.66667%}.columns.is-mobile>.column.is-12{flex:none;width:100%}.columns.is-mobile>.column.is-offset-12{margin-left:100%}@media screen and (max-width:768px){.column.is-narrow-mobile{flex:none}.column.is-full-mobile{flex:none;width:100%}.column.is-three-quarters-mobile{flex:none;width:75%}.column.is-two-thirds-mobile{flex:none;width:66.6666%}.column.is-half-mobile{flex:none;width:50%}.column.is-one-third-mobile{flex:none;width:33.3333%}.column.is-one-quarter-mobile{flex:none;width:25%}.column.is-one-fifth-mobile{flex:none;width:20%}.column.is-two-fifths-mobile{flex:none;width:40%}.column.is-three-fifths-mobile{flex:none;width:60%}.column.is-four-fifths-mobile{flex:none;width:80%}.column.is-offset-three-quarters-mobile{margin-left:75%}.column.is-offset-two-thirds-mobile{margin-left:66.6666%}.column.is-offset-half-mobile{margin-left:50%}.column.is-offset-one-third-mobile{margin-left:33.3333%}.column.is-offset-one-quarter-mobile{margin-left:25%}.column.is-offset-one-fifth-mobile{margin-left:20%}.column.is-offset-two-fifths-mobile{margin-left:40%}.column.is-offset-three-fifths-mobile{margin-left:60%}.column.is-offset-four-fifths-mobile{margin-left:80%}.column.is-0-mobile{flex:none;width:0%}.column.is-offset-0-mobile{margin-left:0}.column.is-1-mobile{flex:none;width:8.33333%}.column.is-offset-1-mobile{margin-left:8.33333%}.column.is-2-mobile{flex:none;width:16.66667%}.column.is-offset-2-mobile{margin-left:16.66667%}.column.is-3-mobile{flex:none;width:25%}.column.is-offset-3-mobile{margin-left:25%}.column.is-4-mobile{flex:none;width:33.33333%}.column.is-offset-4-mobile{margin-left:33.33333%}.column.is-5-mobile{flex:none;width:41.66667%}.column.is-offset-5-mobile{margin-left:41.66667%}.column.is-6-mobile{flex:none;width:50%}.column.is-offset-6-mobile{margin-left:50%}.column.is-7-mobile{flex:none;width:58.33333%}.column.is-offset-7-mobile{margin-left:58.33333%}.column.is-8-mobile{flex:none;width:66.66667%}.column.is-offset-8-mobile{margin-left:66.66667%}.column.is-9-mobile{flex:none;width:75%}.column.is-offset-9-mobile{margin-left:75%}.column.is-10-mobile{flex:none;width:83.33333%}.column.is-offset-10-mobile{margin-left:83.33333%}.column.is-11-mobile{flex:none;width:91.66667%}.column.is-offset-11-mobile{margin-left:91.66667%}.column.is-12-mobile{flex:none;width:100%}.column.is-offset-12-mobile{margin-left:100%}}@media screen and (min-width:769px),print{.column.is-narrow,.column.is-narrow-tablet{flex:none}.column.is-full,.column.is-full-tablet{flex:none;width:100%}.column.is-three-quarters,.column.is-three-quarters-tablet{flex:none;width:75%}.column.is-two-thirds,.column.is-two-thirds-tablet{flex:none;width:66.6666%}.column.is-half,.column.is-half-tablet{flex:none;width:50%}.column.is-one-third,.column.is-one-third-tablet{flex:none;width:33.3333%}.column.is-one-quarter,.column.is-one-quarter-tablet{flex:none;width:25%}.column.is-one-fifth,.column.is-one-fifth-tablet{flex:none;width:20%}.column.is-two-fifths,.column.is-two-fifths-tablet{flex:none;width:40%}.column.is-three-fifths,.column.is-three-fifths-tablet{flex:none;width:60%}.column.is-four-fifths,.column.is-four-fifths-tablet{flex:none;width:80%}.column.is-offset-three-quarters,.column.is-offset-three-quarters-tablet{margin-left:75%}.column.is-offset-two-thirds,.column.is-offset-two-thirds-tablet{margin-left:66.6666%}.column.is-offset-half,.column.is-offset-half-tablet{margin-left:50%}.column.is-offset-one-third,.column.is-offset-one-third-tablet{margin-left:33.3333%}.column.is-offset-one-quarter,.column.is-offset-one-quarter-tablet{margin-left:25%}.column.is-offset-one-fifth,.column.is-offset-one-fifth-tablet{margin-left:20%}.column.is-offset-two-fifths,.column.is-offset-two-fifths-tablet{margin-left:40%}.column.is-offset-three-fifths,.column.is-offset-three-fifths-tablet{margin-left:60%}.column.is-offset-four-fifths,.column.is-offset-four-fifths-tablet{margin-left:80%}.column.is-0,.column.is-0-tablet{flex:none;width:0%}.column.is-offset-0,.column.is-offset-0-tablet{margin-left:0}.column.is-1,.column.is-1-tablet{flex:none;width:8.33333%}.column.is-offset-1,.column.is-offset-1-tablet{margin-left:8.33333%}.column.is-2,.column.is-2-tablet{flex:none;width:16.66667%}.column.is-offset-2,.column.is-offset-2-tablet{margin-left:16.66667%}.column.is-3,.column.is-3-tablet{flex:none;width:25%}.column.is-offset-3,.column.is-offset-3-tablet{margin-left:25%}.column.is-4,.column.is-4-tablet{flex:none;width:33.33333%}.column.is-offset-4,.column.is-offset-4-tablet{margin-left:33.33333%}.column.is-5,.column.is-5-tablet{flex:none;width:41.66667%}.column.is-offset-5,.column.is-offset-5-tablet{margin-left:41.66667%}.column.is-6,.column.is-6-tablet{flex:none;width:50%}.column.is-offset-6,.column.is-offset-6-tablet{margin-left:50%}.column.is-7,.column.is-7-tablet{flex:none;width:58.33333%}.column.is-offset-7,.column.is-offset-7-tablet{margin-left:58.33333%}.column.is-8,.column.is-8-tablet{flex:none;width:66.66667%}.column.is-offset-8,.column.is-offset-8-tablet{margin-left:66.66667%}.column.is-9,.column.is-9-tablet{flex:none;width:75%}.column.is-offset-9,.column.is-offset-9-tablet{margin-left:75%}.column.is-10,.column.is-10-tablet{flex:none;width:83.33333%}.column.is-offset-10,.column.is-offset-10-tablet{margin-left:83.33333%}.column.is-11,.column.is-11-tablet{flex:none;width:91.66667%}.column.is-offset-11,.column.is-offset-11-tablet{margin-left:91.66667%}.column.is-12,.column.is-12-tablet{flex:none;width:100%}.column.is-offset-12,.column.is-offset-12-tablet{margin-left:100%}}@media screen and (max-width:1023px){.column.is-narrow-touch{flex:none}.column.is-full-touch{flex:none;width:100%}.column.is-three-quarters-touch{flex:none;width:75%}.column.is-two-thirds-touch{flex:none;width:66.6666%}.column.is-half-touch{flex:none;width:50%}.column.is-one-third-touch{flex:none;width:33.3333%}.column.is-one-quarter-touch{flex:none;width:25%}.column.is-one-fifth-touch{flex:none;width:20%}.column.is-two-fifths-touch{flex:none;width:40%}.column.is-three-fifths-touch{flex:none;width:60%}.column.is-four-fifths-touch{flex:none;width:80%}.column.is-offset-three-quarters-touch{margin-left:75%}.column.is-offset-two-thirds-touch{margin-left:66.6666%}.column.is-offset-half-touch{margin-left:50%}.column.is-offset-one-third-touch{margin-left:33.3333%}.column.is-offset-one-quarter-touch{margin-left:25%}.column.is-offset-one-fifth-touch{margin-left:20%}.column.is-offset-two-fifths-touch{margin-left:40%}.column.is-offset-three-fifths-touch{margin-left:60%}.column.is-offset-four-fifths-touch{margin-left:80%}.column.is-0-touch{flex:none;width:0%}.column.is-offset-0-touch{margin-left:0}.column.is-1-touch{flex:none;width:8.33333%}.column.is-offset-1-touch{margin-left:8.33333%}.column.is-2-touch{flex:none;width:16.66667%}.column.is-offset-2-touch{margin-left:16.66667%}.column.is-3-touch{flex:none;width:25%}.column.is-offset-3-touch{margin-left:25%}.column.is-4-touch{flex:none;width:33.33333%}.column.is-offset-4-touch{margin-left:33.33333%}.column.is-5-touch{flex:none;width:41.66667%}.column.is-offset-5-touch{margin-left:41.66667%}.column.is-6-touch{flex:none;width:50%}.column.is-offset-6-touch{margin-left:50%}.column.is-7-touch{flex:none;width:58.33333%}.column.is-offset-7-touch{margin-left:58.33333%}.column.is-8-touch{flex:none;width:66.66667%}.column.is-offset-8-touch{margin-left:66.66667%}.column.is-9-touch{flex:none;width:75%}.column.is-offset-9-touch{margin-left:75%}.column.is-10-touch{flex:none;width:83.33333%}.column.is-offset-10-touch{margin-left:83.33333%}.column.is-11-touch{flex:none;width:91.66667%}.column.is-offset-11-touch{margin-left:91.66667%}.column.is-12-touch{flex:none;width:100%}.column.is-offset-12-touch{margin-left:100%}}@media screen and (min-width:1024px){.column.is-narrow-desktop{flex:none}.column.is-full-desktop{flex:none;width:100%}.column.is-three-quarters-desktop{flex:none;width:75%}.column.is-two-thirds-desktop{flex:none;width:66.6666%}.column.is-half-desktop{flex:none;width:50%}.column.is-one-third-desktop{flex:none;width:33.3333%}.column.is-one-quarter-desktop{flex:none;width:25%}.column.is-one-fifth-desktop{flex:none;width:20%}.column.is-two-fifths-desktop{flex:none;width:40%}.column.is-three-fifths-desktop{flex:none;width:60%}.column.is-four-fifths-desktop{flex:none;width:80%}.column.is-offset-three-quarters-desktop{margin-left:75%}.column.is-offset-two-thirds-desktop{margin-left:66.6666%}.column.is-offset-half-desktop{margin-left:50%}.column.is-offset-one-third-desktop{margin-left:33.3333%}.column.is-offset-one-quarter-desktop{margin-left:25%}.column.is-offset-one-fifth-desktop{margin-left:20%}.column.is-offset-two-fifths-desktop{margin-left:40%}.column.is-offset-three-fifths-desktop{margin-left:60%}.column.is-offset-four-fifths-desktop{margin-left:80%}.column.is-0-desktop{flex:none;width:0%}.column.is-offset-0-desktop{margin-left:0}.column.is-1-desktop{flex:none;width:8.33333%}.column.is-offset-1-desktop{margin-left:8.33333%}.column.is-2-desktop{flex:none;width:16.66667%}.column.is-offset-2-desktop{margin-left:16.66667%}.column.is-3-desktop{flex:none;width:25%}.column.is-offset-3-desktop{margin-left:25%}.column.is-4-desktop{flex:none;width:33.33333%}.column.is-offset-4-desktop{margin-left:33.33333%}.column.is-5-desktop{flex:none;width:41.66667%}.column.is-offset-5-desktop{margin-left:41.66667%}.column.is-6-desktop{flex:none;width:50%}.column.is-offset-6-desktop{margin-left:50%}.column.is-7-desktop{flex:none;width:58.33333%}.column.is-offset-7-desktop{margin-left:58.33333%}.column.is-8-desktop{flex:none;width:66.66667%}.column.is-offset-8-desktop{margin-left:66.66667%}.column.is-9-desktop{flex:none;width:75%}.column.is-offset-9-desktop{margin-left:75%}.column.is-10-desktop{flex:none;width:83.33333%}.column.is-offset-10-desktop{margin-left:83.33333%}.column.is-11-desktop{flex:none;width:91.66667%}.column.is-offset-11-desktop{margin-left:91.66667%}.column.is-12-desktop{flex:none;width:100%}.column.is-offset-12-desktop{margin-left:100%}}@media screen and (min-width:1216px){.column.is-narrow-widescreen{flex:none}.column.is-full-widescreen{flex:none;width:100%}.column.is-three-quarters-widescreen{flex:none;width:75%}.column.is-two-thirds-widescreen{flex:none;width:66.6666%}.column.is-half-widescreen{flex:none;width:50%}.column.is-one-third-widescreen{flex:none;width:33.3333%}.column.is-one-quarter-widescreen{flex:none;width:25%}.column.is-one-fifth-widescreen{flex:none;width:20%}.column.is-two-fifths-widescreen{flex:none;width:40%}.column.is-three-fifths-widescreen{flex:none;width:60%}.column.is-four-fifths-widescreen{flex:none;width:80%}.column.is-offset-three-quarters-widescreen{margin-left:75%}.column.is-offset-two-thirds-widescreen{margin-left:66.6666%}.column.is-offset-half-widescreen{margin-left:50%}.column.is-offset-one-third-widescreen{margin-left:33.3333%}.column.is-offset-one-quarter-widescreen{margin-left:25%}.column.is-offset-one-fifth-widescreen{margin-left:20%}.column.is-offset-two-fifths-widescreen{margin-left:40%}.column.is-offset-three-fifths-widescreen{margin-left:60%}.column.is-offset-four-fifths-widescreen{margin-left:80%}.column.is-0-widescreen{flex:none;width:0%}.column.is-offset-0-widescreen{margin-left:0}.column.is-1-widescreen{flex:none;width:8.33333%}.column.is-offset-1-widescreen{margin-left:8.33333%}.column.is-2-widescreen{flex:none;width:16.66667%}.column.is-offset-2-widescreen{margin-left:16.66667%}.column.is-3-widescreen{flex:none;width:25%}.column.is-offset-3-widescreen{margin-left:25%}.column.is-4-widescreen{flex:none;width:33.33333%}.column.is-offset-4-widescreen{margin-left:33.33333%}.column.is-5-widescreen{flex:none;width:41.66667%}.column.is-offset-5-widescreen{margin-left:41.66667%}.column.is-6-widescreen{flex:none;width:50%}.column.is-offset-6-widescreen{margin-left:50%}.column.is-7-widescreen{flex:none;width:58.33333%}.column.is-offset-7-widescreen{margin-left:58.33333%}.column.is-8-widescreen{flex:none;width:66.66667%}.column.is-offset-8-widescreen{margin-left:66.66667%}.column.is-9-widescreen{flex:none;width:75%}.column.is-offset-9-widescreen{margin-left:75%}.column.is-10-widescreen{flex:none;width:83.33333%}.column.is-offset-10-widescreen{margin-left:83.33333%}.column.is-11-widescreen{flex:none;width:91.66667%}.column.is-offset-11-widescreen{margin-left:91.66667%}.column.is-12-widescreen{flex:none;width:100%}.column.is-offset-12-widescreen{margin-left:100%}}@media screen and (min-width:1408px){.column.is-narrow-fullhd{flex:none}.column.is-full-fullhd{flex:none;width:100%}.column.is-three-quarters-fullhd{flex:none;width:75%}.column.is-two-thirds-fullhd{flex:none;width:66.6666%}.column.is-half-fullhd{flex:none;width:50%}.column.is-one-third-fullhd{flex:none;width:33.3333%}.column.is-one-quarter-fullhd{flex:none;width:25%}.column.is-one-fifth-fullhd{flex:none;width:20%}.column.is-two-fifths-fullhd{flex:none;width:40%}.column.is-three-fifths-fullhd{flex:none;width:60%}.column.is-four-fifths-fullhd{flex:none;width:80%}.column.is-offset-three-quarters-fullhd{margin-left:75%}.column.is-offset-two-thirds-fullhd{margin-left:66.6666%}.column.is-offset-half-fullhd{margin-left:50%}.column.is-offset-one-third-fullhd{margin-left:33.3333%}.column.is-offset-one-quarter-fullhd{margin-left:25%}.column.is-offset-one-fifth-fullhd{margin-left:20%}.column.is-offset-two-fifths-fullhd{margin-left:40%}.column.is-offset-three-fifths-fullhd{margin-left:60%}.column.is-offset-four-fifths-fullhd{margin-left:80%}.column.is-0-fullhd{flex:none;width:0%}.column.is-offset-0-fullhd{margin-left:0}.column.is-1-fullhd{flex:none;width:8.33333%}.column.is-offset-1-fullhd{margin-left:8.33333%}.column.is-2-fullhd{flex:none;width:16.66667%}.column.is-offset-2-fullhd{margin-left:16.66667%}.column.is-3-fullhd{flex:none;width:25%}.column.is-offset-3-fullhd{margin-left:25%}.column.is-4-fullhd{flex:none;width:33.33333%}.column.is-offset-4-fullhd{margin-left:33.33333%}.column.is-5-fullhd{flex:none;width:41.66667%}.column.is-offset-5-fullhd{margin-left:41.66667%}.column.is-6-fullhd{flex:none;width:50%}.column.is-offset-6-fullhd{margin-left:50%}.column.is-7-fullhd{flex:none;width:58.33333%}.column.is-offset-7-fullhd{margin-left:58.33333%}.column.is-8-fullhd{flex:none;width:66.66667%}.column.is-offset-8-fullhd{margin-left:66.66667%}.column.is-9-fullhd{flex:none;width:75%}.column.is-offset-9-fullhd{margin-left:75%}.column.is-10-fullhd{flex:none;width:83.33333%}.column.is-offset-10-fullhd{margin-left:83.33333%}.column.is-11-fullhd{flex:none;width:91.66667%}.column.is-offset-11-fullhd{margin-left:91.66667%}.column.is-12-fullhd{flex:none;width:100%}.column.is-offset-12-fullhd{margin-left:100%}}.columns{margin-left:-.75rem;margin-right:-.75rem;margin-top:-.75rem}.columns:last-child{margin-bottom:-.75rem}.columns:not(:last-child){margin-bottom:calc(1.5rem - .75rem)}.columns.is-centered{justify-content:center}.columns.is-gapless{margin-left:0;margin-right:0;margin-top:0}.columns.is-gapless>.column{margin:0;padding:0!important}.columns.is-gapless:not(:last-child){margin-bottom:1.5rem}.columns.is-gapless:last-child{margin-bottom:0}.columns.is-mobile{display:flex}.columns.is-multiline{flex-wrap:wrap}.columns.is-vcentered{align-items:center}@media screen and (min-width:769px),print{.columns:not(.is-desktop){display:flex}}@media screen and (min-width:1024px){.columns.is-desktop{display:flex}}.columns.is-variable{--columnGap:0.75rem;margin-left:calc(-1 * var(--columnGap));margin-right:calc(-1 * var(--columnGap))}.columns.is-variable .column{padding-left:var(--columnGap);padding-right:var(--columnGap)}.columns.is-variable.is-0{--columnGap:0rem}@media screen and (max-width:768px){.columns.is-variable.is-0-mobile{--columnGap:0rem}}@media screen and (min-width:769px),print{.columns.is-variable.is-0-tablet{--columnGap:0rem}}@media screen and (min-width:769px) and (max-width:1023px){.columns.is-variable.is-0-tablet-only{--columnGap:0rem}}@media screen and (max-width:1023px){.columns.is-variable.is-0-touch{--columnGap:0rem}}@media screen and (min-width:1024px){.columns.is-variable.is-0-desktop{--columnGap:0rem}}@media screen and (min-width:1024px) and (max-width:1215px){.columns.is-variable.is-0-desktop-only{--columnGap:0rem}}@media screen and (min-width:1216px){.columns.is-variable.is-0-widescreen{--columnGap:0rem}}@media screen and (min-width:1216px) and (max-width:1407px){.columns.is-variable.is-0-widescreen-only{--columnGap:0rem}}@media screen and (min-width:1408px){.columns.is-variable.is-0-fullhd{--columnGap:0rem}}.columns.is-variable.is-1{--columnGap:0.25rem}@media screen and (max-width:768px){.columns.is-variable.is-1-mobile{--columnGap:0.25rem}}@media screen and (min-width:769px),print{.columns.is-variable.is-1-tablet{--columnGap:0.25rem}}@media screen and (min-width:769px) and (max-width:1023px){.columns.is-variable.is-1-tablet-only{--columnGap:0.25rem}}@media screen and (max-width:1023px){.columns.is-variable.is-1-touch{--columnGap:0.25rem}}@media screen and (min-width:1024px){.columns.is-variable.is-1-desktop{--columnGap:0.25rem}}@media screen and (min-width:1024px) and (max-width:1215px){.columns.is-variable.is-1-desktop-only{--columnGap:0.25rem}}@media screen and (min-width:1216px){.columns.is-variable.is-1-widescreen{--columnGap:0.25rem}}@media screen and (min-width:1216px) and (max-width:1407px){.columns.is-variable.is-1-widescreen-only{--columnGap:0.25rem}}@media screen and (min-width:1408px){.columns.is-variable.is-1-fullhd{--columnGap:0.25rem}}.columns.is-variable.is-2{--columnGap:0.5rem}@media screen and (max-width:768px){.columns.is-variable.is-2-mobile{--columnGap:0.5rem}}@media screen and (min-width:769px),print{.columns.is-variable.is-2-tablet{--columnGap:0.5rem}}@media screen and (min-width:769px) and (max-width:1023px){.columns.is-variable.is-2-tablet-only{--columnGap:0.5rem}}@media screen and (max-width:1023px){.columns.is-variable.is-2-touch{--columnGap:0.5rem}}@media screen and (min-width:1024px){.columns.is-variable.is-2-desktop{--columnGap:0.5rem}}@media screen and (min-width:1024px) and (max-width:1215px){.columns.is-variable.is-2-desktop-only{--columnGap:0.5rem}}@media screen and (min-width:1216px){.columns.is-variable.is-2-widescreen{--columnGap:0.5rem}}@media screen and (min-width:1216px) and (max-width:1407px){.columns.is-variable.is-2-widescreen-only{--columnGap:0.5rem}}@media screen and (min-width:1408px){.columns.is-variable.is-2-fullhd{--columnGap:0.5rem}}.columns.is-variable.is-3{--columnGap:0.75rem}@media screen and (max-width:768px){.columns.is-variable.is-3-mobile{--columnGap:0.75rem}}@media screen and (min-width:769px),print{.columns.is-variable.is-3-tablet{--columnGap:0.75rem}}@media screen and (min-width:769px) and (max-width:1023px){.columns.is-variable.is-3-tablet-only{--columnGap:0.75rem}}@media screen and (max-width:1023px){.columns.is-variable.is-3-touch{--columnGap:0.75rem}}@media screen and (min-width:1024px){.columns.is-variable.is-3-desktop{--columnGap:0.75rem}}@media screen and (min-width:1024px) and (max-width:1215px){.columns.is-variable.is-3-desktop-only{--columnGap:0.75rem}}@media screen and (min-width:1216px){.columns.is-variable.is-3-widescreen{--columnGap:0.75rem}}@media screen and (min-width:1216px) and (max-width:1407px){.columns.is-variable.is-3-widescreen-only{--columnGap:0.75rem}}@media screen and (min-width:1408px){.columns.is-variable.is-3-fullhd{--columnGap:0.75rem}}.columns.is-variable.is-4{--columnGap:1rem}@media screen and (max-width:768px){.columns.is-variable.is-4-mobile{--columnGap:1rem}}@media screen and (min-width:769px),print{.columns.is-variable.is-4-tablet{--columnGap:1rem}}@media screen and (min-width:769px) and (max-width:1023px){.columns.is-variable.is-4-tablet-only{--columnGap:1rem}}@media screen and (max-width:1023px){.columns.is-variable.is-4-touch{--columnGap:1rem}}@media screen and (min-width:1024px){.columns.is-variable.is-4-desktop{--columnGap:1rem}}@media screen and (min-width:1024px) and (max-width:1215px){.columns.is-variable.is-4-desktop-only{--columnGap:1rem}}@media screen and (min-width:1216px){.columns.is-variable.is-4-widescreen{--columnGap:1rem}}@media screen and (min-width:1216px) and (max-width:1407px){.columns.is-variable.is-4-widescreen-only{--columnGap:1rem}}@media screen and (min-width:1408px){.columns.is-variable.is-4-fullhd{--columnGap:1rem}}.columns.is-variable.is-5{--columnGap:1.25rem}@media screen and (max-width:768px){.columns.is-variable.is-5-mobile{--columnGap:1.25rem}}@media screen and (min-width:769px),print{.columns.is-variable.is-5-tablet{--columnGap:1.25rem}}@media screen and (min-width:769px) and (max-width:1023px){.columns.is-variable.is-5-tablet-only{--columnGap:1.25rem}}@media screen and (max-width:1023px){.columns.is-variable.is-5-touch{--columnGap:1.25rem}}@media screen and (min-width:1024px){.columns.is-variable.is-5-desktop{--columnGap:1.25rem}}@media screen and (min-width:1024px) and (max-width:1215px){.columns.is-variable.is-5-desktop-only{--columnGap:1.25rem}}@media screen and (min-width:1216px){.columns.is-variable.is-5-widescreen{--columnGap:1.25rem}}@media screen and (min-width:1216px) and (max-width:1407px){.columns.is-variable.is-5-widescreen-only{--columnGap:1.25rem}}@media screen and (min-width:1408px){.columns.is-variable.is-5-fullhd{--columnGap:1.25rem}}.columns.is-variable.is-6{--columnGap:1.5rem}@media screen and (max-width:768px){.columns.is-variable.is-6-mobile{--columnGap:1.5rem}}@media screen and (min-width:769px),print{.columns.is-variable.is-6-tablet{--columnGap:1.5rem}}@media screen and (min-width:769px) and (max-width:1023px){.columns.is-variable.is-6-tablet-only{--columnGap:1.5rem}}@media screen and (max-width:1023px){.columns.is-variable.is-6-touch{--columnGap:1.5rem}}@media screen and (min-width:1024px){.columns.is-variable.is-6-desktop{--columnGap:1.5rem}}@media screen and (min-width:1024px) and (max-width:1215px){.columns.is-variable.is-6-desktop-only{--columnGap:1.5rem}}@media screen and (min-width:1216px){.columns.is-variable.is-6-widescreen{--columnGap:1.5rem}}@media screen and (min-width:1216px) and (max-width:1407px){.columns.is-variable.is-6-widescreen-only{--columnGap:1.5rem}}@media screen and (min-width:1408px){.columns.is-variable.is-6-fullhd{--columnGap:1.5rem}}.columns.is-variable.is-7{--columnGap:1.75rem}@media screen and (max-width:768px){.columns.is-variable.is-7-mobile{--columnGap:1.75rem}}@media screen and (min-width:769px),print{.columns.is-variable.is-7-tablet{--columnGap:1.75rem}}@media screen and (min-width:769px) and (max-width:1023px){.columns.is-variable.is-7-tablet-only{--columnGap:1.75rem}}@media screen and (max-width:1023px){.columns.is-variable.is-7-touch{--columnGap:1.75rem}}@media screen and (min-width:1024px){.columns.is-variable.is-7-desktop{--columnGap:1.75rem}}@media screen and (min-width:1024px) and (max-width:1215px){.columns.is-variable.is-7-desktop-only{--columnGap:1.75rem}}@media screen and (min-width:1216px){.columns.is-variable.is-7-widescreen{--columnGap:1.75rem}}@media screen and (min-width:1216px) and (max-width:1407px){.columns.is-variable.is-7-widescreen-only{--columnGap:1.75rem}}@media screen and (min-width:1408px){.columns.is-variable.is-7-fullhd{--columnGap:1.75rem}}.columns.is-variable.is-8{--columnGap:2rem}@media screen and (max-width:768px){.columns.is-variable.is-8-mobile{--columnGap:2rem}}@media screen and (min-width:769px),print{.columns.is-variable.is-8-tablet{--columnGap:2rem}}@media screen and (min-width:769px) and (max-width:1023px){.columns.is-variable.is-8-tablet-only{--columnGap:2rem}}@media screen and (max-width:1023px){.columns.is-variable.is-8-touch{--columnGap:2rem}}@media screen and (min-width:1024px){.columns.is-variable.is-8-desktop{--columnGap:2rem}}@media screen and (min-width:1024px) and (max-width:1215px){.columns.is-variable.is-8-desktop-only{--columnGap:2rem}}@media screen and (min-width:1216px){.columns.is-variable.is-8-widescreen{--columnGap:2rem}}@media screen and (min-width:1216px) and (max-width:1407px){.columns.is-variable.is-8-widescreen-only{--columnGap:2rem}}@media screen and (min-width:1408px){.columns.is-variable.is-8-fullhd{--columnGap:2rem}}.tile{align-items:stretch;display:block;flex-basis:0;flex-grow:1;flex-shrink:1;min-height:-webkit-min-content;min-height:-moz-min-content;min-height:min-content}.tile.is-ancestor{margin-left:-.75rem;margin-right:-.75rem;margin-top:-.75rem}.tile.is-ancestor:last-child{margin-bottom:-.75rem}.tile.is-ancestor:not(:last-child){margin-bottom:.75rem}.tile.is-child{margin:0!important}.tile.is-parent{padding:.75rem}.tile.is-vertical{flex-direction:column}.tile.is-vertical>.tile.is-child:not(:last-child){margin-bottom:1.5rem!important}@media screen and (min-width:769px),print{.tile:not(.is-child){display:flex}.tile.is-1{flex:none;width:8.33333%}.tile.is-2{flex:none;width:16.66667%}.tile.is-3{flex:none;width:25%}.tile.is-4{flex:none;width:33.33333%}.tile.is-5{flex:none;width:41.66667%}.tile.is-6{flex:none;width:50%}.tile.is-7{flex:none;width:58.33333%}.tile.is-8{flex:none;width:66.66667%}.tile.is-9{flex:none;width:75%}.tile.is-10{flex:none;width:83.33333%}.tile.is-11{flex:none;width:91.66667%}.tile.is-12{flex:none;width:100%}}.has-text-white{color:#fff!important}a.has-text-white:focus,a.has-text-white:hover{color:#e6e6e6!important}.has-background-white{background-color:#fff!important}.has-text-black{color:#0a0a0a!important}a.has-text-black:focus,a.has-text-black:hover{color:#000!important}.has-background-black{background-color:#0a0a0a!important}.has-text-light{color:#f5f5f5!important}a.has-text-light:focus,a.has-text-light:hover{color:#dbdbdb!important}.has-background-light{background-color:#f5f5f5!important}.has-text-dark{color:#363636!important}a.has-text-dark:focus,a.has-text-dark:hover{color:#1c1c1c!important}.has-background-dark{background-color:#363636!important}.has-text-primary{color:#00d1b2!important}a.has-text-primary:focus,a.has-text-primary:hover{color:#009e86!important}.has-background-primary{background-color:#00d1b2!important}.has-text-primary-light{color:#ebfffc!important}a.has-text-primary-light:focus,a.has-text-primary-light:hover{color:#b8fff4!important}.has-background-primary-light{background-color:#ebfffc!important}.has-text-primary-dark{color:#00947e!important}a.has-text-primary-dark:focus,a.has-text-primary-dark:hover{color:#00c7a9!important}.has-background-primary-dark{background-color:#00947e!important}.has-text-link{color:#3273dc!important}a.has-text-link:focus,a.has-text-link:hover{color:#205bbc!important}.has-background-link{background-color:#3273dc!important}.has-text-link-light{color:#eef3fc!important}a.has-text-link-light:focus,a.has-text-link-light:hover{color:#c2d5f5!important}.has-background-link-light{background-color:#eef3fc!important}.has-text-link-dark{color:#2160c4!important}a.has-text-link-dark:focus,a.has-text-link-dark:hover{color:#3b79de!important}.has-background-link-dark{background-color:#2160c4!important}.has-text-info{color:#3298dc!important}a.has-text-info:focus,a.has-text-info:hover{color:#207dbc!important}.has-background-info{background-color:#3298dc!important}.has-text-info-light{color:#eef6fc!important}a.has-text-info-light:focus,a.has-text-info-light:hover{color:#c2e0f5!important}.has-background-info-light{background-color:#eef6fc!important}.has-text-info-dark{color:#1d72aa!important}a.has-text-info-dark:focus,a.has-text-info-dark:hover{color:#248fd6!important}.has-background-info-dark{background-color:#1d72aa!important}.has-text-success{color:#48c774!important}a.has-text-success:focus,a.has-text-success:hover{color:#34a85c!important}.has-background-success{background-color:#48c774!important}.has-text-success-light{color:#effaf3!important}a.has-text-success-light:focus,a.has-text-success-light:hover{color:#c8eed6!important}.has-background-success-light{background-color:#effaf3!important}.has-text-success-dark{color:#257942!important}a.has-text-success-dark:focus,a.has-text-success-dark:hover{color:#31a058!important}.has-background-success-dark{background-color:#257942!important}.has-text-warning{color:#ffdd57!important}a.has-text-warning:focus,a.has-text-warning:hover{color:#ffd324!important}.has-background-warning{background-color:#ffdd57!important}.has-text-warning-light{color:#fffbeb!important}a.has-text-warning-light:focus,a.has-text-warning-light:hover{color:#fff1b8!important}.has-background-warning-light{background-color:#fffbeb!important}.has-text-warning-dark{color:#947600!important}a.has-text-warning-dark:focus,a.has-text-warning-dark:hover{color:#c79f00!important}.has-background-warning-dark{background-color:#947600!important}.has-text-danger{color:#f14668!important}a.has-text-danger:focus,a.has-text-danger:hover{color:#ee1742!important}.has-background-danger{background-color:#f14668!important}.has-text-danger-light{color:#feecf0!important}a.has-text-danger-light:focus,a.has-text-danger-light:hover{color:#fabdc9!important}.has-background-danger-light{background-color:#feecf0!important}.has-text-danger-dark{color:#cc0f35!important}a.has-text-danger-dark:focus,a.has-text-danger-dark:hover{color:#ee2049!important}.has-background-danger-dark{background-color:#cc0f35!important}.has-text-black-bis{color:#121212!important}.has-background-black-bis{background-color:#121212!important}.has-text-black-ter{color:#242424!important}.has-background-black-ter{background-color:#242424!important}.has-text-grey-darker{color:#363636!important}.has-background-grey-darker{background-color:#363636!important}.has-text-grey-dark{color:#4a4a4a!important}.has-background-grey-dark{background-color:#4a4a4a!important}.has-text-grey{color:#7a7a7a!important}.has-background-grey{background-color:#7a7a7a!important}.has-text-grey-light{color:#b5b5b5!important}.has-background-grey-light{background-color:#b5b5b5!important}.has-text-grey-lighter{color:#dbdbdb!important}.has-background-grey-lighter{background-color:#dbdbdb!important}.has-text-white-ter{color:#f5f5f5!important}.has-background-white-ter{background-color:#f5f5f5!important}.has-text-white-bis{color:#fafafa!important}.has-background-white-bis{background-color:#fafafa!important}.is-flex-direction-row{flex-direction:row!important}.is-flex-direction-row-reverse{flex-direction:row-reverse!important}.is-flex-direction-column{flex-direction:column!important}.is-flex-direction-column-reverse{flex-direction:column-reverse!important}.is-flex-wrap-nowrap{flex-wrap:nowrap!important}.is-flex-wrap-wrap{flex-wrap:wrap!important}.is-flex-wrap-wrap-reverse{flex-wrap:wrap-reverse!important}.is-justify-content-flex-start{justify-content:flex-start!important}.is-justify-content-flex-end{justify-content:flex-end!important}.is-justify-content-center{justify-content:center!important}.is-justify-content-space-between{justify-content:space-between!important}.is-justify-content-space-around{justify-content:space-around!important}.is-justify-content-space-evenly{justify-content:space-evenly!important}.is-justify-content-start{justify-content:start!important}.is-justify-content-end{justify-content:end!important}.is-justify-content-left{justify-content:left!important}.is-justify-content-right{justify-content:right!important}.is-align-content-flex-start{align-content:flex-start!important}.is-align-content-flex-end{align-content:flex-end!important}.is-align-content-center{align-content:center!important}.is-align-content-space-between{align-content:space-between!important}.is-align-content-space-around{align-content:space-around!important}.is-align-content-space-evenly{align-content:space-evenly!important}.is-align-content-stretch{align-content:stretch!important}.is-align-content-start{align-content:start!important}.is-align-content-end{align-content:end!important}.is-align-content-baseline{align-content:baseline!important}.is-align-items-stretch{align-items:stretch!important}.is-align-items-flex-start{align-items:flex-start!important}.is-align-items-flex-end{align-items:flex-end!important}.is-align-items-center{align-items:center!important}.is-align-items-baseline{align-items:baseline!important}.is-align-items-start{align-items:start!important}.is-align-items-end{align-items:end!important}.is-align-items-self-start{align-items:self-start!important}.is-align-items-self-end{align-items:self-end!important}.is-align-self-auto{align-self:auto!important}.is-align-self-flex-start{align-self:flex-start!important}.is-align-self-flex-end{align-self:flex-end!important}.is-align-self-center{align-self:center!important}.is-align-self-baseline{align-self:baseline!important}.is-align-self-stretch{align-self:stretch!important}.is-flex-grow-0{flex-grow:0!important}.is-flex-grow-1{flex-grow:1!important}.is-flex-grow-2{flex-grow:2!important}.is-flex-grow-3{flex-grow:3!important}.is-flex-grow-4{flex-grow:4!important}.is-flex-grow-5{flex-grow:5!important}.is-flex-shrink-0{flex-shrink:0!important}.is-flex-shrink-1{flex-shrink:1!important}.is-flex-shrink-2{flex-shrink:2!important}.is-flex-shrink-3{flex-shrink:3!important}.is-flex-shrink-4{flex-shrink:4!important}.is-flex-shrink-5{flex-shrink:5!important}.is-clearfix::after{clear:both;content:" ";display:table}.is-pulled-left{float:left!important}.is-pulled-right{float:right!important}.is-radiusless{border-radius:0!important}.is-shadowless{box-shadow:none!important}.is-clickable{cursor:pointer!important}.is-clipped{overflow:hidden!important}.is-relative{position:relative!important}.is-marginless{margin:0!important}.is-paddingless{padding:0!important}.m-0{margin:0!important}.mt-0{margin-top:0!important}.mr-0{margin-right:0!important}.mb-0{margin-bottom:0!important}.ml-0{margin-left:0!important}.mx-0{margin-left:0!important;margin-right:0!important}.my-0{margin-top:0!important;margin-bottom:0!important}.m-1{margin:.25rem!important}.mt-1{margin-top:.25rem!important}.mr-1{margin-right:.25rem!important}.mb-1{margin-bottom:.25rem!important}.ml-1{margin-left:.25rem!important}.mx-1{margin-left:.25rem!important;margin-right:.25rem!important}.my-1{margin-top:.25rem!important;margin-bottom:.25rem!important}.m-2{margin:.5rem!important}.mt-2{margin-top:.5rem!important}.mr-2{margin-right:.5rem!important}.mb-2{margin-bottom:.5rem!important}.ml-2{margin-left:.5rem!important}.mx-2{margin-left:.5rem!important;margin-right:.5rem!important}.my-2{margin-top:.5rem!important;margin-bottom:.5rem!important}.m-3{margin:.75rem!important}.mt-3{margin-top:.75rem!important}.mr-3{margin-right:.75rem!important}.mb-3{margin-bottom:.75rem!important}.ml-3{margin-left:.75rem!important}.mx-3{margin-left:.75rem!important;margin-right:.75rem!important}.my-3{margin-top:.75rem!important;margin-bottom:.75rem!important}.m-4{margin:1rem!important}.mt-4{margin-top:1rem!important}.mr-4{margin-right:1rem!important}.mb-4{margin-bottom:1rem!important}.ml-4{margin-left:1rem!important}.mx-4{margin-left:1rem!important;margin-right:1rem!important}.my-4{margin-top:1rem!important;margin-bottom:1rem!important}.m-5{margin:1.5rem!important}.mt-5{margin-top:1.5rem!important}.mr-5{margin-right:1.5rem!important}.mb-5{margin-bottom:1.5rem!important}.ml-5{margin-left:1.5rem!important}.mx-5{margin-left:1.5rem!important;margin-right:1.5rem!important}.my-5{margin-top:1.5rem!important;margin-bottom:1.5rem!important}.m-6{margin:3rem!important}.mt-6{margin-top:3rem!important}.mr-6{margin-right:3rem!important}.mb-6{margin-bottom:3rem!important}.ml-6{margin-left:3rem!important}.mx-6{margin-left:3rem!important;margin-right:3rem!important}.my-6{margin-top:3rem!important;margin-bottom:3rem!important}.p-0{padding:0!important}.pt-0{padding-top:0!important}.pr-0{padding-right:0!important}.pb-0{padding-bottom:0!important}.pl-0{padding-left:0!important}.px-0{padding-left:0!important;padding-right:0!important}.py-0{padding-top:0!important;padding-bottom:0!important}.p-1{padding:.25rem!important}.pt-1{padding-top:.25rem!important}.pr-1{padding-right:.25rem!important}.pb-1{padding-bottom:.25rem!important}.pl-1{padding-left:.25rem!important}.px-1{padding-left:.25rem!important;padding-right:.25rem!important}.py-1{padding-top:.25rem!important;padding-bottom:.25rem!important}.p-2{padding:.5rem!important}.pt-2{padding-top:.5rem!important}.pr-2{padding-right:.5rem!important}.pb-2{padding-bottom:.5rem!important}.pl-2{padding-left:.5rem!important}.px-2{padding-left:.5rem!important;padding-right:.5rem!important}.py-2{padding-top:.5rem!important;padding-bottom:.5rem!important}.p-3{padding:.75rem!important}.pt-3{padding-top:.75rem!important}.pr-3{padding-right:.75rem!important}.pb-3{padding-bottom:.75rem!important}.pl-3{padding-left:.75rem!important}.px-3{padding-left:.75rem!important;padding-right:.75rem!important}.py-3{padding-top:.75rem!important;padding-bottom:.75rem!important}.p-4{padding:1rem!important}.pt-4{padding-top:1rem!important}.pr-4{padding-right:1rem!important}.pb-4{padding-bottom:1rem!important}.pl-4{padding-left:1rem!important}.px-4{padding-left:1rem!important;padding-right:1rem!important}.py-4{padding-top:1rem!important;padding-bottom:1rem!important}.p-5{padding:1.5rem!important}.pt-5{padding-top:1.5rem!important}.pr-5{padding-right:1.5rem!important}.pb-5{padding-bottom:1.5rem!important}.pl-5{padding-left:1.5rem!important}.px-5{padding-left:1.5rem!important;padding-right:1.5rem!important}.py-5{padding-top:1.5rem!important;padding-bottom:1.5rem!important}.p-6{padding:3rem!important}.pt-6{padding-top:3rem!important}.pr-6{padding-right:3rem!important}.pb-6{padding-bottom:3rem!important}.pl-6{padding-left:3rem!important}.px-6{padding-left:3rem!important;padding-right:3rem!important}.py-6{padding-top:3rem!important;padding-bottom:3rem!important}.is-size-1{font-size:3rem!important}.is-size-2{font-size:2.5rem!important}.is-size-3{font-size:2rem!important}.is-size-4{font-size:1.5rem!important}.is-size-5{font-size:1.25rem!important}.is-size-6{font-size:1rem!important}.is-size-7{font-size:.75rem!important}@media screen and (max-width:768px){.is-size-1-mobile{font-size:3rem!important}.is-size-2-mobile{font-size:2.5rem!important}.is-size-3-mobile{font-size:2rem!important}.is-size-4-mobile{font-size:1.5rem!important}.is-size-5-mobile{font-size:1.25rem!important}.is-size-6-mobile{font-size:1rem!important}.is-size-7-mobile{font-size:.75rem!important}}@media screen and (min-width:769px),print{.is-size-1-tablet{font-size:3rem!important}.is-size-2-tablet{font-size:2.5rem!important}.is-size-3-tablet{font-size:2rem!important}.is-size-4-tablet{font-size:1.5rem!important}.is-size-5-tablet{font-size:1.25rem!important}.is-size-6-tablet{font-size:1rem!important}.is-size-7-tablet{font-size:.75rem!important}}@media screen and (max-width:1023px){.is-size-1-touch{font-size:3rem!important}.is-size-2-touch{font-size:2.5rem!important}.is-size-3-touch{font-size:2rem!important}.is-size-4-touch{font-size:1.5rem!important}.is-size-5-touch{font-size:1.25rem!important}.is-size-6-touch{font-size:1rem!important}.is-size-7-touch{font-size:.75rem!important}}@media screen and (min-width:1024px){.is-size-1-desktop{font-size:3rem!important}.is-size-2-desktop{font-size:2.5rem!important}.is-size-3-desktop{font-size:2rem!important}.is-size-4-desktop{font-size:1.5rem!important}.is-size-5-desktop{font-size:1.25rem!important}.is-size-6-desktop{font-size:1rem!important}.is-size-7-desktop{font-size:.75rem!important}}@media screen and (min-width:1216px){.is-size-1-widescreen{font-size:3rem!important}.is-size-2-widescreen{font-size:2.5rem!important}.is-size-3-widescreen{font-size:2rem!important}.is-size-4-widescreen{font-size:1.5rem!important}.is-size-5-widescreen{font-size:1.25rem!important}.is-size-6-widescreen{font-size:1rem!important}.is-size-7-widescreen{font-size:.75rem!important}}@media screen and (min-width:1408px){.is-size-1-fullhd{font-size:3rem!important}.is-size-2-fullhd{font-size:2.5rem!important}.is-size-3-fullhd{font-size:2rem!important}.is-size-4-fullhd{font-size:1.5rem!important}.is-size-5-fullhd{font-size:1.25rem!important}.is-size-6-fullhd{font-size:1rem!important}.is-size-7-fullhd{font-size:.75rem!important}}.has-text-centered{text-align:center!important}.has-text-justified{text-align:justify!important}.has-text-left{text-align:left!important}.has-text-right{text-align:right!important}@media screen and (max-width:768px){.has-text-centered-mobile{text-align:center!important}}@media screen and (min-width:769px),print{.has-text-centered-tablet{text-align:center!important}}@media screen and (min-width:769px) and (max-width:1023px){.has-text-centered-tablet-only{text-align:center!important}}@media screen and (max-width:1023px){.has-text-centered-touch{text-align:center!important}}@media screen and (min-width:1024px){.has-text-centered-desktop{text-align:center!important}}@media screen and (min-width:1024px) and (max-width:1215px){.has-text-centered-desktop-only{text-align:center!important}}@media screen and (min-width:1216px){.has-text-centered-widescreen{text-align:center!important}}@media screen and (min-width:1216px) and (max-width:1407px){.has-text-centered-widescreen-only{text-align:center!important}}@media screen and (min-width:1408px){.has-text-centered-fullhd{text-align:center!important}}@media screen and (max-width:768px){.has-text-justified-mobile{text-align:justify!important}}@media screen and (min-width:769px),print{.has-text-justified-tablet{text-align:justify!important}}@media screen and (min-width:769px) and (max-width:1023px){.has-text-justified-tablet-only{text-align:justify!important}}@media screen and (max-width:1023px){.has-text-justified-touch{text-align:justify!important}}@media screen and (min-width:1024px){.has-text-justified-desktop{text-align:justify!important}}@media screen and (min-width:1024px) and (max-width:1215px){.has-text-justified-desktop-only{text-align:justify!important}}@media screen and (min-width:1216px){.has-text-justified-widescreen{text-align:justify!important}}@media screen and (min-width:1216px) and (max-width:1407px){.has-text-justified-widescreen-only{text-align:justify!important}}@media screen and (min-width:1408px){.has-text-justified-fullhd{text-align:justify!important}}@media screen and (max-width:768px){.has-text-left-mobile{text-align:left!important}}@media screen and (min-width:769px),print{.has-text-left-tablet{text-align:left!important}}@media screen and (min-width:769px) and (max-width:1023px){.has-text-left-tablet-only{text-align:left!important}}@media screen and (max-width:1023px){.has-text-left-touch{text-align:left!important}}@media screen and (min-width:1024px){.has-text-left-desktop{text-align:left!important}}@media screen and (min-width:1024px) and (max-width:1215px){.has-text-left-desktop-only{text-align:left!important}}@media screen and (min-width:1216px){.has-text-left-widescreen{text-align:left!important}}@media screen and (min-width:1216px) and (max-width:1407px){.has-text-left-widescreen-only{text-align:left!important}}@media screen and (min-width:1408px){.has-text-left-fullhd{text-align:left!important}}@media screen and (max-width:768px){.has-text-right-mobile{text-align:right!important}}@media screen and (min-width:769px),print{.has-text-right-tablet{text-align:right!important}}@media screen and (min-width:769px) and (max-width:1023px){.has-text-right-tablet-only{text-align:right!important}}@media screen and (max-width:1023px){.has-text-right-touch{text-align:right!important}}@media screen and (min-width:1024px){.has-text-right-desktop{text-align:right!important}}@media screen and (min-width:1024px) and (max-width:1215px){.has-text-right-desktop-only{text-align:right!important}}@media screen and (min-width:1216px){.has-text-right-widescreen{text-align:right!important}}@media screen and (min-width:1216px) and (max-width:1407px){.has-text-right-widescreen-only{text-align:right!important}}@media screen and (min-width:1408px){.has-text-right-fullhd{text-align:right!important}}.is-capitalized{text-transform:capitalize!important}.is-lowercase{text-transform:lowercase!important}.is-uppercase{text-transform:uppercase!important}.is-italic{font-style:italic!important}.has-text-weight-light{font-weight:300!important}.has-text-weight-normal{font-weight:400!important}.has-text-weight-medium{font-weight:500!important}.has-text-weight-semibold{font-weight:600!important}.has-text-weight-bold{font-weight:700!important}.is-family-primary{font-family:BlinkMacSystemFont,-apple-system,"Segoe UI",Roboto,Oxygen,Ubuntu,Cantarell,"Fira Sans","Droid Sans","Helvetica Neue",Helvetica,Arial,sans-serif!important}.is-family-secondary{font-family:BlinkMacSystemFont,-apple-system,"Segoe UI",Roboto,Oxygen,Ubuntu,Cantarell,"Fira Sans","Droid Sans","Helvetica Neue",Helvetica,Arial,sans-serif!important}.is-family-sans-serif{font-family:BlinkMacSystemFont,-apple-system,"Segoe UI",Roboto,Oxygen,Ubuntu,Cantarell,"Fira Sans","Droid Sans","Helvetica Neue",Helvetica,Arial,sans-serif!important}.is-family-monospace{font-family:monospace!important}.is-family-code{font-family:monospace!important}.is-block{display:block!important}@media screen and (max-width:768px){.is-block-mobile{display:block!important}}@media screen and (min-width:769px),print{.is-block-tablet{display:block!important}}@media screen and (min-width:769px) and (max-width:1023px){.is-block-tablet-only{display:block!important}}@media screen and (max-width:1023px){.is-block-touch{display:block!important}}@media screen and (min-width:1024px){.is-block-desktop{display:block!important}}@media screen and (min-width:1024px) and (max-width:1215px){.is-block-desktop-only{display:block!important}}@media screen and (min-width:1216px){.is-block-widescreen{display:block!important}}@media screen and (min-width:1216px) and (max-width:1407px){.is-block-widescreen-only{display:block!important}}@media screen and (min-width:1408px){.is-block-fullhd{display:block!important}}.is-flex{display:flex!important}@media screen and (max-width:768px){.is-flex-mobile{display:flex!important}}@media screen and (min-width:769px),print{.is-flex-tablet{display:flex!important}}@media screen and (min-width:769px) and (max-width:1023px){.is-flex-tablet-only{display:flex!important}}@media screen and (max-width:1023px){.is-flex-touch{display:flex!important}}@media screen and (min-width:1024px){.is-flex-desktop{display:flex!important}}@media screen and (min-width:1024px) and (max-width:1215px){.is-flex-desktop-only{display:flex!important}}@media screen and (min-width:1216px){.is-flex-widescreen{display:flex!important}}@media screen and (min-width:1216px) and (max-width:1407px){.is-flex-widescreen-only{display:flex!important}}@media screen and (min-width:1408px){.is-flex-fullhd{display:flex!important}}.is-inline{display:inline!important}@media screen and (max-width:768px){.is-inline-mobile{display:inline!important}}@media screen and (min-width:769px),print{.is-inline-tablet{display:inline!important}}@media screen and (min-width:769px) and (max-width:1023px){.is-inline-tablet-only{display:inline!important}}@media screen and (max-width:1023px){.is-inline-touch{display:inline!important}}@media screen and (min-width:1024px){.is-inline-desktop{display:inline!important}}@media screen and (min-width:1024px) and (max-width:1215px){.is-inline-desktop-only{display:inline!important}}@media screen and (min-width:1216px){.is-inline-widescreen{display:inline!important}}@media screen and (min-width:1216px) and (max-width:1407px){.is-inline-widescreen-only{display:inline!important}}@media screen and (min-width:1408px){.is-inline-fullhd{display:inline!important}}.is-inline-block{display:inline-block!important}@media screen and (max-width:768px){.is-inline-block-mobile{display:inline-block!important}}@media screen and (min-width:769px),print{.is-inline-block-tablet{display:inline-block!important}}@media screen and (min-width:769px) and (max-width:1023px){.is-inline-block-tablet-only{display:inline-block!important}}@media screen and (max-width:1023px){.is-inline-block-touch{display:inline-block!important}}@media screen and (min-width:1024px){.is-inline-block-desktop{display:inline-block!important}}@media screen and (min-width:1024px) and (max-width:1215px){.is-inline-block-desktop-only{display:inline-block!important}}@media screen and (min-width:1216px){.is-inline-block-widescreen{display:inline-block!important}}@media screen and (min-width:1216px) and (max-width:1407px){.is-inline-block-widescreen-only{display:inline-block!important}}@media screen and (min-width:1408px){.is-inline-block-fullhd{display:inline-block!important}}.is-inline-flex{display:inline-flex!important}@media screen and (max-width:768px){.is-inline-flex-mobile{display:inline-flex!important}}@media screen and (min-width:769px),print{.is-inline-flex-tablet{display:inline-flex!important}}@media screen and (min-width:769px) and (max-width:1023px){.is-inline-flex-tablet-only{display:inline-flex!important}}@media screen and (max-width:1023px){.is-inline-flex-touch{display:inline-flex!important}}@media screen and (min-width:1024px){.is-inline-flex-desktop{display:inline-flex!important}}@media screen and (min-width:1024px) and (max-width:1215px){.is-inline-flex-desktop-only{display:inline-flex!important}}@media screen and (min-width:1216px){.is-inline-flex-widescreen{display:inline-flex!important}}@media screen and (min-width:1216px) and (max-width:1407px){.is-inline-flex-widescreen-only{display:inline-flex!important}}@media screen and (min-width:1408px){.is-inline-flex-fullhd{display:inline-flex!important}}.is-hidden{display:none!important}.is-sr-only{border:none!important;clip:rect(0,0,0,0)!important;height:.01em!important;overflow:hidden!important;padding:0!important;position:absolute!important;white-space:nowrap!important;width:.01em!important}@media screen and (max-width:768px){.is-hidden-mobile{display:none!important}}@media screen and (min-width:769px),print{.is-hidden-tablet{display:none!important}}@media screen and (min-width:769px) and (max-width:1023px){.is-hidden-tablet-only{display:none!important}}@media screen and (max-width:1023px){.is-hidden-touch{display:none!important}}@media screen and (min-width:1024px){.is-hidden-desktop{display:none!important}}@media screen and (min-width:1024px) and (max-width:1215px){.is-hidden-desktop-only{display:none!important}}@media screen and (min-width:1216px){.is-hidden-widescreen{display:none!important}}@media screen and (min-width:1216px) and (max-width:1407px){.is-hidden-widescreen-only{display:none!important}}@media screen and (min-width:1408px){.is-hidden-fullhd{display:none!important}}.is-invisible{visibility:hidden!important}@media screen and (max-width:768px){.is-invisible-mobile{visibility:hidden!important}}@media screen and (min-width:769px),print{.is-invisible-tablet{visibility:hidden!important}}@media screen and (min-width:769px) and (max-width:1023px){.is-invisible-tablet-only{visibility:hidden!important}}@media screen and (max-width:1023px){.is-invisible-touch{visibility:hidden!important}}@media screen and (min-width:1024px){.is-invisible-desktop{visibility:hidden!important}}@media screen and (min-width:1024px) and (max-width:1215px){.is-invisible-desktop-only{visibility:hidden!important}}@media screen and (min-width:1216px){.is-invisible-widescreen{visibility:hidden!important}}@media screen and (min-width:1216px) and (max-width:1407px){.is-invisible-widescreen-only{visibility:hidden!important}}@media screen and (min-width:1408px){.is-invisible-fullhd{visibility:hidden!important}}.hero{align-items:stretch;display:flex;flex-direction:column;justify-content:space-between}.hero .navbar{background:0 0}.hero .tabs ul{border-bottom:none}.hero.is-white{background-color:#fff;color:#0a0a0a}.hero.is-white a:not(.button):not(.dropdown-item):not(.tag):not(.pagination-link.is-current),.hero.is-white strong{color:inherit}.hero.is-white .title{color:#0a0a0a}.hero.is-white .subtitle{color:rgba(10,10,10,.9)}.hero.is-white .subtitle a:not(.button),.hero.is-white .subtitle strong{color:#0a0a0a}@media screen and (max-width:1023px){.hero.is-white .navbar-menu{background-color:#fff}}.hero.is-white .navbar-item,.hero.is-white .navbar-link{color:rgba(10,10,10,.7)}.hero.is-white .navbar-link.is-active,.hero.is-white .navbar-link:hover,.hero.is-white a.navbar-item.is-active,.hero.is-white a.navbar-item:hover{background-color:#f2f2f2;color:#0a0a0a}.hero.is-white .tabs a{color:#0a0a0a;opacity:.9}.hero.is-white .tabs a:hover{opacity:1}.hero.is-white .tabs li.is-active a{opacity:1}.hero.is-white .tabs.is-boxed a,.hero.is-white .tabs.is-toggle a{color:#0a0a0a}.hero.is-white .tabs.is-boxed a:hover,.hero.is-white .tabs.is-toggle a:hover{background-color:rgba(10,10,10,.1)}.hero.is-white .tabs.is-boxed li.is-active a,.hero.is-white .tabs.is-boxed li.is-active a:hover,.hero.is-white .tabs.is-toggle li.is-active a,.hero.is-white .tabs.is-toggle li.is-active a:hover{background-color:#0a0a0a;border-color:#0a0a0a;color:#fff}.hero.is-white.is-bold{background-image:linear-gradient(141deg,#e6e6e6 0,#fff 71%,#fff 100%)}@media screen and (max-width:768px){.hero.is-white.is-bold .navbar-menu{background-image:linear-gradient(141deg,#e6e6e6 0,#fff 71%,#fff 100%)}}.hero.is-black{background-color:#0a0a0a;color:#fff}.hero.is-black a:not(.button):not(.dropdown-item):not(.tag):not(.pagination-link.is-current),.hero.is-black strong{color:inherit}.hero.is-black .title{color:#fff}.hero.is-black .subtitle{color:rgba(255,255,255,.9)}.hero.is-black .subtitle a:not(.button),.hero.is-black .subtitle strong{color:#fff}@media screen and (max-width:1023px){.hero.is-black .navbar-menu{background-color:#0a0a0a}}.hero.is-black .navbar-item,.hero.is-black .navbar-link{color:rgba(255,255,255,.7)}.hero.is-black .navbar-link.is-active,.hero.is-black .navbar-link:hover,.hero.is-black a.navbar-item.is-active,.hero.is-black a.navbar-item:hover{background-color:#000;color:#fff}.hero.is-black .tabs a{color:#fff;opacity:.9}.hero.is-black .tabs a:hover{opacity:1}.hero.is-black .tabs li.is-active a{opacity:1}.hero.is-black .tabs.is-boxed a,.hero.is-black .tabs.is-toggle a{color:#fff}.hero.is-black .tabs.is-boxed a:hover,.hero.is-black .tabs.is-toggle a:hover{background-color:rgba(10,10,10,.1)}.hero.is-black .tabs.is-boxed li.is-active a,.hero.is-black .tabs.is-boxed li.is-active a:hover,.hero.is-black .tabs.is-toggle li.is-active a,.hero.is-black .tabs.is-toggle li.is-active a:hover{background-color:#fff;border-color:#fff;color:#0a0a0a}.hero.is-black.is-bold{background-image:linear-gradient(141deg,#000 0,#0a0a0a 71%,#181616 100%)}@media screen and (max-width:768px){.hero.is-black.is-bold .navbar-menu{background-image:linear-gradient(141deg,#000 0,#0a0a0a 71%,#181616 100%)}}.hero.is-light{background-color:#f5f5f5;color:rgba(0,0,0,.7)}.hero.is-light a:not(.button):not(.dropdown-item):not(.tag):not(.pagination-link.is-current),.hero.is-light strong{color:inherit}.hero.is-light .title{color:rgba(0,0,0,.7)}.hero.is-light .subtitle{color:rgba(0,0,0,.9)}.hero.is-light .subtitle a:not(.button),.hero.is-light .subtitle strong{color:rgba(0,0,0,.7)}@media screen and (max-width:1023px){.hero.is-light .navbar-menu{background-color:#f5f5f5}}.hero.is-light .navbar-item,.hero.is-light .navbar-link{color:rgba(0,0,0,.7)}.hero.is-light .navbar-link.is-active,.hero.is-light .navbar-link:hover,.hero.is-light a.navbar-item.is-active,.hero.is-light a.navbar-item:hover{background-color:#e8e8e8;color:rgba(0,0,0,.7)}.hero.is-light .tabs a{color:rgba(0,0,0,.7);opacity:.9}.hero.is-light .tabs a:hover{opacity:1}.hero.is-light .tabs li.is-active a{opacity:1}.hero.is-light .tabs.is-boxed a,.hero.is-light .tabs.is-toggle a{color:rgba(0,0,0,.7)}.hero.is-light .tabs.is-boxed a:hover,.hero.is-light .tabs.is-toggle a:hover{background-color:rgba(10,10,10,.1)}.hero.is-light .tabs.is-boxed li.is-active a,.hero.is-light .tabs.is-boxed li.is-active a:hover,.hero.is-light .tabs.is-toggle li.is-active a,.hero.is-light .tabs.is-toggle li.is-active a:hover{background-color:rgba(0,0,0,.7);border-color:rgba(0,0,0,.7);color:#f5f5f5}.hero.is-light.is-bold{background-image:linear-gradient(141deg,#dfd8d9 0,#f5f5f5 71%,#fff 100%)}@media screen and (max-width:768px){.hero.is-light.is-bold .navbar-menu{background-image:linear-gradient(141deg,#dfd8d9 0,#f5f5f5 71%,#fff 100%)}}.hero.is-dark{background-color:#363636;color:#fff}.hero.is-dark a:not(.button):not(.dropdown-item):not(.tag):not(.pagination-link.is-current),.hero.is-dark strong{color:inherit}.hero.is-dark .title{color:#fff}.hero.is-dark .subtitle{color:rgba(255,255,255,.9)}.hero.is-dark .subtitle a:not(.button),.hero.is-dark .subtitle strong{color:#fff}@media screen and (max-width:1023px){.hero.is-dark .navbar-menu{background-color:#363636}}.hero.is-dark .navbar-item,.hero.is-dark .navbar-link{color:rgba(255,255,255,.7)}.hero.is-dark .navbar-link.is-active,.hero.is-dark .navbar-link:hover,.hero.is-dark a.navbar-item.is-active,.hero.is-dark a.navbar-item:hover{background-color:#292929;color:#fff}.hero.is-dark .tabs a{color:#fff;opacity:.9}.hero.is-dark .tabs a:hover{opacity:1}.hero.is-dark .tabs li.is-active a{opacity:1}.hero.is-dark .tabs.is-boxed a,.hero.is-dark .tabs.is-toggle a{color:#fff}.hero.is-dark .tabs.is-boxed a:hover,.hero.is-dark .tabs.is-toggle a:hover{background-color:rgba(10,10,10,.1)}.hero.is-dark .tabs.is-boxed li.is-active a,.hero.is-dark .tabs.is-boxed li.is-active a:hover,.hero.is-dark .tabs.is-toggle li.is-active a,.hero.is-dark .tabs.is-toggle li.is-active a:hover{background-color:#fff;border-color:#fff;color:#363636}.hero.is-dark.is-bold{background-image:linear-gradient(141deg,#1f191a 0,#363636 71%,#46403f 100%)}@media screen and (max-width:768px){.hero.is-dark.is-bold .navbar-menu{background-image:linear-gradient(141deg,#1f191a 0,#363636 71%,#46403f 100%)}}.hero.is-primary{background-color:#00d1b2;color:#fff}.hero.is-primary a:not(.button):not(.dropdown-item):not(.tag):not(.pagination-link.is-current),.hero.is-primary strong{color:inherit}.hero.is-primary .title{color:#fff}.hero.is-primary .subtitle{color:rgba(255,255,255,.9)}.hero.is-primary .subtitle a:not(.button),.hero.is-primary .subtitle strong{color:#fff}@media screen and (max-width:1023px){.hero.is-primary .navbar-menu{background-color:#00d1b2}}.hero.is-primary .navbar-item,.hero.is-primary .navbar-link{color:rgba(255,255,255,.7)}.hero.is-primary .navbar-link.is-active,.hero.is-primary .navbar-link:hover,.hero.is-primary a.navbar-item.is-active,.hero.is-primary a.navbar-item:hover{background-color:#00b89c;color:#fff}.hero.is-primary .tabs a{color:#fff;opacity:.9}.hero.is-primary .tabs a:hover{opacity:1}.hero.is-primary .tabs li.is-active a{opacity:1}.hero.is-primary .tabs.is-boxed a,.hero.is-primary .tabs.is-toggle a{color:#fff}.hero.is-primary .tabs.is-boxed a:hover,.hero.is-primary .tabs.is-toggle a:hover{background-color:rgba(10,10,10,.1)}.hero.is-primary .tabs.is-boxed li.is-active a,.hero.is-primary .tabs.is-boxed li.is-active a:hover,.hero.is-primary .tabs.is-toggle li.is-active a,.hero.is-primary .tabs.is-toggle li.is-active a:hover{background-color:#fff;border-color:#fff;color:#00d1b2}.hero.is-primary.is-bold{background-image:linear-gradient(141deg,#009e6c 0,#00d1b2 71%,#00e7eb 100%)}@media screen and (max-width:768px){.hero.is-primary.is-bold .navbar-menu{background-image:linear-gradient(141deg,#009e6c 0,#00d1b2 71%,#00e7eb 100%)}}.hero.is-link{background-color:#3273dc;color:#fff}.hero.is-link a:not(.button):not(.dropdown-item):not(.tag):not(.pagination-link.is-current),.hero.is-link strong{color:inherit}.hero.is-link .title{color:#fff}.hero.is-link .subtitle{color:rgba(255,255,255,.9)}.hero.is-link .subtitle a:not(.button),.hero.is-link .subtitle strong{color:#fff}@media screen and (max-width:1023px){.hero.is-link .navbar-menu{background-color:#3273dc}}.hero.is-link .navbar-item,.hero.is-link .navbar-link{color:rgba(255,255,255,.7)}.hero.is-link .navbar-link.is-active,.hero.is-link .navbar-link:hover,.hero.is-link a.navbar-item.is-active,.hero.is-link a.navbar-item:hover{background-color:#2366d1;color:#fff}.hero.is-link .tabs a{color:#fff;opacity:.9}.hero.is-link .tabs a:hover{opacity:1}.hero.is-link .tabs li.is-active a{opacity:1}.hero.is-link .tabs.is-boxed a,.hero.is-link .tabs.is-toggle a{color:#fff}.hero.is-link .tabs.is-boxed a:hover,.hero.is-link .tabs.is-toggle a:hover{background-color:rgba(10,10,10,.1)}.hero.is-link .tabs.is-boxed li.is-active a,.hero.is-link .tabs.is-boxed li.is-active a:hover,.hero.is-link .tabs.is-toggle li.is-active a,.hero.is-link .tabs.is-toggle li.is-active a:hover{background-color:#fff;border-color:#fff;color:#3273dc}.hero.is-link.is-bold{background-image:linear-gradient(141deg,#1577c6 0,#3273dc 71%,#4366e5 100%)}@media screen and (max-width:768px){.hero.is-link.is-bold .navbar-menu{background-image:linear-gradient(141deg,#1577c6 0,#3273dc 71%,#4366e5 100%)}}.hero.is-info{background-color:#3298dc;color:#fff}.hero.is-info a:not(.button):not(.dropdown-item):not(.tag):not(.pagination-link.is-current),.hero.is-info strong{color:inherit}.hero.is-info .title{color:#fff}.hero.is-info .subtitle{color:rgba(255,255,255,.9)}.hero.is-info .subtitle a:not(.button),.hero.is-info .subtitle strong{color:#fff}@media screen and (max-width:1023px){.hero.is-info .navbar-menu{background-color:#3298dc}}.hero.is-info .navbar-item,.hero.is-info .navbar-link{color:rgba(255,255,255,.7)}.hero.is-info .navbar-link.is-active,.hero.is-info .navbar-link:hover,.hero.is-info a.navbar-item.is-active,.hero.is-info a.navbar-item:hover{background-color:#238cd1;color:#fff}.hero.is-info .tabs a{color:#fff;opacity:.9}.hero.is-info .tabs a:hover{opacity:1}.hero.is-info .tabs li.is-active a{opacity:1}.hero.is-info .tabs.is-boxed a,.hero.is-info .tabs.is-toggle a{color:#fff}.hero.is-info .tabs.is-boxed a:hover,.hero.is-info .tabs.is-toggle a:hover{background-color:rgba(10,10,10,.1)}.hero.is-info .tabs.is-boxed li.is-active a,.hero.is-info .tabs.is-boxed li.is-active a:hover,.hero.is-info .tabs.is-toggle li.is-active a,.hero.is-info .tabs.is-toggle li.is-active a:hover{background-color:#fff;border-color:#fff;color:#3298dc}.hero.is-info.is-bold{background-image:linear-gradient(141deg,#159dc6 0,#3298dc 71%,#4389e5 100%)}@media screen and (max-width:768px){.hero.is-info.is-bold .navbar-menu{background-image:linear-gradient(141deg,#159dc6 0,#3298dc 71%,#4389e5 100%)}}.hero.is-success{background-color:#48c774;color:#fff}.hero.is-success a:not(.button):not(.dropdown-item):not(.tag):not(.pagination-link.is-current),.hero.is-success strong{color:inherit}.hero.is-success .title{color:#fff}.hero.is-success .subtitle{color:rgba(255,255,255,.9)}.hero.is-success .subtitle a:not(.button),.hero.is-success .subtitle strong{color:#fff}@media screen and (max-width:1023px){.hero.is-success .navbar-menu{background-color:#48c774}}.hero.is-success .navbar-item,.hero.is-success .navbar-link{color:rgba(255,255,255,.7)}.hero.is-success .navbar-link.is-active,.hero.is-success .navbar-link:hover,.hero.is-success a.navbar-item.is-active,.hero.is-success a.navbar-item:hover{background-color:#3abb67;color:#fff}.hero.is-success .tabs a{color:#fff;opacity:.9}.hero.is-success .tabs a:hover{opacity:1}.hero.is-success .tabs li.is-active a{opacity:1}.hero.is-success .tabs.is-boxed a,.hero.is-success .tabs.is-toggle a{color:#fff}.hero.is-success .tabs.is-boxed a:hover,.hero.is-success .tabs.is-toggle a:hover{background-color:rgba(10,10,10,.1)}.hero.is-success .tabs.is-boxed li.is-active a,.hero.is-success .tabs.is-boxed li.is-active a:hover,.hero.is-success .tabs.is-toggle li.is-active a,.hero.is-success .tabs.is-toggle li.is-active a:hover{background-color:#fff;border-color:#fff;color:#48c774}.hero.is-success.is-bold{background-image:linear-gradient(141deg,#29b342 0,#48c774 71%,#56d296 100%)}@media screen and (max-width:768px){.hero.is-success.is-bold .navbar-menu{background-image:linear-gradient(141deg,#29b342 0,#48c774 71%,#56d296 100%)}}.hero.is-warning{background-color:#ffdd57;color:rgba(0,0,0,.7)}.hero.is-warning a:not(.button):not(.dropdown-item):not(.tag):not(.pagination-link.is-current),.hero.is-warning strong{color:inherit}.hero.is-warning .title{color:rgba(0,0,0,.7)}.hero.is-warning .subtitle{color:rgba(0,0,0,.9)}.hero.is-warning .subtitle a:not(.button),.hero.is-warning .subtitle strong{color:rgba(0,0,0,.7)}@media screen and (max-width:1023px){.hero.is-warning .navbar-menu{background-color:#ffdd57}}.hero.is-warning .navbar-item,.hero.is-warning .navbar-link{color:rgba(0,0,0,.7)}.hero.is-warning .navbar-link.is-active,.hero.is-warning .navbar-link:hover,.hero.is-warning a.navbar-item.is-active,.hero.is-warning a.navbar-item:hover{background-color:#ffd83d;color:rgba(0,0,0,.7)}.hero.is-warning .tabs a{color:rgba(0,0,0,.7);opacity:.9}.hero.is-warning .tabs a:hover{opacity:1}.hero.is-warning .tabs li.is-active a{opacity:1}.hero.is-warning .tabs.is-boxed a,.hero.is-warning .tabs.is-toggle a{color:rgba(0,0,0,.7)}.hero.is-warning .tabs.is-boxed a:hover,.hero.is-warning .tabs.is-toggle a:hover{background-color:rgba(10,10,10,.1)}.hero.is-warning .tabs.is-boxed li.is-active a,.hero.is-warning .tabs.is-boxed li.is-active a:hover,.hero.is-warning .tabs.is-toggle li.is-active a,.hero.is-warning .tabs.is-toggle li.is-active a:hover{background-color:rgba(0,0,0,.7);border-color:rgba(0,0,0,.7);color:#ffdd57}.hero.is-warning.is-bold{background-image:linear-gradient(141deg,#ffaf24 0,#ffdd57 71%,#fffa70 100%)}@media screen and (max-width:768px){.hero.is-warning.is-bold .navbar-menu{background-image:linear-gradient(141deg,#ffaf24 0,#ffdd57 71%,#fffa70 100%)}}.hero.is-danger{background-color:#f14668;color:#fff}.hero.is-danger a:not(.button):not(.dropdown-item):not(.tag):not(.pagination-link.is-current),.hero.is-danger strong{color:inherit}.hero.is-danger .title{color:#fff}.hero.is-danger .subtitle{color:rgba(255,255,255,.9)}.hero.is-danger .subtitle a:not(.button),.hero.is-danger .subtitle strong{color:#fff}@media screen and (max-width:1023px){.hero.is-danger .navbar-menu{background-color:#f14668}}.hero.is-danger .navbar-item,.hero.is-danger .navbar-link{color:rgba(255,255,255,.7)}.hero.is-danger .navbar-link.is-active,.hero.is-danger .navbar-link:hover,.hero.is-danger a.navbar-item.is-active,.hero.is-danger a.navbar-item:hover{background-color:#ef2e55;color:#fff}.hero.is-danger .tabs a{color:#fff;opacity:.9}.hero.is-danger .tabs a:hover{opacity:1}.hero.is-danger .tabs li.is-active a{opacity:1}.hero.is-danger .tabs.is-boxed a,.hero.is-danger .tabs.is-toggle a{color:#fff}.hero.is-danger .tabs.is-boxed a:hover,.hero.is-danger .tabs.is-toggle a:hover{background-color:rgba(10,10,10,.1)}.hero.is-danger .tabs.is-boxed li.is-active a,.hero.is-danger .tabs.is-boxed li.is-active a:hover,.hero.is-danger .tabs.is-toggle li.is-active a,.hero.is-danger .tabs.is-toggle li.is-active a:hover{background-color:#fff;border-color:#fff;color:#f14668}.hero.is-danger.is-bold{background-image:linear-gradient(141deg,#fa0a62 0,#f14668 71%,#f7595f 100%)}@media screen and (max-width:768px){.hero.is-danger.is-bold .navbar-menu{background-image:linear-gradient(141deg,#fa0a62 0,#f14668 71%,#f7595f 100%)}}.hero.is-small .hero-body{padding:1.5rem}@media screen and (min-width:769px),print{.hero.is-medium .hero-body{padding:9rem 1.5rem}}@media screen and (min-width:769px),print{.hero.is-large .hero-body{padding:18rem 1.5rem}}.hero.is-fullheight .hero-body,.hero.is-fullheight-with-navbar .hero-body,.hero.is-halfheight .hero-body{align-items:center;display:flex}.hero.is-fullheight .hero-body>.container,.hero.is-fullheight-with-navbar .hero-body>.container,.hero.is-halfheight .hero-body>.container{flex-grow:1;flex-shrink:1}.hero.is-halfheight{min-height:50vh}.hero.is-fullheight{min-height:100vh}.hero-video{overflow:hidden}.hero-video video{left:50%;min-height:100%;min-width:100%;position:absolute;top:50%;transform:translate3d(-50%,-50%,0)}.hero-video.is-transparent{opacity:.3}@media screen and (max-width:768px){.hero-video{display:none}}.hero-buttons{margin-top:1.5rem}@media screen and (max-width:768px){.hero-buttons .button{display:flex}.hero-buttons .button:not(:last-child){margin-bottom:.75rem}}@media screen and (min-width:769px),print{.hero-buttons{display:flex;justify-content:center}.hero-buttons .button:not(:last-child){margin-right:1.5rem}}.hero-foot,.hero-head{flex-grow:0;flex-shrink:0}.hero-body{flex-grow:1;flex-shrink:0;padding:3rem 1.5rem}.section{padding:3rem 1.5rem}@media screen and (min-width:1024px){.section.is-medium{padding:9rem 1.5rem}.section.is-large{padding:18rem 1.5rem}}.footer{background-color:#fafafa;padding:3rem 1.5rem 6rem}
diff --git a/docs/project_page/static/css/fontawesome.all.min.css b/docs/project_page/static/css/fontawesome.all.min.css
new file mode 100644
index 0000000..c50c878
--- /dev/null
+++ b/docs/project_page/static/css/fontawesome.all.min.css
@@ -0,0 +1,5 @@
+/*!
+ * Font Awesome Free 5.15.1 by @fontawesome - https://fontawesome.com
+ * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)
+ */
+.fa,.fab,.fad,.fal,.far,.fas{-moz-osx-font-smoothing:grayscale;-webkit-font-smoothing:antialiased;display:inline-block;font-style:normal;font-variant:normal;text-rendering:auto;line-height:1}.fa-lg{font-size:1.33333em;line-height:.75em;vertical-align:-.0667em}.fa-xs{font-size:.75em}.fa-sm{font-size:.875em}.fa-1x{font-size:1em}.fa-2x{font-size:2em}.fa-3x{font-size:3em}.fa-4x{font-size:4em}.fa-5x{font-size:5em}.fa-6x{font-size:6em}.fa-7x{font-size:7em}.fa-8x{font-size:8em}.fa-9x{font-size:9em}.fa-10x{font-size:10em}.fa-fw{text-align:center;width:1.25em}.fa-ul{list-style-type:none;margin-left:2.5em;padding-left:0}.fa-ul>li{position:relative}.fa-li{left:-2em;position:absolute;text-align:center;width:2em;line-height:inherit}.fa-border{border:.08em solid #eee;border-radius:.1em;padding:.2em .25em .15em}.fa-pull-left{float:left}.fa-pull-right{float:right}.fa.fa-pull-left,.fab.fa-pull-left,.fal.fa-pull-left,.far.fa-pull-left,.fas.fa-pull-left{margin-right:.3em}.fa.fa-pull-right,.fab.fa-pull-right,.fal.fa-pull-right,.far.fa-pull-right,.fas.fa-pull-right{margin-left:.3em}.fa-spin{-webkit-animation:fa-spin 2s linear infinite;animation:fa-spin 2s linear infinite}.fa-pulse{-webkit-animation:fa-spin 1s steps(8) infinite;animation:fa-spin 1s steps(8) infinite}@-webkit-keyframes fa-spin{0%{-webkit-transform:rotate(0deg);transform:rotate(0deg)}to{-webkit-transform:rotate(1turn);transform:rotate(1turn)}}@keyframes fa-spin{0%{-webkit-transform:rotate(0deg);transform:rotate(0deg)}to{-webkit-transform:rotate(1turn);transform:rotate(1turn)}}.fa-rotate-90{-ms-filter:"progid:DXImageTransform.Microsoft.BasicImage(rotation=1)";-webkit-transform:rotate(90deg);transform:rotate(90deg)}.fa-rotate-180{-ms-filter:"progid:DXImageTransform.Microsoft.BasicImage(rotation=2)";-webkit-transform:rotate(180deg);transform:rotate(180deg)}.fa-rotate-270{-ms-filter:"progid:DXImageTransform.Microsoft.BasicImage(rotation=3)";-webkit-transform:rotate(270deg);transform:rotate(270deg)}.fa-flip-horizontal{-ms-filter:"progid:DXImageTransform.Microsoft.BasicImage(rotation=0, mirror=1)";-webkit-transform:scaleX(-1);transform:scaleX(-1)}.fa-flip-vertical{-webkit-transform:scaleY(-1);transform:scaleY(-1)}.fa-flip-both,.fa-flip-horizontal.fa-flip-vertical,.fa-flip-vertical{-ms-filter:"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)"}.fa-flip-both,.fa-flip-horizontal.fa-flip-vertical{-webkit-transform:scale(-1);transform:scale(-1)}:root .fa-flip-both,:root .fa-flip-horizontal,:root .fa-flip-vertical,:root .fa-rotate-90,:root .fa-rotate-180,:root .fa-rotate-270{-webkit-filter:none;filter:none}.fa-stack{display:inline-block;height:2em;line-height:2em;position:relative;vertical-align:middle;width:2.5em}.fa-stack-1x,.fa-stack-2x{left:0;position:absolute;text-align:center;width:100%}.fa-stack-1x{line-height:inherit}.fa-stack-2x{font-size:2em}.fa-inverse{color:#fff}.fa-500px:before{content:"\f26e"}.fa-accessible-icon:before{content:"\f368"}.fa-accusoft:before{content:"\f369"}.fa-acquisitions-incorporated:before{content:"\f6af"}.fa-ad:before{content:"\f641"}.fa-address-book:before{content:"\f2b9"}.fa-address-card:before{content:"\f2bb"}.fa-adjust:before{content:"\f042"}.fa-adn:before{content:"\f170"}.fa-adversal:before{content:"\f36a"}.fa-affiliatetheme:before{content:"\f36b"}.fa-air-freshener:before{content:"\f5d0"}.fa-airbnb:before{content:"\f834"}.fa-algolia:before{content:"\f36c"}.fa-align-center:before{content:"\f037"}.fa-align-justify:before{content:"\f039"}.fa-align-left:before{content:"\f036"}.fa-align-right:before{content:"\f038"}.fa-alipay:before{content:"\f642"}.fa-allergies:before{content:"\f461"}.fa-amazon:before{content:"\f270"}.fa-amazon-pay:before{content:"\f42c"}.fa-ambulance:before{content:"\f0f9"}.fa-american-sign-language-interpreting:before{content:"\f2a3"}.fa-amilia:before{content:"\f36d"}.fa-anchor:before{content:"\f13d"}.fa-android:before{content:"\f17b"}.fa-angellist:before{content:"\f209"}.fa-angle-double-down:before{content:"\f103"}.fa-angle-double-left:before{content:"\f100"}.fa-angle-double-right:before{content:"\f101"}.fa-angle-double-up:before{content:"\f102"}.fa-angle-down:before{content:"\f107"}.fa-angle-left:before{content:"\f104"}.fa-angle-right:before{content:"\f105"}.fa-angle-up:before{content:"\f106"}.fa-angry:before{content:"\f556"}.fa-angrycreative:before{content:"\f36e"}.fa-angular:before{content:"\f420"}.fa-ankh:before{content:"\f644"}.fa-app-store:before{content:"\f36f"}.fa-app-store-ios:before{content:"\f370"}.fa-apper:before{content:"\f371"}.fa-apple:before{content:"\f179"}.fa-apple-alt:before{content:"\f5d1"}.fa-apple-pay:before{content:"\f415"}.fa-archive:before{content:"\f187"}.fa-archway:before{content:"\f557"}.fa-arrow-alt-circle-down:before{content:"\f358"}.fa-arrow-alt-circle-left:before{content:"\f359"}.fa-arrow-alt-circle-right:before{content:"\f35a"}.fa-arrow-alt-circle-up:before{content:"\f35b"}.fa-arrow-circle-down:before{content:"\f0ab"}.fa-arrow-circle-left:before{content:"\f0a8"}.fa-arrow-circle-right:before{content:"\f0a9"}.fa-arrow-circle-up:before{content:"\f0aa"}.fa-arrow-down:before{content:"\f063"}.fa-arrow-left:before{content:"\f060"}.fa-arrow-right:before{content:"\f061"}.fa-arrow-up:before{content:"\f062"}.fa-arrows-alt:before{content:"\f0b2"}.fa-arrows-alt-h:before{content:"\f337"}.fa-arrows-alt-v:before{content:"\f338"}.fa-artstation:before{content:"\f77a"}.fa-assistive-listening-systems:before{content:"\f2a2"}.fa-asterisk:before{content:"\f069"}.fa-asymmetrik:before{content:"\f372"}.fa-at:before{content:"\f1fa"}.fa-atlas:before{content:"\f558"}.fa-atlassian:before{content:"\f77b"}.fa-atom:before{content:"\f5d2"}.fa-audible:before{content:"\f373"}.fa-audio-description:before{content:"\f29e"}.fa-autoprefixer:before{content:"\f41c"}.fa-avianex:before{content:"\f374"}.fa-aviato:before{content:"\f421"}.fa-award:before{content:"\f559"}.fa-aws:before{content:"\f375"}.fa-baby:before{content:"\f77c"}.fa-baby-carriage:before{content:"\f77d"}.fa-backspace:before{content:"\f55a"}.fa-backward:before{content:"\f04a"}.fa-bacon:before{content:"\f7e5"}.fa-bacteria:before{content:"\e059"}.fa-bacterium:before{content:"\e05a"}.fa-bahai:before{content:"\f666"}.fa-balance-scale:before{content:"\f24e"}.fa-balance-scale-left:before{content:"\f515"}.fa-balance-scale-right:before{content:"\f516"}.fa-ban:before{content:"\f05e"}.fa-band-aid:before{content:"\f462"}.fa-bandcamp:before{content:"\f2d5"}.fa-barcode:before{content:"\f02a"}.fa-bars:before{content:"\f0c9"}.fa-baseball-ball:before{content:"\f433"}.fa-basketball-ball:before{content:"\f434"}.fa-bath:before{content:"\f2cd"}.fa-battery-empty:before{content:"\f244"}.fa-battery-full:before{content:"\f240"}.fa-battery-half:before{content:"\f242"}.fa-battery-quarter:before{content:"\f243"}.fa-battery-three-quarters:before{content:"\f241"}.fa-battle-net:before{content:"\f835"}.fa-bed:before{content:"\f236"}.fa-beer:before{content:"\f0fc"}.fa-behance:before{content:"\f1b4"}.fa-behance-square:before{content:"\f1b5"}.fa-bell:before{content:"\f0f3"}.fa-bell-slash:before{content:"\f1f6"}.fa-bezier-curve:before{content:"\f55b"}.fa-bible:before{content:"\f647"}.fa-bicycle:before{content:"\f206"}.fa-biking:before{content:"\f84a"}.fa-bimobject:before{content:"\f378"}.fa-binoculars:before{content:"\f1e5"}.fa-biohazard:before{content:"\f780"}.fa-birthday-cake:before{content:"\f1fd"}.fa-bitbucket:before{content:"\f171"}.fa-bitcoin:before{content:"\f379"}.fa-bity:before{content:"\f37a"}.fa-black-tie:before{content:"\f27e"}.fa-blackberry:before{content:"\f37b"}.fa-blender:before{content:"\f517"}.fa-blender-phone:before{content:"\f6b6"}.fa-blind:before{content:"\f29d"}.fa-blog:before{content:"\f781"}.fa-blogger:before{content:"\f37c"}.fa-blogger-b:before{content:"\f37d"}.fa-bluetooth:before{content:"\f293"}.fa-bluetooth-b:before{content:"\f294"}.fa-bold:before{content:"\f032"}.fa-bolt:before{content:"\f0e7"}.fa-bomb:before{content:"\f1e2"}.fa-bone:before{content:"\f5d7"}.fa-bong:before{content:"\f55c"}.fa-book:before{content:"\f02d"}.fa-book-dead:before{content:"\f6b7"}.fa-book-medical:before{content:"\f7e6"}.fa-book-open:before{content:"\f518"}.fa-book-reader:before{content:"\f5da"}.fa-bookmark:before{content:"\f02e"}.fa-bootstrap:before{content:"\f836"}.fa-border-all:before{content:"\f84c"}.fa-border-none:before{content:"\f850"}.fa-border-style:before{content:"\f853"}.fa-bowling-ball:before{content:"\f436"}.fa-box:before{content:"\f466"}.fa-box-open:before{content:"\f49e"}.fa-box-tissue:before{content:"\e05b"}.fa-boxes:before{content:"\f468"}.fa-braille:before{content:"\f2a1"}.fa-brain:before{content:"\f5dc"}.fa-bread-slice:before{content:"\f7ec"}.fa-briefcase:before{content:"\f0b1"}.fa-briefcase-medical:before{content:"\f469"}.fa-broadcast-tower:before{content:"\f519"}.fa-broom:before{content:"\f51a"}.fa-brush:before{content:"\f55d"}.fa-btc:before{content:"\f15a"}.fa-buffer:before{content:"\f837"}.fa-bug:before{content:"\f188"}.fa-building:before{content:"\f1ad"}.fa-bullhorn:before{content:"\f0a1"}.fa-bullseye:before{content:"\f140"}.fa-burn:before{content:"\f46a"}.fa-buromobelexperte:before{content:"\f37f"}.fa-bus:before{content:"\f207"}.fa-bus-alt:before{content:"\f55e"}.fa-business-time:before{content:"\f64a"}.fa-buy-n-large:before{content:"\f8a6"}.fa-buysellads:before{content:"\f20d"}.fa-calculator:before{content:"\f1ec"}.fa-calendar:before{content:"\f133"}.fa-calendar-alt:before{content:"\f073"}.fa-calendar-check:before{content:"\f274"}.fa-calendar-day:before{content:"\f783"}.fa-calendar-minus:before{content:"\f272"}.fa-calendar-plus:before{content:"\f271"}.fa-calendar-times:before{content:"\f273"}.fa-calendar-week:before{content:"\f784"}.fa-camera:before{content:"\f030"}.fa-camera-retro:before{content:"\f083"}.fa-campground:before{content:"\f6bb"}.fa-canadian-maple-leaf:before{content:"\f785"}.fa-candy-cane:before{content:"\f786"}.fa-cannabis:before{content:"\f55f"}.fa-capsules:before{content:"\f46b"}.fa-car:before{content:"\f1b9"}.fa-car-alt:before{content:"\f5de"}.fa-car-battery:before{content:"\f5df"}.fa-car-crash:before{content:"\f5e1"}.fa-car-side:before{content:"\f5e4"}.fa-caravan:before{content:"\f8ff"}.fa-caret-down:before{content:"\f0d7"}.fa-caret-left:before{content:"\f0d9"}.fa-caret-right:before{content:"\f0da"}.fa-caret-square-down:before{content:"\f150"}.fa-caret-square-left:before{content:"\f191"}.fa-caret-square-right:before{content:"\f152"}.fa-caret-square-up:before{content:"\f151"}.fa-caret-up:before{content:"\f0d8"}.fa-carrot:before{content:"\f787"}.fa-cart-arrow-down:before{content:"\f218"}.fa-cart-plus:before{content:"\f217"}.fa-cash-register:before{content:"\f788"}.fa-cat:before{content:"\f6be"}.fa-cc-amazon-pay:before{content:"\f42d"}.fa-cc-amex:before{content:"\f1f3"}.fa-cc-apple-pay:before{content:"\f416"}.fa-cc-diners-club:before{content:"\f24c"}.fa-cc-discover:before{content:"\f1f2"}.fa-cc-jcb:before{content:"\f24b"}.fa-cc-mastercard:before{content:"\f1f1"}.fa-cc-paypal:before{content:"\f1f4"}.fa-cc-stripe:before{content:"\f1f5"}.fa-cc-visa:before{content:"\f1f0"}.fa-centercode:before{content:"\f380"}.fa-centos:before{content:"\f789"}.fa-certificate:before{content:"\f0a3"}.fa-chair:before{content:"\f6c0"}.fa-chalkboard:before{content:"\f51b"}.fa-chalkboard-teacher:before{content:"\f51c"}.fa-charging-station:before{content:"\f5e7"}.fa-chart-area:before{content:"\f1fe"}.fa-chart-bar:before{content:"\f080"}.fa-chart-line:before{content:"\f201"}.fa-chart-pie:before{content:"\f200"}.fa-check:before{content:"\f00c"}.fa-check-circle:before{content:"\f058"}.fa-check-double:before{content:"\f560"}.fa-check-square:before{content:"\f14a"}.fa-cheese:before{content:"\f7ef"}.fa-chess:before{content:"\f439"}.fa-chess-bishop:before{content:"\f43a"}.fa-chess-board:before{content:"\f43c"}.fa-chess-king:before{content:"\f43f"}.fa-chess-knight:before{content:"\f441"}.fa-chess-pawn:before{content:"\f443"}.fa-chess-queen:before{content:"\f445"}.fa-chess-rook:before{content:"\f447"}.fa-chevron-circle-down:before{content:"\f13a"}.fa-chevron-circle-left:before{content:"\f137"}.fa-chevron-circle-right:before{content:"\f138"}.fa-chevron-circle-up:before{content:"\f139"}.fa-chevron-down:before{content:"\f078"}.fa-chevron-left:before{content:"\f053"}.fa-chevron-right:before{content:"\f054"}.fa-chevron-up:before{content:"\f077"}.fa-child:before{content:"\f1ae"}.fa-chrome:before{content:"\f268"}.fa-chromecast:before{content:"\f838"}.fa-church:before{content:"\f51d"}.fa-circle:before{content:"\f111"}.fa-circle-notch:before{content:"\f1ce"}.fa-city:before{content:"\f64f"}.fa-clinic-medical:before{content:"\f7f2"}.fa-clipboard:before{content:"\f328"}.fa-clipboard-check:before{content:"\f46c"}.fa-clipboard-list:before{content:"\f46d"}.fa-clock:before{content:"\f017"}.fa-clone:before{content:"\f24d"}.fa-closed-captioning:before{content:"\f20a"}.fa-cloud:before{content:"\f0c2"}.fa-cloud-download-alt:before{content:"\f381"}.fa-cloud-meatball:before{content:"\f73b"}.fa-cloud-moon:before{content:"\f6c3"}.fa-cloud-moon-rain:before{content:"\f73c"}.fa-cloud-rain:before{content:"\f73d"}.fa-cloud-showers-heavy:before{content:"\f740"}.fa-cloud-sun:before{content:"\f6c4"}.fa-cloud-sun-rain:before{content:"\f743"}.fa-cloud-upload-alt:before{content:"\f382"}.fa-cloudflare:before{content:"\e07d"}.fa-cloudscale:before{content:"\f383"}.fa-cloudsmith:before{content:"\f384"}.fa-cloudversify:before{content:"\f385"}.fa-cocktail:before{content:"\f561"}.fa-code:before{content:"\f121"}.fa-code-branch:before{content:"\f126"}.fa-codepen:before{content:"\f1cb"}.fa-codiepie:before{content:"\f284"}.fa-coffee:before{content:"\f0f4"}.fa-cog:before{content:"\f013"}.fa-cogs:before{content:"\f085"}.fa-coins:before{content:"\f51e"}.fa-columns:before{content:"\f0db"}.fa-comment:before{content:"\f075"}.fa-comment-alt:before{content:"\f27a"}.fa-comment-dollar:before{content:"\f651"}.fa-comment-dots:before{content:"\f4ad"}.fa-comment-medical:before{content:"\f7f5"}.fa-comment-slash:before{content:"\f4b3"}.fa-comments:before{content:"\f086"}.fa-comments-dollar:before{content:"\f653"}.fa-compact-disc:before{content:"\f51f"}.fa-compass:before{content:"\f14e"}.fa-compress:before{content:"\f066"}.fa-compress-alt:before{content:"\f422"}.fa-compress-arrows-alt:before{content:"\f78c"}.fa-concierge-bell:before{content:"\f562"}.fa-confluence:before{content:"\f78d"}.fa-connectdevelop:before{content:"\f20e"}.fa-contao:before{content:"\f26d"}.fa-cookie:before{content:"\f563"}.fa-cookie-bite:before{content:"\f564"}.fa-copy:before{content:"\f0c5"}.fa-copyright:before{content:"\f1f9"}.fa-cotton-bureau:before{content:"\f89e"}.fa-couch:before{content:"\f4b8"}.fa-cpanel:before{content:"\f388"}.fa-creative-commons:before{content:"\f25e"}.fa-creative-commons-by:before{content:"\f4e7"}.fa-creative-commons-nc:before{content:"\f4e8"}.fa-creative-commons-nc-eu:before{content:"\f4e9"}.fa-creative-commons-nc-jp:before{content:"\f4ea"}.fa-creative-commons-nd:before{content:"\f4eb"}.fa-creative-commons-pd:before{content:"\f4ec"}.fa-creative-commons-pd-alt:before{content:"\f4ed"}.fa-creative-commons-remix:before{content:"\f4ee"}.fa-creative-commons-sa:before{content:"\f4ef"}.fa-creative-commons-sampling:before{content:"\f4f0"}.fa-creative-commons-sampling-plus:before{content:"\f4f1"}.fa-creative-commons-share:before{content:"\f4f2"}.fa-creative-commons-zero:before{content:"\f4f3"}.fa-credit-card:before{content:"\f09d"}.fa-critical-role:before{content:"\f6c9"}.fa-crop:before{content:"\f125"}.fa-crop-alt:before{content:"\f565"}.fa-cross:before{content:"\f654"}.fa-crosshairs:before{content:"\f05b"}.fa-crow:before{content:"\f520"}.fa-crown:before{content:"\f521"}.fa-crutch:before{content:"\f7f7"}.fa-css3:before{content:"\f13c"}.fa-css3-alt:before{content:"\f38b"}.fa-cube:before{content:"\f1b2"}.fa-cubes:before{content:"\f1b3"}.fa-cut:before{content:"\f0c4"}.fa-cuttlefish:before{content:"\f38c"}.fa-d-and-d:before{content:"\f38d"}.fa-d-and-d-beyond:before{content:"\f6ca"}.fa-dailymotion:before{content:"\e052"}.fa-dashcube:before{content:"\f210"}.fa-database:before{content:"\f1c0"}.fa-deaf:before{content:"\f2a4"}.fa-deezer:before{content:"\e077"}.fa-delicious:before{content:"\f1a5"}.fa-democrat:before{content:"\f747"}.fa-deploydog:before{content:"\f38e"}.fa-deskpro:before{content:"\f38f"}.fa-desktop:before{content:"\f108"}.fa-dev:before{content:"\f6cc"}.fa-deviantart:before{content:"\f1bd"}.fa-dharmachakra:before{content:"\f655"}.fa-dhl:before{content:"\f790"}.fa-diagnoses:before{content:"\f470"}.fa-diaspora:before{content:"\f791"}.fa-dice:before{content:"\f522"}.fa-dice-d20:before{content:"\f6cf"}.fa-dice-d6:before{content:"\f6d1"}.fa-dice-five:before{content:"\f523"}.fa-dice-four:before{content:"\f524"}.fa-dice-one:before{content:"\f525"}.fa-dice-six:before{content:"\f526"}.fa-dice-three:before{content:"\f527"}.fa-dice-two:before{content:"\f528"}.fa-digg:before{content:"\f1a6"}.fa-digital-ocean:before{content:"\f391"}.fa-digital-tachograph:before{content:"\f566"}.fa-directions:before{content:"\f5eb"}.fa-discord:before{content:"\f392"}.fa-discourse:before{content:"\f393"}.fa-disease:before{content:"\f7fa"}.fa-divide:before{content:"\f529"}.fa-dizzy:before{content:"\f567"}.fa-dna:before{content:"\f471"}.fa-dochub:before{content:"\f394"}.fa-docker:before{content:"\f395"}.fa-dog:before{content:"\f6d3"}.fa-dollar-sign:before{content:"\f155"}.fa-dolly:before{content:"\f472"}.fa-dolly-flatbed:before{content:"\f474"}.fa-donate:before{content:"\f4b9"}.fa-door-closed:before{content:"\f52a"}.fa-door-open:before{content:"\f52b"}.fa-dot-circle:before{content:"\f192"}.fa-dove:before{content:"\f4ba"}.fa-download:before{content:"\f019"}.fa-draft2digital:before{content:"\f396"}.fa-drafting-compass:before{content:"\f568"}.fa-dragon:before{content:"\f6d5"}.fa-draw-polygon:before{content:"\f5ee"}.fa-dribbble:before{content:"\f17d"}.fa-dribbble-square:before{content:"\f397"}.fa-dropbox:before{content:"\f16b"}.fa-drum:before{content:"\f569"}.fa-drum-steelpan:before{content:"\f56a"}.fa-drumstick-bite:before{content:"\f6d7"}.fa-drupal:before{content:"\f1a9"}.fa-dumbbell:before{content:"\f44b"}.fa-dumpster:before{content:"\f793"}.fa-dumpster-fire:before{content:"\f794"}.fa-dungeon:before{content:"\f6d9"}.fa-dyalog:before{content:"\f399"}.fa-earlybirds:before{content:"\f39a"}.fa-ebay:before{content:"\f4f4"}.fa-edge:before{content:"\f282"}.fa-edge-legacy:before{content:"\e078"}.fa-edit:before{content:"\f044"}.fa-egg:before{content:"\f7fb"}.fa-eject:before{content:"\f052"}.fa-elementor:before{content:"\f430"}.fa-ellipsis-h:before{content:"\f141"}.fa-ellipsis-v:before{content:"\f142"}.fa-ello:before{content:"\f5f1"}.fa-ember:before{content:"\f423"}.fa-empire:before{content:"\f1d1"}.fa-envelope:before{content:"\f0e0"}.fa-envelope-open:before{content:"\f2b6"}.fa-envelope-open-text:before{content:"\f658"}.fa-envelope-square:before{content:"\f199"}.fa-envira:before{content:"\f299"}.fa-equals:before{content:"\f52c"}.fa-eraser:before{content:"\f12d"}.fa-erlang:before{content:"\f39d"}.fa-ethereum:before{content:"\f42e"}.fa-ethernet:before{content:"\f796"}.fa-etsy:before{content:"\f2d7"}.fa-euro-sign:before{content:"\f153"}.fa-evernote:before{content:"\f839"}.fa-exchange-alt:before{content:"\f362"}.fa-exclamation:before{content:"\f12a"}.fa-exclamation-circle:before{content:"\f06a"}.fa-exclamation-triangle:before{content:"\f071"}.fa-expand:before{content:"\f065"}.fa-expand-alt:before{content:"\f424"}.fa-expand-arrows-alt:before{content:"\f31e"}.fa-expeditedssl:before{content:"\f23e"}.fa-external-link-alt:before{content:"\f35d"}.fa-external-link-square-alt:before{content:"\f360"}.fa-eye:before{content:"\f06e"}.fa-eye-dropper:before{content:"\f1fb"}.fa-eye-slash:before{content:"\f070"}.fa-facebook:before{content:"\f09a"}.fa-facebook-f:before{content:"\f39e"}.fa-facebook-messenger:before{content:"\f39f"}.fa-facebook-square:before{content:"\f082"}.fa-fan:before{content:"\f863"}.fa-fantasy-flight-games:before{content:"\f6dc"}.fa-fast-backward:before{content:"\f049"}.fa-fast-forward:before{content:"\f050"}.fa-faucet:before{content:"\e005"}.fa-fax:before{content:"\f1ac"}.fa-feather:before{content:"\f52d"}.fa-feather-alt:before{content:"\f56b"}.fa-fedex:before{content:"\f797"}.fa-fedora:before{content:"\f798"}.fa-female:before{content:"\f182"}.fa-fighter-jet:before{content:"\f0fb"}.fa-figma:before{content:"\f799"}.fa-file:before{content:"\f15b"}.fa-file-alt:before{content:"\f15c"}.fa-file-archive:before{content:"\f1c6"}.fa-file-audio:before{content:"\f1c7"}.fa-file-code:before{content:"\f1c9"}.fa-file-contract:before{content:"\f56c"}.fa-file-csv:before{content:"\f6dd"}.fa-file-download:before{content:"\f56d"}.fa-file-excel:before{content:"\f1c3"}.fa-file-export:before{content:"\f56e"}.fa-file-image:before{content:"\f1c5"}.fa-file-import:before{content:"\f56f"}.fa-file-invoice:before{content:"\f570"}.fa-file-invoice-dollar:before{content:"\f571"}.fa-file-medical:before{content:"\f477"}.fa-file-medical-alt:before{content:"\f478"}.fa-file-pdf:before{content:"\f1c1"}.fa-file-powerpoint:before{content:"\f1c4"}.fa-file-prescription:before{content:"\f572"}.fa-file-signature:before{content:"\f573"}.fa-file-upload:before{content:"\f574"}.fa-file-video:before{content:"\f1c8"}.fa-file-word:before{content:"\f1c2"}.fa-fill:before{content:"\f575"}.fa-fill-drip:before{content:"\f576"}.fa-film:before{content:"\f008"}.fa-filter:before{content:"\f0b0"}.fa-fingerprint:before{content:"\f577"}.fa-fire:before{content:"\f06d"}.fa-fire-alt:before{content:"\f7e4"}.fa-fire-extinguisher:before{content:"\f134"}.fa-firefox:before{content:"\f269"}.fa-firefox-browser:before{content:"\e007"}.fa-first-aid:before{content:"\f479"}.fa-first-order:before{content:"\f2b0"}.fa-first-order-alt:before{content:"\f50a"}.fa-firstdraft:before{content:"\f3a1"}.fa-fish:before{content:"\f578"}.fa-fist-raised:before{content:"\f6de"}.fa-flag:before{content:"\f024"}.fa-flag-checkered:before{content:"\f11e"}.fa-flag-usa:before{content:"\f74d"}.fa-flask:before{content:"\f0c3"}.fa-flickr:before{content:"\f16e"}.fa-flipboard:before{content:"\f44d"}.fa-flushed:before{content:"\f579"}.fa-fly:before{content:"\f417"}.fa-folder:before{content:"\f07b"}.fa-folder-minus:before{content:"\f65d"}.fa-folder-open:before{content:"\f07c"}.fa-folder-plus:before{content:"\f65e"}.fa-font:before{content:"\f031"}.fa-font-awesome:before{content:"\f2b4"}.fa-font-awesome-alt:before{content:"\f35c"}.fa-font-awesome-flag:before{content:"\f425"}.fa-font-awesome-logo-full:before{content:"\f4e6"}.fa-fonticons:before{content:"\f280"}.fa-fonticons-fi:before{content:"\f3a2"}.fa-football-ball:before{content:"\f44e"}.fa-fort-awesome:before{content:"\f286"}.fa-fort-awesome-alt:before{content:"\f3a3"}.fa-forumbee:before{content:"\f211"}.fa-forward:before{content:"\f04e"}.fa-foursquare:before{content:"\f180"}.fa-free-code-camp:before{content:"\f2c5"}.fa-freebsd:before{content:"\f3a4"}.fa-frog:before{content:"\f52e"}.fa-frown:before{content:"\f119"}.fa-frown-open:before{content:"\f57a"}.fa-fulcrum:before{content:"\f50b"}.fa-funnel-dollar:before{content:"\f662"}.fa-futbol:before{content:"\f1e3"}.fa-galactic-republic:before{content:"\f50c"}.fa-galactic-senate:before{content:"\f50d"}.fa-gamepad:before{content:"\f11b"}.fa-gas-pump:before{content:"\f52f"}.fa-gavel:before{content:"\f0e3"}.fa-gem:before{content:"\f3a5"}.fa-genderless:before{content:"\f22d"}.fa-get-pocket:before{content:"\f265"}.fa-gg:before{content:"\f260"}.fa-gg-circle:before{content:"\f261"}.fa-ghost:before{content:"\f6e2"}.fa-gift:before{content:"\f06b"}.fa-gifts:before{content:"\f79c"}.fa-git:before{content:"\f1d3"}.fa-git-alt:before{content:"\f841"}.fa-git-square:before{content:"\f1d2"}.fa-github:before{content:"\f09b"}.fa-github-alt:before{content:"\f113"}.fa-github-square:before{content:"\f092"}.fa-gitkraken:before{content:"\f3a6"}.fa-gitlab:before{content:"\f296"}.fa-gitter:before{content:"\f426"}.fa-glass-cheers:before{content:"\f79f"}.fa-glass-martini:before{content:"\f000"}.fa-glass-martini-alt:before{content:"\f57b"}.fa-glass-whiskey:before{content:"\f7a0"}.fa-glasses:before{content:"\f530"}.fa-glide:before{content:"\f2a5"}.fa-glide-g:before{content:"\f2a6"}.fa-globe:before{content:"\f0ac"}.fa-globe-africa:before{content:"\f57c"}.fa-globe-americas:before{content:"\f57d"}.fa-globe-asia:before{content:"\f57e"}.fa-globe-europe:before{content:"\f7a2"}.fa-gofore:before{content:"\f3a7"}.fa-golf-ball:before{content:"\f450"}.fa-goodreads:before{content:"\f3a8"}.fa-goodreads-g:before{content:"\f3a9"}.fa-google:before{content:"\f1a0"}.fa-google-drive:before{content:"\f3aa"}.fa-google-pay:before{content:"\e079"}.fa-google-play:before{content:"\f3ab"}.fa-google-plus:before{content:"\f2b3"}.fa-google-plus-g:before{content:"\f0d5"}.fa-google-plus-square:before{content:"\f0d4"}.fa-google-wallet:before{content:"\f1ee"}.fa-gopuram:before{content:"\f664"}.fa-graduation-cap:before{content:"\f19d"}.fa-gratipay:before{content:"\f184"}.fa-grav:before{content:"\f2d6"}.fa-greater-than:before{content:"\f531"}.fa-greater-than-equal:before{content:"\f532"}.fa-grimace:before{content:"\f57f"}.fa-grin:before{content:"\f580"}.fa-grin-alt:before{content:"\f581"}.fa-grin-beam:before{content:"\f582"}.fa-grin-beam-sweat:before{content:"\f583"}.fa-grin-hearts:before{content:"\f584"}.fa-grin-squint:before{content:"\f585"}.fa-grin-squint-tears:before{content:"\f586"}.fa-grin-stars:before{content:"\f587"}.fa-grin-tears:before{content:"\f588"}.fa-grin-tongue:before{content:"\f589"}.fa-grin-tongue-squint:before{content:"\f58a"}.fa-grin-tongue-wink:before{content:"\f58b"}.fa-grin-wink:before{content:"\f58c"}.fa-grip-horizontal:before{content:"\f58d"}.fa-grip-lines:before{content:"\f7a4"}.fa-grip-lines-vertical:before{content:"\f7a5"}.fa-grip-vertical:before{content:"\f58e"}.fa-gripfire:before{content:"\f3ac"}.fa-grunt:before{content:"\f3ad"}.fa-guilded:before{content:"\e07e"}.fa-guitar:before{content:"\f7a6"}.fa-gulp:before{content:"\f3ae"}.fa-h-square:before{content:"\f0fd"}.fa-hacker-news:before{content:"\f1d4"}.fa-hacker-news-square:before{content:"\f3af"}.fa-hackerrank:before{content:"\f5f7"}.fa-hamburger:before{content:"\f805"}.fa-hammer:before{content:"\f6e3"}.fa-hamsa:before{content:"\f665"}.fa-hand-holding:before{content:"\f4bd"}.fa-hand-holding-heart:before{content:"\f4be"}.fa-hand-holding-medical:before{content:"\e05c"}.fa-hand-holding-usd:before{content:"\f4c0"}.fa-hand-holding-water:before{content:"\f4c1"}.fa-hand-lizard:before{content:"\f258"}.fa-hand-middle-finger:before{content:"\f806"}.fa-hand-paper:before{content:"\f256"}.fa-hand-peace:before{content:"\f25b"}.fa-hand-point-down:before{content:"\f0a7"}.fa-hand-point-left:before{content:"\f0a5"}.fa-hand-point-right:before{content:"\f0a4"}.fa-hand-point-up:before{content:"\f0a6"}.fa-hand-pointer:before{content:"\f25a"}.fa-hand-rock:before{content:"\f255"}.fa-hand-scissors:before{content:"\f257"}.fa-hand-sparkles:before{content:"\e05d"}.fa-hand-spock:before{content:"\f259"}.fa-hands:before{content:"\f4c2"}.fa-hands-helping:before{content:"\f4c4"}.fa-hands-wash:before{content:"\e05e"}.fa-handshake:before{content:"\f2b5"}.fa-handshake-alt-slash:before{content:"\e05f"}.fa-handshake-slash:before{content:"\e060"}.fa-hanukiah:before{content:"\f6e6"}.fa-hard-hat:before{content:"\f807"}.fa-hashtag:before{content:"\f292"}.fa-hat-cowboy:before{content:"\f8c0"}.fa-hat-cowboy-side:before{content:"\f8c1"}.fa-hat-wizard:before{content:"\f6e8"}.fa-hdd:before{content:"\f0a0"}.fa-head-side-cough:before{content:"\e061"}.fa-head-side-cough-slash:before{content:"\e062"}.fa-head-side-mask:before{content:"\e063"}.fa-head-side-virus:before{content:"\e064"}.fa-heading:before{content:"\f1dc"}.fa-headphones:before{content:"\f025"}.fa-headphones-alt:before{content:"\f58f"}.fa-headset:before{content:"\f590"}.fa-heart:before{content:"\f004"}.fa-heart-broken:before{content:"\f7a9"}.fa-heartbeat:before{content:"\f21e"}.fa-helicopter:before{content:"\f533"}.fa-highlighter:before{content:"\f591"}.fa-hiking:before{content:"\f6ec"}.fa-hippo:before{content:"\f6ed"}.fa-hips:before{content:"\f452"}.fa-hire-a-helper:before{content:"\f3b0"}.fa-history:before{content:"\f1da"}.fa-hive:before{content:"\e07f"}.fa-hockey-puck:before{content:"\f453"}.fa-holly-berry:before{content:"\f7aa"}.fa-home:before{content:"\f015"}.fa-hooli:before{content:"\f427"}.fa-hornbill:before{content:"\f592"}.fa-horse:before{content:"\f6f0"}.fa-horse-head:before{content:"\f7ab"}.fa-hospital:before{content:"\f0f8"}.fa-hospital-alt:before{content:"\f47d"}.fa-hospital-symbol:before{content:"\f47e"}.fa-hospital-user:before{content:"\f80d"}.fa-hot-tub:before{content:"\f593"}.fa-hotdog:before{content:"\f80f"}.fa-hotel:before{content:"\f594"}.fa-hotjar:before{content:"\f3b1"}.fa-hourglass:before{content:"\f254"}.fa-hourglass-end:before{content:"\f253"}.fa-hourglass-half:before{content:"\f252"}.fa-hourglass-start:before{content:"\f251"}.fa-house-damage:before{content:"\f6f1"}.fa-house-user:before{content:"\e065"}.fa-houzz:before{content:"\f27c"}.fa-hryvnia:before{content:"\f6f2"}.fa-html5:before{content:"\f13b"}.fa-hubspot:before{content:"\f3b2"}.fa-i-cursor:before{content:"\f246"}.fa-ice-cream:before{content:"\f810"}.fa-icicles:before{content:"\f7ad"}.fa-icons:before{content:"\f86d"}.fa-id-badge:before{content:"\f2c1"}.fa-id-card:before{content:"\f2c2"}.fa-id-card-alt:before{content:"\f47f"}.fa-ideal:before{content:"\e013"}.fa-igloo:before{content:"\f7ae"}.fa-image:before{content:"\f03e"}.fa-images:before{content:"\f302"}.fa-imdb:before{content:"\f2d8"}.fa-inbox:before{content:"\f01c"}.fa-indent:before{content:"\f03c"}.fa-industry:before{content:"\f275"}.fa-infinity:before{content:"\f534"}.fa-info:before{content:"\f129"}.fa-info-circle:before{content:"\f05a"}.fa-innosoft:before{content:"\e080"}.fa-instagram:before{content:"\f16d"}.fa-instagram-square:before{content:"\e055"}.fa-instalod:before{content:"\e081"}.fa-intercom:before{content:"\f7af"}.fa-internet-explorer:before{content:"\f26b"}.fa-invision:before{content:"\f7b0"}.fa-ioxhost:before{content:"\f208"}.fa-italic:before{content:"\f033"}.fa-itch-io:before{content:"\f83a"}.fa-itunes:before{content:"\f3b4"}.fa-itunes-note:before{content:"\f3b5"}.fa-java:before{content:"\f4e4"}.fa-jedi:before{content:"\f669"}.fa-jedi-order:before{content:"\f50e"}.fa-jenkins:before{content:"\f3b6"}.fa-jira:before{content:"\f7b1"}.fa-joget:before{content:"\f3b7"}.fa-joint:before{content:"\f595"}.fa-joomla:before{content:"\f1aa"}.fa-journal-whills:before{content:"\f66a"}.fa-js:before{content:"\f3b8"}.fa-js-square:before{content:"\f3b9"}.fa-jsfiddle:before{content:"\f1cc"}.fa-kaaba:before{content:"\f66b"}.fa-kaggle:before{content:"\f5fa"}.fa-key:before{content:"\f084"}.fa-keybase:before{content:"\f4f5"}.fa-keyboard:before{content:"\f11c"}.fa-keycdn:before{content:"\f3ba"}.fa-khanda:before{content:"\f66d"}.fa-kickstarter:before{content:"\f3bb"}.fa-kickstarter-k:before{content:"\f3bc"}.fa-kiss:before{content:"\f596"}.fa-kiss-beam:before{content:"\f597"}.fa-kiss-wink-heart:before{content:"\f598"}.fa-kiwi-bird:before{content:"\f535"}.fa-korvue:before{content:"\f42f"}.fa-landmark:before{content:"\f66f"}.fa-language:before{content:"\f1ab"}.fa-laptop:before{content:"\f109"}.fa-laptop-code:before{content:"\f5fc"}.fa-laptop-house:before{content:"\e066"}.fa-laptop-medical:before{content:"\f812"}.fa-laravel:before{content:"\f3bd"}.fa-lastfm:before{content:"\f202"}.fa-lastfm-square:before{content:"\f203"}.fa-laugh:before{content:"\f599"}.fa-laugh-beam:before{content:"\f59a"}.fa-laugh-squint:before{content:"\f59b"}.fa-laugh-wink:before{content:"\f59c"}.fa-layer-group:before{content:"\f5fd"}.fa-leaf:before{content:"\f06c"}.fa-leanpub:before{content:"\f212"}.fa-lemon:before{content:"\f094"}.fa-less:before{content:"\f41d"}.fa-less-than:before{content:"\f536"}.fa-less-than-equal:before{content:"\f537"}.fa-level-down-alt:before{content:"\f3be"}.fa-level-up-alt:before{content:"\f3bf"}.fa-life-ring:before{content:"\f1cd"}.fa-lightbulb:before{content:"\f0eb"}.fa-line:before{content:"\f3c0"}.fa-link:before{content:"\f0c1"}.fa-linkedin:before{content:"\f08c"}.fa-linkedin-in:before{content:"\f0e1"}.fa-linode:before{content:"\f2b8"}.fa-linux:before{content:"\f17c"}.fa-lira-sign:before{content:"\f195"}.fa-list:before{content:"\f03a"}.fa-list-alt:before{content:"\f022"}.fa-list-ol:before{content:"\f0cb"}.fa-list-ul:before{content:"\f0ca"}.fa-location-arrow:before{content:"\f124"}.fa-lock:before{content:"\f023"}.fa-lock-open:before{content:"\f3c1"}.fa-long-arrow-alt-down:before{content:"\f309"}.fa-long-arrow-alt-left:before{content:"\f30a"}.fa-long-arrow-alt-right:before{content:"\f30b"}.fa-long-arrow-alt-up:before{content:"\f30c"}.fa-low-vision:before{content:"\f2a8"}.fa-luggage-cart:before{content:"\f59d"}.fa-lungs:before{content:"\f604"}.fa-lungs-virus:before{content:"\e067"}.fa-lyft:before{content:"\f3c3"}.fa-magento:before{content:"\f3c4"}.fa-magic:before{content:"\f0d0"}.fa-magnet:before{content:"\f076"}.fa-mail-bulk:before{content:"\f674"}.fa-mailchimp:before{content:"\f59e"}.fa-male:before{content:"\f183"}.fa-mandalorian:before{content:"\f50f"}.fa-map:before{content:"\f279"}.fa-map-marked:before{content:"\f59f"}.fa-map-marked-alt:before{content:"\f5a0"}.fa-map-marker:before{content:"\f041"}.fa-map-marker-alt:before{content:"\f3c5"}.fa-map-pin:before{content:"\f276"}.fa-map-signs:before{content:"\f277"}.fa-markdown:before{content:"\f60f"}.fa-marker:before{content:"\f5a1"}.fa-mars:before{content:"\f222"}.fa-mars-double:before{content:"\f227"}.fa-mars-stroke:before{content:"\f229"}.fa-mars-stroke-h:before{content:"\f22b"}.fa-mars-stroke-v:before{content:"\f22a"}.fa-mask:before{content:"\f6fa"}.fa-mastodon:before{content:"\f4f6"}.fa-maxcdn:before{content:"\f136"}.fa-mdb:before{content:"\f8ca"}.fa-medal:before{content:"\f5a2"}.fa-medapps:before{content:"\f3c6"}.fa-medium:before{content:"\f23a"}.fa-medium-m:before{content:"\f3c7"}.fa-medkit:before{content:"\f0fa"}.fa-medrt:before{content:"\f3c8"}.fa-meetup:before{content:"\f2e0"}.fa-megaport:before{content:"\f5a3"}.fa-meh:before{content:"\f11a"}.fa-meh-blank:before{content:"\f5a4"}.fa-meh-rolling-eyes:before{content:"\f5a5"}.fa-memory:before{content:"\f538"}.fa-mendeley:before{content:"\f7b3"}.fa-menorah:before{content:"\f676"}.fa-mercury:before{content:"\f223"}.fa-meteor:before{content:"\f753"}.fa-microblog:before{content:"\e01a"}.fa-microchip:before{content:"\f2db"}.fa-microphone:before{content:"\f130"}.fa-microphone-alt:before{content:"\f3c9"}.fa-microphone-alt-slash:before{content:"\f539"}.fa-microphone-slash:before{content:"\f131"}.fa-microscope:before{content:"\f610"}.fa-microsoft:before{content:"\f3ca"}.fa-minus:before{content:"\f068"}.fa-minus-circle:before{content:"\f056"}.fa-minus-square:before{content:"\f146"}.fa-mitten:before{content:"\f7b5"}.fa-mix:before{content:"\f3cb"}.fa-mixcloud:before{content:"\f289"}.fa-mixer:before{content:"\e056"}.fa-mizuni:before{content:"\f3cc"}.fa-mobile:before{content:"\f10b"}.fa-mobile-alt:before{content:"\f3cd"}.fa-modx:before{content:"\f285"}.fa-monero:before{content:"\f3d0"}.fa-money-bill:before{content:"\f0d6"}.fa-money-bill-alt:before{content:"\f3d1"}.fa-money-bill-wave:before{content:"\f53a"}.fa-money-bill-wave-alt:before{content:"\f53b"}.fa-money-check:before{content:"\f53c"}.fa-money-check-alt:before{content:"\f53d"}.fa-monument:before{content:"\f5a6"}.fa-moon:before{content:"\f186"}.fa-mortar-pestle:before{content:"\f5a7"}.fa-mosque:before{content:"\f678"}.fa-motorcycle:before{content:"\f21c"}.fa-mountain:before{content:"\f6fc"}.fa-mouse:before{content:"\f8cc"}.fa-mouse-pointer:before{content:"\f245"}.fa-mug-hot:before{content:"\f7b6"}.fa-music:before{content:"\f001"}.fa-napster:before{content:"\f3d2"}.fa-neos:before{content:"\f612"}.fa-network-wired:before{content:"\f6ff"}.fa-neuter:before{content:"\f22c"}.fa-newspaper:before{content:"\f1ea"}.fa-nimblr:before{content:"\f5a8"}.fa-node:before{content:"\f419"}.fa-node-js:before{content:"\f3d3"}.fa-not-equal:before{content:"\f53e"}.fa-notes-medical:before{content:"\f481"}.fa-npm:before{content:"\f3d4"}.fa-ns8:before{content:"\f3d5"}.fa-nutritionix:before{content:"\f3d6"}.fa-object-group:before{content:"\f247"}.fa-object-ungroup:before{content:"\f248"}.fa-octopus-deploy:before{content:"\e082"}.fa-odnoklassniki:before{content:"\f263"}.fa-odnoklassniki-square:before{content:"\f264"}.fa-oil-can:before{content:"\f613"}.fa-old-republic:before{content:"\f510"}.fa-om:before{content:"\f679"}.fa-opencart:before{content:"\f23d"}.fa-openid:before{content:"\f19b"}.fa-opera:before{content:"\f26a"}.fa-optin-monster:before{content:"\f23c"}.fa-orcid:before{content:"\f8d2"}.fa-osi:before{content:"\f41a"}.fa-otter:before{content:"\f700"}.fa-outdent:before{content:"\f03b"}.fa-page4:before{content:"\f3d7"}.fa-pagelines:before{content:"\f18c"}.fa-pager:before{content:"\f815"}.fa-paint-brush:before{content:"\f1fc"}.fa-paint-roller:before{content:"\f5aa"}.fa-palette:before{content:"\f53f"}.fa-palfed:before{content:"\f3d8"}.fa-pallet:before{content:"\f482"}.fa-paper-plane:before{content:"\f1d8"}.fa-paperclip:before{content:"\f0c6"}.fa-parachute-box:before{content:"\f4cd"}.fa-paragraph:before{content:"\f1dd"}.fa-parking:before{content:"\f540"}.fa-passport:before{content:"\f5ab"}.fa-pastafarianism:before{content:"\f67b"}.fa-paste:before{content:"\f0ea"}.fa-patreon:before{content:"\f3d9"}.fa-pause:before{content:"\f04c"}.fa-pause-circle:before{content:"\f28b"}.fa-paw:before{content:"\f1b0"}.fa-paypal:before{content:"\f1ed"}.fa-peace:before{content:"\f67c"}.fa-pen:before{content:"\f304"}.fa-pen-alt:before{content:"\f305"}.fa-pen-fancy:before{content:"\f5ac"}.fa-pen-nib:before{content:"\f5ad"}.fa-pen-square:before{content:"\f14b"}.fa-pencil-alt:before{content:"\f303"}.fa-pencil-ruler:before{content:"\f5ae"}.fa-penny-arcade:before{content:"\f704"}.fa-people-arrows:before{content:"\e068"}.fa-people-carry:before{content:"\f4ce"}.fa-pepper-hot:before{content:"\f816"}.fa-perbyte:before{content:"\e083"}.fa-percent:before{content:"\f295"}.fa-percentage:before{content:"\f541"}.fa-periscope:before{content:"\f3da"}.fa-person-booth:before{content:"\f756"}.fa-phabricator:before{content:"\f3db"}.fa-phoenix-framework:before{content:"\f3dc"}.fa-phoenix-squadron:before{content:"\f511"}.fa-phone:before{content:"\f095"}.fa-phone-alt:before{content:"\f879"}.fa-phone-slash:before{content:"\f3dd"}.fa-phone-square:before{content:"\f098"}.fa-phone-square-alt:before{content:"\f87b"}.fa-phone-volume:before{content:"\f2a0"}.fa-photo-video:before{content:"\f87c"}.fa-php:before{content:"\f457"}.fa-pied-piper:before{content:"\f2ae"}.fa-pied-piper-alt:before{content:"\f1a8"}.fa-pied-piper-hat:before{content:"\f4e5"}.fa-pied-piper-pp:before{content:"\f1a7"}.fa-pied-piper-square:before{content:"\e01e"}.fa-piggy-bank:before{content:"\f4d3"}.fa-pills:before{content:"\f484"}.fa-pinterest:before{content:"\f0d2"}.fa-pinterest-p:before{content:"\f231"}.fa-pinterest-square:before{content:"\f0d3"}.fa-pizza-slice:before{content:"\f818"}.fa-place-of-worship:before{content:"\f67f"}.fa-plane:before{content:"\f072"}.fa-plane-arrival:before{content:"\f5af"}.fa-plane-departure:before{content:"\f5b0"}.fa-plane-slash:before{content:"\e069"}.fa-play:before{content:"\f04b"}.fa-play-circle:before{content:"\f144"}.fa-playstation:before{content:"\f3df"}.fa-plug:before{content:"\f1e6"}.fa-plus:before{content:"\f067"}.fa-plus-circle:before{content:"\f055"}.fa-plus-square:before{content:"\f0fe"}.fa-podcast:before{content:"\f2ce"}.fa-poll:before{content:"\f681"}.fa-poll-h:before{content:"\f682"}.fa-poo:before{content:"\f2fe"}.fa-poo-storm:before{content:"\f75a"}.fa-poop:before{content:"\f619"}.fa-portrait:before{content:"\f3e0"}.fa-pound-sign:before{content:"\f154"}.fa-power-off:before{content:"\f011"}.fa-pray:before{content:"\f683"}.fa-praying-hands:before{content:"\f684"}.fa-prescription:before{content:"\f5b1"}.fa-prescription-bottle:before{content:"\f485"}.fa-prescription-bottle-alt:before{content:"\f486"}.fa-print:before{content:"\f02f"}.fa-procedures:before{content:"\f487"}.fa-product-hunt:before{content:"\f288"}.fa-project-diagram:before{content:"\f542"}.fa-pump-medical:before{content:"\e06a"}.fa-pump-soap:before{content:"\e06b"}.fa-pushed:before{content:"\f3e1"}.fa-puzzle-piece:before{content:"\f12e"}.fa-python:before{content:"\f3e2"}.fa-qq:before{content:"\f1d6"}.fa-qrcode:before{content:"\f029"}.fa-question:before{content:"\f128"}.fa-question-circle:before{content:"\f059"}.fa-quidditch:before{content:"\f458"}.fa-quinscape:before{content:"\f459"}.fa-quora:before{content:"\f2c4"}.fa-quote-left:before{content:"\f10d"}.fa-quote-right:before{content:"\f10e"}.fa-quran:before{content:"\f687"}.fa-r-project:before{content:"\f4f7"}.fa-radiation:before{content:"\f7b9"}.fa-radiation-alt:before{content:"\f7ba"}.fa-rainbow:before{content:"\f75b"}.fa-random:before{content:"\f074"}.fa-raspberry-pi:before{content:"\f7bb"}.fa-ravelry:before{content:"\f2d9"}.fa-react:before{content:"\f41b"}.fa-reacteurope:before{content:"\f75d"}.fa-readme:before{content:"\f4d5"}.fa-rebel:before{content:"\f1d0"}.fa-receipt:before{content:"\f543"}.fa-record-vinyl:before{content:"\f8d9"}.fa-recycle:before{content:"\f1b8"}.fa-red-river:before{content:"\f3e3"}.fa-reddit:before{content:"\f1a1"}.fa-reddit-alien:before{content:"\f281"}.fa-reddit-square:before{content:"\f1a2"}.fa-redhat:before{content:"\f7bc"}.fa-redo:before{content:"\f01e"}.fa-redo-alt:before{content:"\f2f9"}.fa-registered:before{content:"\f25d"}.fa-remove-format:before{content:"\f87d"}.fa-renren:before{content:"\f18b"}.fa-reply:before{content:"\f3e5"}.fa-reply-all:before{content:"\f122"}.fa-replyd:before{content:"\f3e6"}.fa-republican:before{content:"\f75e"}.fa-researchgate:before{content:"\f4f8"}.fa-resolving:before{content:"\f3e7"}.fa-restroom:before{content:"\f7bd"}.fa-retweet:before{content:"\f079"}.fa-rev:before{content:"\f5b2"}.fa-ribbon:before{content:"\f4d6"}.fa-ring:before{content:"\f70b"}.fa-road:before{content:"\f018"}.fa-robot:before{content:"\f544"}.fa-rocket:before{content:"\f135"}.fa-rocketchat:before{content:"\f3e8"}.fa-rockrms:before{content:"\f3e9"}.fa-route:before{content:"\f4d7"}.fa-rss:before{content:"\f09e"}.fa-rss-square:before{content:"\f143"}.fa-ruble-sign:before{content:"\f158"}.fa-ruler:before{content:"\f545"}.fa-ruler-combined:before{content:"\f546"}.fa-ruler-horizontal:before{content:"\f547"}.fa-ruler-vertical:before{content:"\f548"}.fa-running:before{content:"\f70c"}.fa-rupee-sign:before{content:"\f156"}.fa-rust:before{content:"\e07a"}.fa-sad-cry:before{content:"\f5b3"}.fa-sad-tear:before{content:"\f5b4"}.fa-safari:before{content:"\f267"}.fa-salesforce:before{content:"\f83b"}.fa-sass:before{content:"\f41e"}.fa-satellite:before{content:"\f7bf"}.fa-satellite-dish:before{content:"\f7c0"}.fa-save:before{content:"\f0c7"}.fa-schlix:before{content:"\f3ea"}.fa-school:before{content:"\f549"}.fa-screwdriver:before{content:"\f54a"}.fa-scribd:before{content:"\f28a"}.fa-scroll:before{content:"\f70e"}.fa-sd-card:before{content:"\f7c2"}.fa-search:before{content:"\f002"}.fa-search-dollar:before{content:"\f688"}.fa-search-location:before{content:"\f689"}.fa-search-minus:before{content:"\f010"}.fa-search-plus:before{content:"\f00e"}.fa-searchengin:before{content:"\f3eb"}.fa-seedling:before{content:"\f4d8"}.fa-sellcast:before{content:"\f2da"}.fa-sellsy:before{content:"\f213"}.fa-server:before{content:"\f233"}.fa-servicestack:before{content:"\f3ec"}.fa-shapes:before{content:"\f61f"}.fa-share:before{content:"\f064"}.fa-share-alt:before{content:"\f1e0"}.fa-share-alt-square:before{content:"\f1e1"}.fa-share-square:before{content:"\f14d"}.fa-shekel-sign:before{content:"\f20b"}.fa-shield-alt:before{content:"\f3ed"}.fa-shield-virus:before{content:"\e06c"}.fa-ship:before{content:"\f21a"}.fa-shipping-fast:before{content:"\f48b"}.fa-shirtsinbulk:before{content:"\f214"}.fa-shoe-prints:before{content:"\f54b"}.fa-shopify:before{content:"\e057"}.fa-shopping-bag:before{content:"\f290"}.fa-shopping-basket:before{content:"\f291"}.fa-shopping-cart:before{content:"\f07a"}.fa-shopware:before{content:"\f5b5"}.fa-shower:before{content:"\f2cc"}.fa-shuttle-van:before{content:"\f5b6"}.fa-sign:before{content:"\f4d9"}.fa-sign-in-alt:before{content:"\f2f6"}.fa-sign-language:before{content:"\f2a7"}.fa-sign-out-alt:before{content:"\f2f5"}.fa-signal:before{content:"\f012"}.fa-signature:before{content:"\f5b7"}.fa-sim-card:before{content:"\f7c4"}.fa-simplybuilt:before{content:"\f215"}.fa-sink:before{content:"\e06d"}.fa-sistrix:before{content:"\f3ee"}.fa-sitemap:before{content:"\f0e8"}.fa-sith:before{content:"\f512"}.fa-skating:before{content:"\f7c5"}.fa-sketch:before{content:"\f7c6"}.fa-skiing:before{content:"\f7c9"}.fa-skiing-nordic:before{content:"\f7ca"}.fa-skull:before{content:"\f54c"}.fa-skull-crossbones:before{content:"\f714"}.fa-skyatlas:before{content:"\f216"}.fa-skype:before{content:"\f17e"}.fa-slack:before{content:"\f198"}.fa-slack-hash:before{content:"\f3ef"}.fa-slash:before{content:"\f715"}.fa-sleigh:before{content:"\f7cc"}.fa-sliders-h:before{content:"\f1de"}.fa-slideshare:before{content:"\f1e7"}.fa-smile:before{content:"\f118"}.fa-smile-beam:before{content:"\f5b8"}.fa-smile-wink:before{content:"\f4da"}.fa-smog:before{content:"\f75f"}.fa-smoking:before{content:"\f48d"}.fa-smoking-ban:before{content:"\f54d"}.fa-sms:before{content:"\f7cd"}.fa-snapchat:before{content:"\f2ab"}.fa-snapchat-ghost:before{content:"\f2ac"}.fa-snapchat-square:before{content:"\f2ad"}.fa-snowboarding:before{content:"\f7ce"}.fa-snowflake:before{content:"\f2dc"}.fa-snowman:before{content:"\f7d0"}.fa-snowplow:before{content:"\f7d2"}.fa-soap:before{content:"\e06e"}.fa-socks:before{content:"\f696"}.fa-solar-panel:before{content:"\f5ba"}.fa-sort:before{content:"\f0dc"}.fa-sort-alpha-down:before{content:"\f15d"}.fa-sort-alpha-down-alt:before{content:"\f881"}.fa-sort-alpha-up:before{content:"\f15e"}.fa-sort-alpha-up-alt:before{content:"\f882"}.fa-sort-amount-down:before{content:"\f160"}.fa-sort-amount-down-alt:before{content:"\f884"}.fa-sort-amount-up:before{content:"\f161"}.fa-sort-amount-up-alt:before{content:"\f885"}.fa-sort-down:before{content:"\f0dd"}.fa-sort-numeric-down:before{content:"\f162"}.fa-sort-numeric-down-alt:before{content:"\f886"}.fa-sort-numeric-up:before{content:"\f163"}.fa-sort-numeric-up-alt:before{content:"\f887"}.fa-sort-up:before{content:"\f0de"}.fa-soundcloud:before{content:"\f1be"}.fa-sourcetree:before{content:"\f7d3"}.fa-spa:before{content:"\f5bb"}.fa-space-shuttle:before{content:"\f197"}.fa-speakap:before{content:"\f3f3"}.fa-speaker-deck:before{content:"\f83c"}.fa-spell-check:before{content:"\f891"}.fa-spider:before{content:"\f717"}.fa-spinner:before{content:"\f110"}.fa-splotch:before{content:"\f5bc"}.fa-spotify:before{content:"\f1bc"}.fa-spray-can:before{content:"\f5bd"}.fa-square:before{content:"\f0c8"}.fa-square-full:before{content:"\f45c"}.fa-square-root-alt:before{content:"\f698"}.fa-squarespace:before{content:"\f5be"}.fa-stack-exchange:before{content:"\f18d"}.fa-stack-overflow:before{content:"\f16c"}.fa-stackpath:before{content:"\f842"}.fa-stamp:before{content:"\f5bf"}.fa-star:before{content:"\f005"}.fa-star-and-crescent:before{content:"\f699"}.fa-star-half:before{content:"\f089"}.fa-star-half-alt:before{content:"\f5c0"}.fa-star-of-david:before{content:"\f69a"}.fa-star-of-life:before{content:"\f621"}.fa-staylinked:before{content:"\f3f5"}.fa-steam:before{content:"\f1b6"}.fa-steam-square:before{content:"\f1b7"}.fa-steam-symbol:before{content:"\f3f6"}.fa-step-backward:before{content:"\f048"}.fa-step-forward:before{content:"\f051"}.fa-stethoscope:before{content:"\f0f1"}.fa-sticker-mule:before{content:"\f3f7"}.fa-sticky-note:before{content:"\f249"}.fa-stop:before{content:"\f04d"}.fa-stop-circle:before{content:"\f28d"}.fa-stopwatch:before{content:"\f2f2"}.fa-stopwatch-20:before{content:"\e06f"}.fa-store:before{content:"\f54e"}.fa-store-alt:before{content:"\f54f"}.fa-store-alt-slash:before{content:"\e070"}.fa-store-slash:before{content:"\e071"}.fa-strava:before{content:"\f428"}.fa-stream:before{content:"\f550"}.fa-street-view:before{content:"\f21d"}.fa-strikethrough:before{content:"\f0cc"}.fa-stripe:before{content:"\f429"}.fa-stripe-s:before{content:"\f42a"}.fa-stroopwafel:before{content:"\f551"}.fa-studiovinari:before{content:"\f3f8"}.fa-stumbleupon:before{content:"\f1a4"}.fa-stumbleupon-circle:before{content:"\f1a3"}.fa-subscript:before{content:"\f12c"}.fa-subway:before{content:"\f239"}.fa-suitcase:before{content:"\f0f2"}.fa-suitcase-rolling:before{content:"\f5c1"}.fa-sun:before{content:"\f185"}.fa-superpowers:before{content:"\f2dd"}.fa-superscript:before{content:"\f12b"}.fa-supple:before{content:"\f3f9"}.fa-surprise:before{content:"\f5c2"}.fa-suse:before{content:"\f7d6"}.fa-swatchbook:before{content:"\f5c3"}.fa-swift:before{content:"\f8e1"}.fa-swimmer:before{content:"\f5c4"}.fa-swimming-pool:before{content:"\f5c5"}.fa-symfony:before{content:"\f83d"}.fa-synagogue:before{content:"\f69b"}.fa-sync:before{content:"\f021"}.fa-sync-alt:before{content:"\f2f1"}.fa-syringe:before{content:"\f48e"}.fa-table:before{content:"\f0ce"}.fa-table-tennis:before{content:"\f45d"}.fa-tablet:before{content:"\f10a"}.fa-tablet-alt:before{content:"\f3fa"}.fa-tablets:before{content:"\f490"}.fa-tachometer-alt:before{content:"\f3fd"}.fa-tag:before{content:"\f02b"}.fa-tags:before{content:"\f02c"}.fa-tape:before{content:"\f4db"}.fa-tasks:before{content:"\f0ae"}.fa-taxi:before{content:"\f1ba"}.fa-teamspeak:before{content:"\f4f9"}.fa-teeth:before{content:"\f62e"}.fa-teeth-open:before{content:"\f62f"}.fa-telegram:before{content:"\f2c6"}.fa-telegram-plane:before{content:"\f3fe"}.fa-temperature-high:before{content:"\f769"}.fa-temperature-low:before{content:"\f76b"}.fa-tencent-weibo:before{content:"\f1d5"}.fa-tenge:before{content:"\f7d7"}.fa-terminal:before{content:"\f120"}.fa-text-height:before{content:"\f034"}.fa-text-width:before{content:"\f035"}.fa-th:before{content:"\f00a"}.fa-th-large:before{content:"\f009"}.fa-th-list:before{content:"\f00b"}.fa-the-red-yeti:before{content:"\f69d"}.fa-theater-masks:before{content:"\f630"}.fa-themeco:before{content:"\f5c6"}.fa-themeisle:before{content:"\f2b2"}.fa-thermometer:before{content:"\f491"}.fa-thermometer-empty:before{content:"\f2cb"}.fa-thermometer-full:before{content:"\f2c7"}.fa-thermometer-half:before{content:"\f2c9"}.fa-thermometer-quarter:before{content:"\f2ca"}.fa-thermometer-three-quarters:before{content:"\f2c8"}.fa-think-peaks:before{content:"\f731"}.fa-thumbs-down:before{content:"\f165"}.fa-thumbs-up:before{content:"\f164"}.fa-thumbtack:before{content:"\f08d"}.fa-ticket-alt:before{content:"\f3ff"}.fa-tiktok:before{content:"\e07b"}.fa-times:before{content:"\f00d"}.fa-times-circle:before{content:"\f057"}.fa-tint:before{content:"\f043"}.fa-tint-slash:before{content:"\f5c7"}.fa-tired:before{content:"\f5c8"}.fa-toggle-off:before{content:"\f204"}.fa-toggle-on:before{content:"\f205"}.fa-toilet:before{content:"\f7d8"}.fa-toilet-paper:before{content:"\f71e"}.fa-toilet-paper-slash:before{content:"\e072"}.fa-toolbox:before{content:"\f552"}.fa-tools:before{content:"\f7d9"}.fa-tooth:before{content:"\f5c9"}.fa-torah:before{content:"\f6a0"}.fa-torii-gate:before{content:"\f6a1"}.fa-tractor:before{content:"\f722"}.fa-trade-federation:before{content:"\f513"}.fa-trademark:before{content:"\f25c"}.fa-traffic-light:before{content:"\f637"}.fa-trailer:before{content:"\e041"}.fa-train:before{content:"\f238"}.fa-tram:before{content:"\f7da"}.fa-transgender:before{content:"\f224"}.fa-transgender-alt:before{content:"\f225"}.fa-trash:before{content:"\f1f8"}.fa-trash-alt:before{content:"\f2ed"}.fa-trash-restore:before{content:"\f829"}.fa-trash-restore-alt:before{content:"\f82a"}.fa-tree:before{content:"\f1bb"}.fa-trello:before{content:"\f181"}.fa-tripadvisor:before{content:"\f262"}.fa-trophy:before{content:"\f091"}.fa-truck:before{content:"\f0d1"}.fa-truck-loading:before{content:"\f4de"}.fa-truck-monster:before{content:"\f63b"}.fa-truck-moving:before{content:"\f4df"}.fa-truck-pickup:before{content:"\f63c"}.fa-tshirt:before{content:"\f553"}.fa-tty:before{content:"\f1e4"}.fa-tumblr:before{content:"\f173"}.fa-tumblr-square:before{content:"\f174"}.fa-tv:before{content:"\f26c"}.fa-twitch:before{content:"\f1e8"}.fa-twitter:before{content:"\f099"}.fa-twitter-square:before{content:"\f081"}.fa-typo3:before{content:"\f42b"}.fa-uber:before{content:"\f402"}.fa-ubuntu:before{content:"\f7df"}.fa-uikit:before{content:"\f403"}.fa-umbraco:before{content:"\f8e8"}.fa-umbrella:before{content:"\f0e9"}.fa-umbrella-beach:before{content:"\f5ca"}.fa-uncharted:before{content:"\e084"}.fa-underline:before{content:"\f0cd"}.fa-undo:before{content:"\f0e2"}.fa-undo-alt:before{content:"\f2ea"}.fa-uniregistry:before{content:"\f404"}.fa-unity:before{content:"\e049"}.fa-universal-access:before{content:"\f29a"}.fa-university:before{content:"\f19c"}.fa-unlink:before{content:"\f127"}.fa-unlock:before{content:"\f09c"}.fa-unlock-alt:before{content:"\f13e"}.fa-unsplash:before{content:"\e07c"}.fa-untappd:before{content:"\f405"}.fa-upload:before{content:"\f093"}.fa-ups:before{content:"\f7e0"}.fa-usb:before{content:"\f287"}.fa-user:before{content:"\f007"}.fa-user-alt:before{content:"\f406"}.fa-user-alt-slash:before{content:"\f4fa"}.fa-user-astronaut:before{content:"\f4fb"}.fa-user-check:before{content:"\f4fc"}.fa-user-circle:before{content:"\f2bd"}.fa-user-clock:before{content:"\f4fd"}.fa-user-cog:before{content:"\f4fe"}.fa-user-edit:before{content:"\f4ff"}.fa-user-friends:before{content:"\f500"}.fa-user-graduate:before{content:"\f501"}.fa-user-injured:before{content:"\f728"}.fa-user-lock:before{content:"\f502"}.fa-user-md:before{content:"\f0f0"}.fa-user-minus:before{content:"\f503"}.fa-user-ninja:before{content:"\f504"}.fa-user-nurse:before{content:"\f82f"}.fa-user-plus:before{content:"\f234"}.fa-user-secret:before{content:"\f21b"}.fa-user-shield:before{content:"\f505"}.fa-user-slash:before{content:"\f506"}.fa-user-tag:before{content:"\f507"}.fa-user-tie:before{content:"\f508"}.fa-user-times:before{content:"\f235"}.fa-users:before{content:"\f0c0"}.fa-users-cog:before{content:"\f509"}.fa-users-slash:before{content:"\e073"}.fa-usps:before{content:"\f7e1"}.fa-ussunnah:before{content:"\f407"}.fa-utensil-spoon:before{content:"\f2e5"}.fa-utensils:before{content:"\f2e7"}.fa-vaadin:before{content:"\f408"}.fa-vector-square:before{content:"\f5cb"}.fa-venus:before{content:"\f221"}.fa-venus-double:before{content:"\f226"}.fa-venus-mars:before{content:"\f228"}.fa-vest:before{content:"\e085"}.fa-vest-patches:before{content:"\e086"}.fa-viacoin:before{content:"\f237"}.fa-viadeo:before{content:"\f2a9"}.fa-viadeo-square:before{content:"\f2aa"}.fa-vial:before{content:"\f492"}.fa-vials:before{content:"\f493"}.fa-viber:before{content:"\f409"}.fa-video:before{content:"\f03d"}.fa-video-slash:before{content:"\f4e2"}.fa-vihara:before{content:"\f6a7"}.fa-vimeo:before{content:"\f40a"}.fa-vimeo-square:before{content:"\f194"}.fa-vimeo-v:before{content:"\f27d"}.fa-vine:before{content:"\f1ca"}.fa-virus:before{content:"\e074"}.fa-virus-slash:before{content:"\e075"}.fa-viruses:before{content:"\e076"}.fa-vk:before{content:"\f189"}.fa-vnv:before{content:"\f40b"}.fa-voicemail:before{content:"\f897"}.fa-volleyball-ball:before{content:"\f45f"}.fa-volume-down:before{content:"\f027"}.fa-volume-mute:before{content:"\f6a9"}.fa-volume-off:before{content:"\f026"}.fa-volume-up:before{content:"\f028"}.fa-vote-yea:before{content:"\f772"}.fa-vr-cardboard:before{content:"\f729"}.fa-vuejs:before{content:"\f41f"}.fa-walking:before{content:"\f554"}.fa-wallet:before{content:"\f555"}.fa-warehouse:before{content:"\f494"}.fa-watchman-monitoring:before{content:"\e087"}.fa-water:before{content:"\f773"}.fa-wave-square:before{content:"\f83e"}.fa-waze:before{content:"\f83f"}.fa-weebly:before{content:"\f5cc"}.fa-weibo:before{content:"\f18a"}.fa-weight:before{content:"\f496"}.fa-weight-hanging:before{content:"\f5cd"}.fa-weixin:before{content:"\f1d7"}.fa-whatsapp:before{content:"\f232"}.fa-whatsapp-square:before{content:"\f40c"}.fa-wheelchair:before{content:"\f193"}.fa-whmcs:before{content:"\f40d"}.fa-wifi:before{content:"\f1eb"}.fa-wikipedia-w:before{content:"\f266"}.fa-wind:before{content:"\f72e"}.fa-window-close:before{content:"\f410"}.fa-window-maximize:before{content:"\f2d0"}.fa-window-minimize:before{content:"\f2d1"}.fa-window-restore:before{content:"\f2d2"}.fa-windows:before{content:"\f17a"}.fa-wine-bottle:before{content:"\f72f"}.fa-wine-glass:before{content:"\f4e3"}.fa-wine-glass-alt:before{content:"\f5ce"}.fa-wix:before{content:"\f5cf"}.fa-wizards-of-the-coast:before{content:"\f730"}.fa-wodu:before{content:"\e088"}.fa-wolf-pack-battalion:before{content:"\f514"}.fa-won-sign:before{content:"\f159"}.fa-wordpress:before{content:"\f19a"}.fa-wordpress-simple:before{content:"\f411"}.fa-wpbeginner:before{content:"\f297"}.fa-wpexplorer:before{content:"\f2de"}.fa-wpforms:before{content:"\f298"}.fa-wpressr:before{content:"\f3e4"}.fa-wrench:before{content:"\f0ad"}.fa-x-ray:before{content:"\f497"}.fa-xbox:before{content:"\f412"}.fa-xing:before{content:"\f168"}.fa-xing-square:before{content:"\f169"}.fa-y-combinator:before{content:"\f23b"}.fa-yahoo:before{content:"\f19e"}.fa-yammer:before{content:"\f840"}.fa-yandex:before{content:"\f413"}.fa-yandex-international:before{content:"\f414"}.fa-yarn:before{content:"\f7e3"}.fa-yelp:before{content:"\f1e9"}.fa-yen-sign:before{content:"\f157"}.fa-yin-yang:before{content:"\f6ad"}.fa-yoast:before{content:"\f2b1"}.fa-youtube:before{content:"\f167"}.fa-youtube-square:before{content:"\f431"}.fa-zhihu:before{content:"\f63f"}.sr-only{border:0;clip:rect(0,0,0,0);height:1px;margin:-1px;overflow:hidden;padding:0;position:absolute;width:1px}.sr-only-focusable:active,.sr-only-focusable:focus{clip:auto;height:auto;margin:0;overflow:visible;position:static;width:auto}@font-face{font-family:"Font Awesome 5 Brands";font-style:normal;font-weight:400;font-display:block;src:url(../webfonts/fa-brands-400.eot);src:url(../webfonts/fa-brands-400.eot?#iefix) format("embedded-opentype"),url(../webfonts/fa-brands-400.woff2) format("woff2"),url(../webfonts/fa-brands-400.woff) format("woff"),url(../webfonts/fa-brands-400.ttf) format("truetype"),url(../webfonts/fa-brands-400.svg#fontawesome) format("svg")}.fab{font-family:"Font Awesome 5 Brands"}@font-face{font-family:"Font Awesome 5 Free";font-style:normal;font-weight:400;font-display:block;src:url(../webfonts/fa-regular-400.eot);src:url(../webfonts/fa-regular-400.eot?#iefix) format("embedded-opentype"),url(../webfonts/fa-regular-400.woff2) format("woff2"),url(../webfonts/fa-regular-400.woff) format("woff"),url(../webfonts/fa-regular-400.ttf) format("truetype"),url(../webfonts/fa-regular-400.svg#fontawesome) format("svg")}.fab,.far{font-weight:400}@font-face{font-family:"Font Awesome 5 Free";font-style:normal;font-weight:900;font-display:block;src:url(../webfonts/fa-solid-900.eot);src:url(../webfonts/fa-solid-900.eot?#iefix) format("embedded-opentype"),url(../webfonts/fa-solid-900.woff2) format("woff2"),url(../webfonts/fa-solid-900.woff) format("woff"),url(../webfonts/fa-solid-900.ttf) format("truetype"),url(../webfonts/fa-solid-900.svg#fontawesome) format("svg")}.fa,.far,.fas{font-family:"Font Awesome 5 Free"}.fa,.fas{font-weight:900}
diff --git a/docs/project_page/static/css/index.css b/docs/project_page/static/css/index.css
new file mode 100644
index 0000000..f56e05e
--- /dev/null
+++ b/docs/project_page/static/css/index.css
@@ -0,0 +1,128 @@
+body {
+ font-family: 'Noto Sans', sans-serif;
+}
+
+
+.footer .icon-link {
+ font-size: 25px;
+ color: #000;
+}
+
+.link-block a {
+ margin-top: 5px;
+ margin-bottom: 5px;
+}
+
+.dnerf {
+ font-variant: small-caps;
+}
+
+
+.teaser .hero-body {
+ padding-top: 0;
+ padding-bottom: 3rem;
+}
+
+.teaser {
+ font-family: 'Google Sans', sans-serif;
+}
+
+
+.publication-title {
+}
+
+.publication-banner {
+ max-height: parent;
+
+}
+
+.publication-banner video {
+ position: relative;
+ left: auto;
+ top: auto;
+ transform: none;
+ object-fit: fit;
+}
+
+.publication-header .hero-body {
+}
+
+.publication-title {
+ font-family: 'Google Sans', sans-serif;
+}
+
+.publication-authors {
+ font-family: 'Google Sans', sans-serif;
+}
+
+.publication-venue {
+ color: #555;
+ width: fit-content;
+ font-weight: bold;
+}
+
+.publication-awards {
+ color: #ff3860;
+ width: fit-content;
+ font-weight: bolder;
+}
+
+.publication-authors {
+}
+
+.publication-authors a {
+ color: hsl(204, 86%, 53%) !important;
+}
+
+.publication-authors a:hover {
+ text-decoration: underline;
+}
+
+.author-block {
+ display: inline-block;
+}
+
+.publication-banner img {
+}
+
+.publication-authors {
+ /*color: #4286f4;*/
+}
+
+.publication-video {
+ position: relative;
+ width: 100%;
+ height: 0;
+ padding-bottom: 56.25%;
+
+ overflow: hidden;
+ border-radius: 10px !important;
+}
+
+.publication-video iframe {
+ position: absolute;
+ top: 0;
+ left: 0;
+ width: 100%;
+ height: 100%;
+}
+
+.publication-body img {
+}
+
+.results-carousel {
+ overflow: hidden;
+}
+
+.results-carousel .item {
+ margin: 5px;
+ overflow: hidden;
+ border: 1px solid #bbb;
+ border-radius: 10px;
+ padding: 0;
+ font-size: 0;
+}
+
+.results-carousel video {
+ margin: 0;
+}
diff --git a/docs/project_page/static/images/benchmark.png b/docs/project_page/static/images/benchmark.png
new file mode 100644
index 0000000..2cdca96
--- /dev/null
+++ b/docs/project_page/static/images/benchmark.png
@@ -0,0 +1,3 @@
+version https://git-lfs.github.com/spec/v1
+oid sha256:ad32d1440d219afa9a65bb2ce15d2c26aa845fc7f1c11ce6b6cfb9ec7466ec8e
+size 182434
diff --git a/docs/project_page/static/images/method.png b/docs/project_page/static/images/method.png
new file mode 100644
index 0000000..60391a0
--- /dev/null
+++ b/docs/project_page/static/images/method.png
@@ -0,0 +1,3 @@
+version https://git-lfs.github.com/spec/v1
+oid sha256:ba2ea0a476d1a713b59a2b22a867b58a7d1537d1ccfc639146ef098a3bba145d
+size 5696834
diff --git a/docs/project_page/static/js/bulma-carousel.js b/docs/project_page/static/js/bulma-carousel.js
new file mode 100644
index 0000000..06e554a
--- /dev/null
+++ b/docs/project_page/static/js/bulma-carousel.js
@@ -0,0 +1,2371 @@
+(function webpackUniversalModuleDefinition(root, factory) {
+ if(typeof exports === 'object' && typeof module === 'object')
+ module.exports = factory();
+ else if(typeof define === 'function' && define.amd)
+ define([], factory);
+ else if(typeof exports === 'object')
+ exports["bulmaCarousel"] = factory();
+ else
+ root["bulmaCarousel"] = factory();
+})(typeof self !== 'undefined' ? self : this, function() {
+return /******/ (function(modules) { // webpackBootstrap
+/******/ // The module cache
+/******/ var installedModules = {};
+/******/
+/******/ // The require function
+/******/ function __webpack_require__(moduleId) {
+/******/
+/******/ // Check if module is in cache
+/******/ if(installedModules[moduleId]) {
+/******/ return installedModules[moduleId].exports;
+/******/ }
+/******/ // Create a new module (and put it into the cache)
+/******/ var module = installedModules[moduleId] = {
+/******/ i: moduleId,
+/******/ l: false,
+/******/ exports: {}
+/******/ };
+/******/
+/******/ // Execute the module function
+/******/ modules[moduleId].call(module.exports, module, module.exports, __webpack_require__);
+/******/
+/******/ // Flag the module as loaded
+/******/ module.l = true;
+/******/
+/******/ // Return the exports of the module
+/******/ return module.exports;
+/******/ }
+/******/
+/******/
+/******/ // expose the modules object (__webpack_modules__)
+/******/ __webpack_require__.m = modules;
+/******/
+/******/ // expose the module cache
+/******/ __webpack_require__.c = installedModules;
+/******/
+/******/ // define getter function for harmony exports
+/******/ __webpack_require__.d = function(exports, name, getter) {
+/******/ if(!__webpack_require__.o(exports, name)) {
+/******/ Object.defineProperty(exports, name, {
+/******/ configurable: false,
+/******/ enumerable: true,
+/******/ get: getter
+/******/ });
+/******/ }
+/******/ };
+/******/
+/******/ // getDefaultExport function for compatibility with non-harmony modules
+/******/ __webpack_require__.n = function(module) {
+/******/ var getter = module && module.__esModule ?
+/******/ function getDefault() { return module['default']; } :
+/******/ function getModuleExports() { return module; };
+/******/ __webpack_require__.d(getter, 'a', getter);
+/******/ return getter;
+/******/ };
+/******/
+/******/ // Object.prototype.hasOwnProperty.call
+/******/ __webpack_require__.o = function(object, property) { return Object.prototype.hasOwnProperty.call(object, property); };
+/******/
+/******/ // __webpack_public_path__
+/******/ __webpack_require__.p = "";
+/******/
+/******/ // Load entry module and return exports
+/******/ return __webpack_require__(__webpack_require__.s = 5);
+/******/ })
+/************************************************************************/
+/******/ ([
+/* 0 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* unused harmony export addClasses */
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "d", function() { return removeClasses; });
+/* unused harmony export show */
+/* unused harmony export hide */
+/* unused harmony export offset */
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "e", function() { return width; });
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "b", function() { return height; });
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "c", function() { return outerHeight; });
+/* unused harmony export outerWidth */
+/* unused harmony export position */
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "a", function() { return css; });
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__type__ = __webpack_require__(2);
+
+
+var addClasses = function addClasses(element, classes) {
+ classes = Array.isArray(classes) ? classes : classes.split(' ');
+ classes.forEach(function (cls) {
+ element.classList.add(cls);
+ });
+};
+
+var removeClasses = function removeClasses(element, classes) {
+ classes = Array.isArray(classes) ? classes : classes.split(' ');
+ classes.forEach(function (cls) {
+ element.classList.remove(cls);
+ });
+};
+
+var show = function show(elements) {
+ elements = Array.isArray(elements) ? elements : [elements];
+ elements.forEach(function (element) {
+ element.style.display = '';
+ });
+};
+
+var hide = function hide(elements) {
+ elements = Array.isArray(elements) ? elements : [elements];
+ elements.forEach(function (element) {
+ element.style.display = 'none';
+ });
+};
+
+var offset = function offset(element) {
+ var rect = element.getBoundingClientRect();
+ return {
+ top: rect.top + document.body.scrollTop,
+ left: rect.left + document.body.scrollLeft
+ };
+};
+
+// returns an element's width
+var width = function width(element) {
+ return element.getBoundingClientRect().width || element.offsetWidth;
+};
+// returns an element's height
+var height = function height(element) {
+ return element.getBoundingClientRect().height || element.offsetHeight;
+};
+
+var outerHeight = function outerHeight(element) {
+ var withMargin = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : false;
+
+ var height = element.offsetHeight;
+ if (withMargin) {
+ var style = window.getComputedStyle(element);
+ height += parseInt(style.marginTop) + parseInt(style.marginBottom);
+ }
+ return height;
+};
+
+var outerWidth = function outerWidth(element) {
+ var withMargin = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : false;
+
+ var width = element.offsetWidth;
+ if (withMargin) {
+ var style = window.getComputedStyle(element);
+ width += parseInt(style.marginLeft) + parseInt(style.marginRight);
+ }
+ return width;
+};
+
+var position = function position(element) {
+ return {
+ left: element.offsetLeft,
+ top: element.offsetTop
+ };
+};
+
+var css = function css(element, obj) {
+ if (!obj) {
+ return window.getComputedStyle(element);
+ }
+ if (Object(__WEBPACK_IMPORTED_MODULE_0__type__["b" /* isObject */])(obj)) {
+ var style = '';
+ Object.keys(obj).forEach(function (key) {
+ style += key + ': ' + obj[key] + ';';
+ });
+
+ element.style.cssText += style;
+ }
+};
+
+/***/ }),
+/* 1 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony export (immutable) */ __webpack_exports__["a"] = detectSupportsPassive;
+function detectSupportsPassive() {
+ var supportsPassive = false;
+
+ try {
+ var opts = Object.defineProperty({}, 'passive', {
+ get: function get() {
+ supportsPassive = true;
+ }
+ });
+
+ window.addEventListener('testPassive', null, opts);
+ window.removeEventListener('testPassive', null, opts);
+ } catch (e) {}
+
+ return supportsPassive;
+}
+
+/***/ }),
+/* 2 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "a", function() { return isFunction; });
+/* unused harmony export isNumber */
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "c", function() { return isString; });
+/* unused harmony export isDate */
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "b", function() { return isObject; });
+/* unused harmony export isEmptyObject */
+/* unused harmony export isNode */
+/* unused harmony export isVideo */
+/* unused harmony export isHTML5 */
+/* unused harmony export isIFrame */
+/* unused harmony export isYoutube */
+/* unused harmony export isVimeo */
+var _typeof = typeof Symbol === "function" && typeof Symbol.iterator === "symbol" ? function (obj) { return typeof obj; } : function (obj) { return obj && typeof Symbol === "function" && obj.constructor === Symbol && obj !== Symbol.prototype ? "symbol" : typeof obj; };
+
+var isFunction = function isFunction(unknown) {
+ return typeof unknown === 'function';
+};
+var isNumber = function isNumber(unknown) {
+ return typeof unknown === "number";
+};
+var isString = function isString(unknown) {
+ return typeof unknown === 'string' || !!unknown && (typeof unknown === 'undefined' ? 'undefined' : _typeof(unknown)) === 'object' && Object.prototype.toString.call(unknown) === '[object String]';
+};
+var isDate = function isDate(unknown) {
+ return (Object.prototype.toString.call(unknown) === '[object Date]' || unknown instanceof Date) && !isNaN(unknown.valueOf());
+};
+var isObject = function isObject(unknown) {
+ return (typeof unknown === 'function' || (typeof unknown === 'undefined' ? 'undefined' : _typeof(unknown)) === 'object' && !!unknown) && !Array.isArray(unknown);
+};
+var isEmptyObject = function isEmptyObject(unknown) {
+ for (var name in unknown) {
+ if (unknown.hasOwnProperty(name)) {
+ return false;
+ }
+ }
+ return true;
+};
+
+var isNode = function isNode(unknown) {
+ return !!(unknown && unknown.nodeType === HTMLElement | SVGElement);
+};
+var isVideo = function isVideo(unknown) {
+ return isYoutube(unknown) || isVimeo(unknown) || isHTML5(unknown);
+};
+var isHTML5 = function isHTML5(unknown) {
+ return isNode(unknown) && unknown.tagName === 'VIDEO';
+};
+var isIFrame = function isIFrame(unknown) {
+ return isNode(unknown) && unknown.tagName === 'IFRAME';
+};
+var isYoutube = function isYoutube(unknown) {
+ return isIFrame(unknown) && !!unknown.src.match(/\/\/.*?youtube(-nocookie)?\.[a-z]+\/(watch\?v=[^&\s]+|embed)|youtu\.be\/.*/);
+};
+var isVimeo = function isVimeo(unknown) {
+ return isIFrame(unknown) && !!unknown.src.match(/vimeo\.com\/video\/.*/);
+};
+
+/***/ }),
+/* 3 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _toConsumableArray(arr) { if (Array.isArray(arr)) { for (var i = 0, arr2 = Array(arr.length); i < arr.length; i++) { arr2[i] = arr[i]; } return arr2; } else { return Array.from(arr); } }
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+var EventEmitter = function () {
+ function EventEmitter() {
+ var events = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : [];
+
+ _classCallCheck(this, EventEmitter);
+
+ this.events = new Map(events);
+ }
+
+ _createClass(EventEmitter, [{
+ key: "on",
+ value: function on(name, cb) {
+ var _this = this;
+
+ this.events.set(name, [].concat(_toConsumableArray(this.events.has(name) ? this.events.get(name) : []), [cb]));
+
+ return function () {
+ return _this.events.set(name, _this.events.get(name).filter(function (fn) {
+ return fn !== cb;
+ }));
+ };
+ }
+ }, {
+ key: "emit",
+ value: function emit(name) {
+ for (var _len = arguments.length, args = Array(_len > 1 ? _len - 1 : 0), _key = 1; _key < _len; _key++) {
+ args[_key - 1] = arguments[_key];
+ }
+
+ return this.events.has(name) && this.events.get(name).map(function (fn) {
+ return fn.apply(undefined, args);
+ });
+ }
+ }]);
+
+ return EventEmitter;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (EventEmitter);
+
+/***/ }),
+/* 4 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+var Coordinate = function () {
+ function Coordinate() {
+ var x = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : 0;
+ var y = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : 0;
+
+ _classCallCheck(this, Coordinate);
+
+ this._x = x;
+ this._y = y;
+ }
+
+ _createClass(Coordinate, [{
+ key: 'add',
+ value: function add(coord) {
+ return new Coordinate(this._x + coord._x, this._y + coord._y);
+ }
+ }, {
+ key: 'sub',
+ value: function sub(coord) {
+ return new Coordinate(this._x - coord._x, this._y - coord._y);
+ }
+ }, {
+ key: 'distance',
+ value: function distance(coord) {
+ var deltaX = this._x - coord._x;
+ var deltaY = this._y - coord._y;
+
+ return Math.sqrt(Math.pow(deltaX, 2) + Math.pow(deltaY, 2));
+ }
+ }, {
+ key: 'max',
+ value: function max(coord) {
+ var x = Math.max(this._x, coord._x);
+ var y = Math.max(this._y, coord._y);
+
+ return new Coordinate(x, y);
+ }
+ }, {
+ key: 'equals',
+ value: function equals(coord) {
+ if (this == coord) {
+ return true;
+ }
+ if (!coord || coord == null) {
+ return false;
+ }
+ return this._x == coord._x && this._y == coord._y;
+ }
+ }, {
+ key: 'inside',
+ value: function inside(northwest, southeast) {
+ if (this._x >= northwest._x && this._x <= southeast._x && this._y >= northwest._y && this._y <= southeast._y) {
+
+ return true;
+ }
+ return false;
+ }
+ }, {
+ key: 'constrain',
+ value: function constrain(min, max) {
+ if (min._x > max._x || min._y > max._y) {
+ return this;
+ }
+
+ var x = this._x,
+ y = this._y;
+
+ if (min._x !== null) {
+ x = Math.max(x, min._x);
+ }
+ if (max._x !== null) {
+ x = Math.min(x, max._x);
+ }
+ if (min._y !== null) {
+ y = Math.max(y, min._y);
+ }
+ if (max._y !== null) {
+ y = Math.min(y, max._y);
+ }
+
+ return new Coordinate(x, y);
+ }
+ }, {
+ key: 'reposition',
+ value: function reposition(element) {
+ element.style['top'] = this._y + 'px';
+ element.style['left'] = this._x + 'px';
+ }
+ }, {
+ key: 'toString',
+ value: function toString() {
+ return '(' + this._x + ',' + this._y + ')';
+ }
+ }, {
+ key: 'x',
+ get: function get() {
+ return this._x;
+ },
+ set: function set() {
+ var value = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : 0;
+
+ this._x = value;
+ return this;
+ }
+ }, {
+ key: 'y',
+ get: function get() {
+ return this._y;
+ },
+ set: function set() {
+ var value = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : 0;
+
+ this._y = value;
+ return this;
+ }
+ }]);
+
+ return Coordinate;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (Coordinate);
+
+/***/ }),
+/* 5 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+Object.defineProperty(__webpack_exports__, "__esModule", { value: true });
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__utils_index__ = __webpack_require__(6);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_1__utils_css__ = __webpack_require__(0);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_2__utils_type__ = __webpack_require__(2);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_3__utils_eventEmitter__ = __webpack_require__(3);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_4__components_autoplay__ = __webpack_require__(7);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_5__components_breakpoint__ = __webpack_require__(9);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_6__components_infinite__ = __webpack_require__(10);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_7__components_loop__ = __webpack_require__(11);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_8__components_navigation__ = __webpack_require__(13);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_9__components_pagination__ = __webpack_require__(15);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_10__components_swipe__ = __webpack_require__(18);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_11__components_transitioner__ = __webpack_require__(19);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_12__defaultOptions__ = __webpack_require__(22);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_13__templates__ = __webpack_require__(23);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_14__templates_item__ = __webpack_require__(24);
+var _extends = Object.assign || function (target) { for (var i = 1; i < arguments.length; i++) { var source = arguments[i]; for (var key in source) { if (Object.prototype.hasOwnProperty.call(source, key)) { target[key] = source[key]; } } } return target; };
+
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _defineProperty(obj, key, value) { if (key in obj) { Object.defineProperty(obj, key, { value: value, enumerable: true, configurable: true, writable: true }); } else { obj[key] = value; } return obj; }
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+function _possibleConstructorReturn(self, call) { if (!self) { throw new ReferenceError("this hasn't been initialised - super() hasn't been called"); } return call && (typeof call === "object" || typeof call === "function") ? call : self; }
+
+function _inherits(subClass, superClass) { if (typeof superClass !== "function" && superClass !== null) { throw new TypeError("Super expression must either be null or a function, not " + typeof superClass); } subClass.prototype = Object.create(superClass && superClass.prototype, { constructor: { value: subClass, enumerable: false, writable: true, configurable: true } }); if (superClass) Object.setPrototypeOf ? Object.setPrototypeOf(subClass, superClass) : subClass.__proto__ = superClass; }
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+var bulmaCarousel = function (_EventEmitter) {
+ _inherits(bulmaCarousel, _EventEmitter);
+
+ function bulmaCarousel(selector) {
+ var options = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};
+
+ _classCallCheck(this, bulmaCarousel);
+
+ var _this = _possibleConstructorReturn(this, (bulmaCarousel.__proto__ || Object.getPrototypeOf(bulmaCarousel)).call(this));
+
+ _this.element = Object(__WEBPACK_IMPORTED_MODULE_2__utils_type__["c" /* isString */])(selector) ? document.querySelector(selector) : selector;
+ // An invalid selector or non-DOM node has been provided.
+ if (!_this.element) {
+ throw new Error('An invalid selector or non-DOM node has been provided.');
+ }
+ _this._clickEvents = ['click', 'touch'];
+
+ // Use Element dataset values to override options
+ var elementConfig = _this.element.dataset ? Object.keys(_this.element.dataset).filter(function (key) {
+ return Object.keys(__WEBPACK_IMPORTED_MODULE_12__defaultOptions__["a" /* default */]).includes(key);
+ }).reduce(function (obj, key) {
+ return _extends({}, obj, _defineProperty({}, key, _this.element.dataset[key]));
+ }, {}) : {};
+ // Set default options - dataset attributes are master
+ _this.options = _extends({}, __WEBPACK_IMPORTED_MODULE_12__defaultOptions__["a" /* default */], options, elementConfig);
+
+ _this._id = Object(__WEBPACK_IMPORTED_MODULE_0__utils_index__["a" /* uuid */])('slider');
+
+ _this.onShow = _this.onShow.bind(_this);
+
+ // Initiate plugin
+ _this._init();
+ return _this;
+ }
+
+ /**
+ * Initiate all DOM element containing datePicker class
+ * @method
+ * @return {Array} Array of all datePicker instances
+ */
+
+
+ _createClass(bulmaCarousel, [{
+ key: '_init',
+
+
+ /****************************************************
+ * *
+ * PRIVATE FUNCTIONS *
+ * *
+ ****************************************************/
+ /**
+ * Initiate plugin instance
+ * @method _init
+ * @return {Slider} Current plugin instance
+ */
+ value: function _init() {
+ this._items = Array.from(this.element.children);
+
+ // Load plugins
+ this._breakpoint = new __WEBPACK_IMPORTED_MODULE_5__components_breakpoint__["a" /* default */](this);
+ this._autoplay = new __WEBPACK_IMPORTED_MODULE_4__components_autoplay__["a" /* default */](this);
+ this._navigation = new __WEBPACK_IMPORTED_MODULE_8__components_navigation__["a" /* default */](this);
+ this._pagination = new __WEBPACK_IMPORTED_MODULE_9__components_pagination__["a" /* default */](this);
+ this._infinite = new __WEBPACK_IMPORTED_MODULE_6__components_infinite__["a" /* default */](this);
+ this._loop = new __WEBPACK_IMPORTED_MODULE_7__components_loop__["a" /* default */](this);
+ this._swipe = new __WEBPACK_IMPORTED_MODULE_10__components_swipe__["a" /* default */](this);
+
+ this._build();
+
+ if (Object(__WEBPACK_IMPORTED_MODULE_2__utils_type__["a" /* isFunction */])(this.options.onReady)) {
+ this.options.onReady(this);
+ }
+
+ return this;
+ }
+
+ /**
+ * Build Slider HTML component and append it to the DOM
+ * @method _build
+ */
+
+ }, {
+ key: '_build',
+ value: function _build() {
+ var _this2 = this;
+
+ // Generate HTML Fragment of template
+ this.node = document.createRange().createContextualFragment(Object(__WEBPACK_IMPORTED_MODULE_13__templates__["a" /* default */])(this.id));
+ // Save pointers to template parts
+ this._ui = {
+ wrapper: this.node.firstChild,
+ container: this.node.querySelector('.slider-container')
+
+ // Add slider to DOM
+ };this.element.appendChild(this.node);
+ this._ui.wrapper.classList.add('is-loading');
+ this._ui.container.style.opacity = 0;
+
+ this._transitioner = new __WEBPACK_IMPORTED_MODULE_11__components_transitioner__["a" /* default */](this);
+
+ // Wrap all items by slide element
+ this._slides = this._items.map(function (item, index) {
+ return _this2._createSlide(item, index);
+ });
+
+ this.reset();
+
+ this._bindEvents();
+
+ this._ui.container.style.opacity = 1;
+ this._ui.wrapper.classList.remove('is-loading');
+ }
+
+ /**
+ * Bind all events
+ * @method _bindEvents
+ * @return {void}
+ */
+
+ }, {
+ key: '_bindEvents',
+ value: function _bindEvents() {
+ this.on('show', this.onShow);
+ }
+ }, {
+ key: '_unbindEvents',
+ value: function _unbindEvents() {
+ this.off('show', this.onShow);
+ }
+ }, {
+ key: '_createSlide',
+ value: function _createSlide(item, index) {
+ var slide = document.createRange().createContextualFragment(Object(__WEBPACK_IMPORTED_MODULE_14__templates_item__["a" /* default */])()).firstChild;
+ slide.dataset.sliderIndex = index;
+ slide.appendChild(item);
+ return slide;
+ }
+
+ /**
+ * Calculate slider dimensions
+ */
+
+ }, {
+ key: '_setDimensions',
+ value: function _setDimensions() {
+ var _this3 = this;
+
+ if (!this.options.vertical) {
+ if (this.options.centerMode) {
+ this._ui.wrapper.style.padding = '0px ' + this.options.centerPadding;
+ }
+ } else {
+ this._ui.wrapper.style.height = Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["c" /* outerHeight */])(this._slides[0]) * this.slidesToShow;
+ if (this.options.centerMode) {
+ this._ui.wrapper.style.padding = this.options.centerPadding + ' 0px';
+ }
+ }
+
+ this._wrapperWidth = Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["e" /* width */])(this._ui.wrapper);
+ this._wrapperHeight = Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["c" /* outerHeight */])(this._ui.wrapper);
+
+ if (!this.options.vertical) {
+ this._slideWidth = Math.ceil(this._wrapperWidth / this.slidesToShow);
+ this._containerWidth = Math.ceil(this._slideWidth * this._slides.length);
+ this._ui.container.style.width = this._containerWidth + 'px';
+ } else {
+ this._slideWidth = Math.ceil(this._wrapperWidth);
+ this._containerHeight = Math.ceil(Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["c" /* outerHeight */])(this._slides[0]) * this._slides.length);
+ this._ui.container.style.height = this._containerHeight + 'px';
+ }
+
+ this._slides.forEach(function (slide) {
+ slide.style.width = _this3._slideWidth + 'px';
+ });
+ }
+ }, {
+ key: '_setHeight',
+ value: function _setHeight() {
+ if (this.options.effect !== 'translate') {
+ this._ui.container.style.height = Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["c" /* outerHeight */])(this._slides[this.state.index]) + 'px';
+ }
+ }
+
+ // Update slides classes
+
+ }, {
+ key: '_setClasses',
+ value: function _setClasses() {
+ var _this4 = this;
+
+ this._slides.forEach(function (slide) {
+ Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["d" /* removeClasses */])(slide, 'is-active is-current is-slide-previous is-slide-next');
+ if (Math.abs((_this4.state.index - 1) % _this4.state.length) === parseInt(slide.dataset.sliderIndex, 10)) {
+ slide.classList.add('is-slide-previous');
+ }
+ if (Math.abs(_this4.state.index % _this4.state.length) === parseInt(slide.dataset.sliderIndex, 10)) {
+ slide.classList.add('is-current');
+ }
+ if (Math.abs((_this4.state.index + 1) % _this4.state.length) === parseInt(slide.dataset.sliderIndex, 10)) {
+ slide.classList.add('is-slide-next');
+ }
+ });
+ }
+
+ /****************************************************
+ * *
+ * GETTERS and SETTERS *
+ * *
+ ****************************************************/
+
+ /**
+ * Get id of current datePicker
+ */
+
+ }, {
+ key: 'onShow',
+
+
+ /****************************************************
+ * *
+ * EVENTS FUNCTIONS *
+ * *
+ ****************************************************/
+ value: function onShow(e) {
+ this._navigation.refresh();
+ this._pagination.refresh();
+ this._setClasses();
+ }
+
+ /****************************************************
+ * *
+ * PUBLIC FUNCTIONS *
+ * *
+ ****************************************************/
+
+ }, {
+ key: 'next',
+ value: function next() {
+ if (!this.options.loop && !this.options.infinite && this.state.index + this.slidesToScroll > this.state.length - this.slidesToShow && !this.options.centerMode) {
+ this.state.next = this.state.index;
+ } else {
+ this.state.next = this.state.index + this.slidesToScroll;
+ }
+ this.show();
+ }
+ }, {
+ key: 'previous',
+ value: function previous() {
+ if (!this.options.loop && !this.options.infinite && this.state.index === 0) {
+ this.state.next = this.state.index;
+ } else {
+ this.state.next = this.state.index - this.slidesToScroll;
+ }
+ this.show();
+ }
+ }, {
+ key: 'start',
+ value: function start() {
+ this._autoplay.start();
+ }
+ }, {
+ key: 'pause',
+ value: function pause() {
+ this._autoplay.pause();
+ }
+ }, {
+ key: 'stop',
+ value: function stop() {
+ this._autoplay.stop();
+ }
+ }, {
+ key: 'show',
+ value: function show(index) {
+ var force = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : false;
+
+ // If all slides are already visible then return
+ if (!this.state.length || this.state.length <= this.slidesToShow) {
+ return;
+ }
+
+ if (typeof index === 'Number') {
+ this.state.next = index;
+ }
+
+ if (this.options.loop) {
+ this._loop.apply();
+ }
+ if (this.options.infinite) {
+ this._infinite.apply();
+ }
+
+ // If new slide is already the current one then return
+ if (this.state.index === this.state.next) {
+ return;
+ }
+
+ this.emit('before:show', this.state);
+ this._transitioner.apply(force, this._setHeight.bind(this));
+ this.emit('after:show', this.state);
+
+ this.emit('show', this);
+ }
+ }, {
+ key: 'reset',
+ value: function reset() {
+ var _this5 = this;
+
+ this.state = {
+ length: this._items.length,
+ index: Math.abs(this.options.initialSlide),
+ next: Math.abs(this.options.initialSlide),
+ prev: undefined
+ };
+
+ // Fix options
+ if (this.options.loop && this.options.infinite) {
+ this.options.loop = false;
+ }
+ if (this.options.slidesToScroll > this.options.slidesToShow) {
+ this.options.slidesToScroll = this.slidesToShow;
+ }
+ this._breakpoint.init();
+
+ if (this.state.index >= this.state.length && this.state.index !== 0) {
+ this.state.index = this.state.index - this.slidesToScroll;
+ }
+ if (this.state.length <= this.slidesToShow) {
+ this.state.index = 0;
+ }
+
+ this._ui.wrapper.appendChild(this._navigation.init().render());
+ this._ui.wrapper.appendChild(this._pagination.init().render());
+
+ if (this.options.navigationSwipe) {
+ this._swipe.bindEvents();
+ } else {
+ this._swipe._bindEvents();
+ }
+
+ this._breakpoint.apply();
+ // Move all created slides into slider
+ this._slides.forEach(function (slide) {
+ return _this5._ui.container.appendChild(slide);
+ });
+ this._transitioner.init().apply(true, this._setHeight.bind(this));
+
+ if (this.options.autoplay) {
+ this._autoplay.init().start();
+ }
+ }
+
+ /**
+ * Destroy Slider
+ * @method destroy
+ */
+
+ }, {
+ key: 'destroy',
+ value: function destroy() {
+ var _this6 = this;
+
+ this._unbindEvents();
+ this._items.forEach(function (item) {
+ _this6.element.appendChild(item);
+ });
+ this.node.remove();
+ }
+ }, {
+ key: 'id',
+ get: function get() {
+ return this._id;
+ }
+ }, {
+ key: 'index',
+ set: function set(index) {
+ this._index = index;
+ },
+ get: function get() {
+ return this._index;
+ }
+ }, {
+ key: 'length',
+ set: function set(length) {
+ this._length = length;
+ },
+ get: function get() {
+ return this._length;
+ }
+ }, {
+ key: 'slides',
+ get: function get() {
+ return this._slides;
+ },
+ set: function set(slides) {
+ this._slides = slides;
+ }
+ }, {
+ key: 'slidesToScroll',
+ get: function get() {
+ return this.options.effect === 'translate' ? this._breakpoint.getSlidesToScroll() : 1;
+ }
+ }, {
+ key: 'slidesToShow',
+ get: function get() {
+ return this.options.effect === 'translate' ? this._breakpoint.getSlidesToShow() : 1;
+ }
+ }, {
+ key: 'direction',
+ get: function get() {
+ return this.element.dir.toLowerCase() === 'rtl' || this.element.style.direction === 'rtl' ? 'rtl' : 'ltr';
+ }
+ }, {
+ key: 'wrapper',
+ get: function get() {
+ return this._ui.wrapper;
+ }
+ }, {
+ key: 'wrapperWidth',
+ get: function get() {
+ return this._wrapperWidth || 0;
+ }
+ }, {
+ key: 'container',
+ get: function get() {
+ return this._ui.container;
+ }
+ }, {
+ key: 'containerWidth',
+ get: function get() {
+ return this._containerWidth || 0;
+ }
+ }, {
+ key: 'slideWidth',
+ get: function get() {
+ return this._slideWidth || 0;
+ }
+ }, {
+ key: 'transitioner',
+ get: function get() {
+ return this._transitioner;
+ }
+ }], [{
+ key: 'attach',
+ value: function attach() {
+ var _this7 = this;
+
+ var selector = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : '.slider';
+ var options = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};
+
+ var instances = new Array();
+
+ var elements = Object(__WEBPACK_IMPORTED_MODULE_2__utils_type__["c" /* isString */])(selector) ? document.querySelectorAll(selector) : Array.isArray(selector) ? selector : [selector];
+ [].forEach.call(elements, function (element) {
+ if (typeof element[_this7.constructor.name] === 'undefined') {
+ var instance = new bulmaCarousel(element, options);
+ element[_this7.constructor.name] = instance;
+ instances.push(instance);
+ } else {
+ instances.push(element[_this7.constructor.name]);
+ }
+ });
+
+ return instances;
+ }
+ }]);
+
+ return bulmaCarousel;
+}(__WEBPACK_IMPORTED_MODULE_3__utils_eventEmitter__["a" /* default */]);
+
+/* harmony default export */ __webpack_exports__["default"] = (bulmaCarousel);
+
+/***/ }),
+/* 6 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "a", function() { return uuid; });
+/* unused harmony export isRtl */
+/* unused harmony export defer */
+/* unused harmony export getNodeIndex */
+/* unused harmony export camelize */
+function _toConsumableArray(arr) { if (Array.isArray(arr)) { for (var i = 0, arr2 = Array(arr.length); i < arr.length; i++) { arr2[i] = arr[i]; } return arr2; } else { return Array.from(arr); } }
+
+var uuid = function uuid() {
+ var prefix = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : '';
+ return prefix + ([1e7] + -1e3 + -4e3 + -8e3 + -1e11).replace(/[018]/g, function (c) {
+ return (c ^ crypto.getRandomValues(new Uint8Array(1))[0] & 15 >> c / 4).toString(16);
+ });
+};
+var isRtl = function isRtl() {
+ return document.documentElement.getAttribute('dir') === 'rtl';
+};
+
+var defer = function defer() {
+ this.promise = new Promise(function (resolve, reject) {
+ this.resolve = resolve;
+ this.reject = reject;
+ }.bind(this));
+
+ this.then = this.promise.then.bind(this.promise);
+ this.catch = this.promise.catch.bind(this.promise);
+};
+
+var getNodeIndex = function getNodeIndex(node) {
+ return [].concat(_toConsumableArray(node.parentNode.children)).indexOf(node);
+};
+var camelize = function camelize(str) {
+ return str.replace(/-(\w)/g, toUpper);
+};
+
+/***/ }),
+/* 7 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__utils_eventEmitter__ = __webpack_require__(3);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_1__utils_device__ = __webpack_require__(8);
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+function _possibleConstructorReturn(self, call) { if (!self) { throw new ReferenceError("this hasn't been initialised - super() hasn't been called"); } return call && (typeof call === "object" || typeof call === "function") ? call : self; }
+
+function _inherits(subClass, superClass) { if (typeof superClass !== "function" && superClass !== null) { throw new TypeError("Super expression must either be null or a function, not " + typeof superClass); } subClass.prototype = Object.create(superClass && superClass.prototype, { constructor: { value: subClass, enumerable: false, writable: true, configurable: true } }); if (superClass) Object.setPrototypeOf ? Object.setPrototypeOf(subClass, superClass) : subClass.__proto__ = superClass; }
+
+
+
+
+var onVisibilityChange = Symbol('onVisibilityChange');
+var onMouseEnter = Symbol('onMouseEnter');
+var onMouseLeave = Symbol('onMouseLeave');
+
+var defaultOptions = {
+ autoplay: false,
+ autoplaySpeed: 3000
+};
+
+var Autoplay = function (_EventEmitter) {
+ _inherits(Autoplay, _EventEmitter);
+
+ function Autoplay(slider) {
+ _classCallCheck(this, Autoplay);
+
+ var _this = _possibleConstructorReturn(this, (Autoplay.__proto__ || Object.getPrototypeOf(Autoplay)).call(this));
+
+ _this.slider = slider;
+
+ _this.onVisibilityChange = _this.onVisibilityChange.bind(_this);
+ _this.onMouseEnter = _this.onMouseEnter.bind(_this);
+ _this.onMouseLeave = _this.onMouseLeave.bind(_this);
+ return _this;
+ }
+
+ _createClass(Autoplay, [{
+ key: 'init',
+ value: function init() {
+ this._bindEvents();
+ return this;
+ }
+ }, {
+ key: '_bindEvents',
+ value: function _bindEvents() {
+ document.addEventListener('visibilitychange', this.onVisibilityChange);
+ if (this.slider.options.pauseOnHover) {
+ this.slider.container.addEventListener(__WEBPACK_IMPORTED_MODULE_1__utils_device__["a" /* pointerEnter */], this.onMouseEnter);
+ this.slider.container.addEventListener(__WEBPACK_IMPORTED_MODULE_1__utils_device__["b" /* pointerLeave */], this.onMouseLeave);
+ }
+ }
+ }, {
+ key: '_unbindEvents',
+ value: function _unbindEvents() {
+ document.removeEventListener('visibilitychange', this.onVisibilityChange);
+ this.slider.container.removeEventListener(__WEBPACK_IMPORTED_MODULE_1__utils_device__["a" /* pointerEnter */], this.onMouseEnter);
+ this.slider.container.removeEventListener(__WEBPACK_IMPORTED_MODULE_1__utils_device__["b" /* pointerLeave */], this.onMouseLeave);
+ }
+ }, {
+ key: 'start',
+ value: function start() {
+ var _this2 = this;
+
+ this.stop();
+ if (this.slider.options.autoplay) {
+ this.emit('start', this);
+ this._interval = setInterval(function () {
+ if (!(_this2._hovering && _this2.slider.options.pauseOnHover)) {
+ if (!_this2.slider.options.centerMode && _this2.slider.state.next >= _this2.slider.state.length - _this2.slider.slidesToShow && !_this2.slider.options.loop && !_this2.slider.options.infinite) {
+ _this2.stop();
+ } else {
+ _this2.slider.next();
+ }
+ }
+ }, this.slider.options.autoplaySpeed);
+ }
+ }
+ }, {
+ key: 'stop',
+ value: function stop() {
+ this._interval = clearInterval(this._interval);
+ this.emit('stop', this);
+ }
+ }, {
+ key: 'pause',
+ value: function pause() {
+ var _this3 = this;
+
+ var speed = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : 0;
+
+ if (this.paused) {
+ return;
+ }
+ if (this.timer) {
+ this.stop();
+ }
+ this.paused = true;
+ if (speed === 0) {
+ this.paused = false;
+ this.start();
+ } else {
+ this.slider.on('transition:end', function () {
+ if (!_this3) {
+ return;
+ }
+ _this3.paused = false;
+ if (!_this3.run) {
+ _this3.stop();
+ } else {
+ _this3.start();
+ }
+ });
+ }
+ }
+ }, {
+ key: 'onVisibilityChange',
+ value: function onVisibilityChange(e) {
+ if (document.hidden) {
+ this.stop();
+ } else {
+ this.start();
+ }
+ }
+ }, {
+ key: 'onMouseEnter',
+ value: function onMouseEnter(e) {
+ this._hovering = true;
+ if (this.slider.options.pauseOnHover) {
+ this.pause();
+ }
+ }
+ }, {
+ key: 'onMouseLeave',
+ value: function onMouseLeave(e) {
+ this._hovering = false;
+ if (this.slider.options.pauseOnHover) {
+ this.pause();
+ }
+ }
+ }]);
+
+ return Autoplay;
+}(__WEBPACK_IMPORTED_MODULE_0__utils_eventEmitter__["a" /* default */]);
+
+/* harmony default export */ __webpack_exports__["a"] = (Autoplay);
+
+/***/ }),
+/* 8 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* unused harmony export isIE */
+/* unused harmony export isIETouch */
+/* unused harmony export isAndroid */
+/* unused harmony export isiPad */
+/* unused harmony export isiPod */
+/* unused harmony export isiPhone */
+/* unused harmony export isSafari */
+/* unused harmony export isUiWebView */
+/* unused harmony export supportsTouchEvents */
+/* unused harmony export supportsPointerEvents */
+/* unused harmony export supportsTouch */
+/* unused harmony export pointerDown */
+/* unused harmony export pointerMove */
+/* unused harmony export pointerUp */
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "a", function() { return pointerEnter; });
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "b", function() { return pointerLeave; });
+var isIE = window.navigator.pointerEnabled || window.navigator.msPointerEnabled;
+var isIETouch = window.navigator.msPointerEnabled && window.navigator.msMaxTouchPoints > 1 || window.navigator.pointerEnabled && window.navigator.maxTouchPoints > 1;
+var isAndroid = navigator.userAgent.match(/(Android);?[\s\/]+([\d.]+)?/);
+var isiPad = navigator.userAgent.match(/(iPad).*OS\s([\d_]+)/);
+var isiPod = navigator.userAgent.match(/(iPod)(.*OS\s([\d_]+))?/);
+var isiPhone = !navigator.userAgent.match(/(iPad).*OS\s([\d_]+)/) && navigator.userAgent.match(/(iPhone\sOS)\s([\d_]+)/);
+var isSafari = navigator.userAgent.toLowerCase().indexOf('safari') >= 0 && navigator.userAgent.toLowerCase().indexOf('chrome') < 0 && navigator.userAgent.toLowerCase().indexOf('android') < 0;
+var isUiWebView = /(iPhone|iPod|iPad).*AppleWebKit(?!.*Safari)/i.test(navigator.userAgent);
+
+var supportsTouchEvents = !!('ontouchstart' in window);
+var supportsPointerEvents = !!('PointerEvent' in window);
+var supportsTouch = supportsTouchEvents || window.DocumentTouch && document instanceof DocumentTouch || navigator.maxTouchPoints; // IE >=11
+var pointerDown = !supportsTouch ? 'mousedown' : 'mousedown ' + (supportsTouchEvents ? 'touchstart' : 'pointerdown');
+var pointerMove = !supportsTouch ? 'mousemove' : 'mousemove ' + (supportsTouchEvents ? 'touchmove' : 'pointermove');
+var pointerUp = !supportsTouch ? 'mouseup' : 'mouseup ' + (supportsTouchEvents ? 'touchend' : 'pointerup');
+var pointerEnter = supportsTouch && supportsPointerEvents ? 'pointerenter' : 'mouseenter';
+var pointerLeave = supportsTouch && supportsPointerEvents ? 'pointerleave' : 'mouseleave';
+
+/***/ }),
+/* 9 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+var onResize = Symbol('onResize');
+
+var Breakpoints = function () {
+ function Breakpoints(slider) {
+ _classCallCheck(this, Breakpoints);
+
+ this.slider = slider;
+ this.options = slider.options;
+
+ this[onResize] = this[onResize].bind(this);
+
+ this._bindEvents();
+ }
+
+ _createClass(Breakpoints, [{
+ key: 'init',
+ value: function init() {
+ this._defaultBreakpoint = {
+ slidesToShow: this.options.slidesToShow,
+ slidesToScroll: this.options.slidesToScroll
+ };
+ this.options.breakpoints.sort(function (a, b) {
+ return parseInt(a.changePoint, 10) > parseInt(b.changePoint, 10);
+ });
+ this._currentBreakpoint = this._getActiveBreakpoint();
+
+ return this;
+ }
+ }, {
+ key: 'destroy',
+ value: function destroy() {
+ this._unbindEvents();
+ }
+ }, {
+ key: '_bindEvents',
+ value: function _bindEvents() {
+ window.addEventListener('resize', this[onResize]);
+ window.addEventListener('orientationchange', this[onResize]);
+ }
+ }, {
+ key: '_unbindEvents',
+ value: function _unbindEvents() {
+ window.removeEventListener('resize', this[onResize]);
+ window.removeEventListener('orientationchange', this[onResize]);
+ }
+ }, {
+ key: '_getActiveBreakpoint',
+ value: function _getActiveBreakpoint() {
+ //Get breakpoint for window width
+ var _iteratorNormalCompletion = true;
+ var _didIteratorError = false;
+ var _iteratorError = undefined;
+
+ try {
+ for (var _iterator = this.options.breakpoints[Symbol.iterator](), _step; !(_iteratorNormalCompletion = (_step = _iterator.next()).done); _iteratorNormalCompletion = true) {
+ var point = _step.value;
+
+ if (point.changePoint >= window.innerWidth) {
+ return point;
+ }
+ }
+ } catch (err) {
+ _didIteratorError = true;
+ _iteratorError = err;
+ } finally {
+ try {
+ if (!_iteratorNormalCompletion && _iterator.return) {
+ _iterator.return();
+ }
+ } finally {
+ if (_didIteratorError) {
+ throw _iteratorError;
+ }
+ }
+ }
+
+ return this._defaultBreakpoint;
+ }
+ }, {
+ key: 'getSlidesToShow',
+ value: function getSlidesToShow() {
+ return this._currentBreakpoint ? this._currentBreakpoint.slidesToShow : this._defaultBreakpoint.slidesToShow;
+ }
+ }, {
+ key: 'getSlidesToScroll',
+ value: function getSlidesToScroll() {
+ return this._currentBreakpoint ? this._currentBreakpoint.slidesToScroll : this._defaultBreakpoint.slidesToScroll;
+ }
+ }, {
+ key: 'apply',
+ value: function apply() {
+ if (this.slider.state.index >= this.slider.state.length && this.slider.state.index !== 0) {
+ this.slider.state.index = this.slider.state.index - this._currentBreakpoint.slidesToScroll;
+ }
+ if (this.slider.state.length <= this._currentBreakpoint.slidesToShow) {
+ this.slider.state.index = 0;
+ }
+
+ if (this.options.loop) {
+ this.slider._loop.init().apply();
+ }
+
+ if (this.options.infinite) {
+ this.slider._infinite.init().apply();
+ }
+
+ this.slider._setDimensions();
+ this.slider._transitioner.init().apply(true, this.slider._setHeight.bind(this.slider));
+ this.slider._setClasses();
+
+ this.slider._navigation.refresh();
+ this.slider._pagination.refresh();
+ }
+ }, {
+ key: onResize,
+ value: function value(e) {
+ var newBreakPoint = this._getActiveBreakpoint();
+ if (newBreakPoint.slidesToShow !== this._currentBreakpoint.slidesToShow) {
+ this._currentBreakpoint = newBreakPoint;
+ this.apply();
+ }
+ }
+ }]);
+
+ return Breakpoints;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (Breakpoints);
+
+/***/ }),
+/* 10 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _toConsumableArray(arr) { if (Array.isArray(arr)) { for (var i = 0, arr2 = Array(arr.length); i < arr.length; i++) { arr2[i] = arr[i]; } return arr2; } else { return Array.from(arr); } }
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+var Infinite = function () {
+ function Infinite(slider) {
+ _classCallCheck(this, Infinite);
+
+ this.slider = slider;
+ }
+
+ _createClass(Infinite, [{
+ key: 'init',
+ value: function init() {
+ if (this.slider.options.infinite && this.slider.options.effect === 'translate') {
+ if (this.slider.options.centerMode) {
+ this._infiniteCount = Math.ceil(this.slider.slidesToShow + this.slider.slidesToShow / 2);
+ } else {
+ this._infiniteCount = this.slider.slidesToShow;
+ }
+
+ var frontClones = [];
+ var slideIndex = 0;
+ for (var i = this.slider.state.length; i > this.slider.state.length - 1 - this._infiniteCount; i -= 1) {
+ slideIndex = i - 1;
+ frontClones.unshift(this._cloneSlide(this.slider.slides[slideIndex], slideIndex - this.slider.state.length));
+ }
+
+ var backClones = [];
+ for (var _i = 0; _i < this._infiniteCount + this.slider.state.length; _i += 1) {
+ backClones.push(this._cloneSlide(this.slider.slides[_i % this.slider.state.length], _i + this.slider.state.length));
+ }
+
+ this.slider.slides = [].concat(frontClones, _toConsumableArray(this.slider.slides), backClones);
+ }
+ return this;
+ }
+ }, {
+ key: 'apply',
+ value: function apply() {}
+ }, {
+ key: 'onTransitionEnd',
+ value: function onTransitionEnd(e) {
+ if (this.slider.options.infinite) {
+ if (this.slider.state.next >= this.slider.state.length) {
+ this.slider.state.index = this.slider.state.next = this.slider.state.next - this.slider.state.length;
+ this.slider.transitioner.apply(true);
+ } else if (this.slider.state.next < 0) {
+ this.slider.state.index = this.slider.state.next = this.slider.state.length + this.slider.state.next;
+ this.slider.transitioner.apply(true);
+ }
+ }
+ }
+ }, {
+ key: '_cloneSlide',
+ value: function _cloneSlide(slide, index) {
+ var newSlide = slide.cloneNode(true);
+ newSlide.dataset.sliderIndex = index;
+ newSlide.dataset.cloned = true;
+ var ids = newSlide.querySelectorAll('[id]') || [];
+ ids.forEach(function (id) {
+ id.setAttribute('id', '');
+ });
+ return newSlide;
+ }
+ }]);
+
+ return Infinite;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (Infinite);
+
+/***/ }),
+/* 11 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__utils_dom__ = __webpack_require__(12);
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+
+
+var Loop = function () {
+ function Loop(slider) {
+ _classCallCheck(this, Loop);
+
+ this.slider = slider;
+ }
+
+ _createClass(Loop, [{
+ key: "init",
+ value: function init() {
+ return this;
+ }
+ }, {
+ key: "apply",
+ value: function apply() {
+ if (this.slider.options.loop) {
+ if (this.slider.state.next > 0) {
+ if (this.slider.state.next < this.slider.state.length) {
+ if (this.slider.state.next > this.slider.state.length - this.slider.slidesToShow && Object(__WEBPACK_IMPORTED_MODULE_0__utils_dom__["a" /* isInViewport */])(this.slider._slides[this.slider.state.length - 1], this.slider.wrapper)) {
+ this.slider.state.next = 0;
+ } else {
+ this.slider.state.next = Math.min(Math.max(this.slider.state.next, 0), this.slider.state.length - this.slider.slidesToShow);
+ }
+ } else {
+ this.slider.state.next = 0;
+ }
+ } else {
+ if (this.slider.state.next <= 0 - this.slider.slidesToScroll) {
+ this.slider.state.next = this.slider.state.length - this.slider.slidesToShow;
+ } else {
+ this.slider.state.next = 0;
+ }
+ }
+ }
+ }
+ }]);
+
+ return Loop;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (Loop);
+
+/***/ }),
+/* 12 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "a", function() { return isInViewport; });
+var isInViewport = function isInViewport(element, html) {
+ var rect = element.getBoundingClientRect();
+ html = html || document.documentElement;
+ return rect.top >= 0 && rect.left >= 0 && rect.bottom <= (window.innerHeight || html.clientHeight) && rect.right <= (window.innerWidth || html.clientWidth);
+};
+
+/***/ }),
+/* 13 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__templates_navigation__ = __webpack_require__(14);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_1__utils_detect_supportsPassive__ = __webpack_require__(1);
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+
+
+
+var Navigation = function () {
+ function Navigation(slider) {
+ _classCallCheck(this, Navigation);
+
+ this.slider = slider;
+
+ this._clickEvents = ['click', 'touch'];
+ this._supportsPassive = Object(__WEBPACK_IMPORTED_MODULE_1__utils_detect_supportsPassive__["a" /* default */])();
+
+ this.onPreviousClick = this.onPreviousClick.bind(this);
+ this.onNextClick = this.onNextClick.bind(this);
+ this.onKeyUp = this.onKeyUp.bind(this);
+ }
+
+ _createClass(Navigation, [{
+ key: 'init',
+ value: function init() {
+ this.node = document.createRange().createContextualFragment(Object(__WEBPACK_IMPORTED_MODULE_0__templates_navigation__["a" /* default */])(this.slider.options.icons));
+ this._ui = {
+ previous: this.node.querySelector('.slider-navigation-previous'),
+ next: this.node.querySelector('.slider-navigation-next')
+ };
+
+ this._unbindEvents();
+ this._bindEvents();
+
+ this.refresh();
+
+ return this;
+ }
+ }, {
+ key: 'destroy',
+ value: function destroy() {
+ this._unbindEvents();
+ }
+ }, {
+ key: '_bindEvents',
+ value: function _bindEvents() {
+ var _this = this;
+
+ this.slider.wrapper.addEventListener('keyup', this.onKeyUp);
+ this._clickEvents.forEach(function (clickEvent) {
+ _this._ui.previous.addEventListener(clickEvent, _this.onPreviousClick);
+ _this._ui.next.addEventListener(clickEvent, _this.onNextClick);
+ });
+ }
+ }, {
+ key: '_unbindEvents',
+ value: function _unbindEvents() {
+ var _this2 = this;
+
+ this.slider.wrapper.removeEventListener('keyup', this.onKeyUp);
+ this._clickEvents.forEach(function (clickEvent) {
+ _this2._ui.previous.removeEventListener(clickEvent, _this2.onPreviousClick);
+ _this2._ui.next.removeEventListener(clickEvent, _this2.onNextClick);
+ });
+ }
+ }, {
+ key: 'onNextClick',
+ value: function onNextClick(e) {
+ if (!this._supportsPassive) {
+ e.preventDefault();
+ }
+
+ if (this.slider.options.navigation) {
+ this.slider.next();
+ }
+ }
+ }, {
+ key: 'onPreviousClick',
+ value: function onPreviousClick(e) {
+ if (!this._supportsPassive) {
+ e.preventDefault();
+ }
+
+ if (this.slider.options.navigation) {
+ this.slider.previous();
+ }
+ }
+ }, {
+ key: 'onKeyUp',
+ value: function onKeyUp(e) {
+ if (this.slider.options.keyNavigation) {
+ if (e.key === 'ArrowRight' || e.key === 'Right') {
+ this.slider.next();
+ } else if (e.key === 'ArrowLeft' || e.key === 'Left') {
+ this.slider.previous();
+ }
+ }
+ }
+ }, {
+ key: 'refresh',
+ value: function refresh() {
+ // let centerOffset = Math.floor(this.options.slidesToShow / 2);
+ if (!this.slider.options.loop && !this.slider.options.infinite) {
+ if (this.slider.options.navigation && this.slider.state.length > this.slider.slidesToShow) {
+ this._ui.previous.classList.remove('is-hidden');
+ this._ui.next.classList.remove('is-hidden');
+ if (this.slider.state.next === 0) {
+ this._ui.previous.classList.add('is-hidden');
+ this._ui.next.classList.remove('is-hidden');
+ } else if (this.slider.state.next >= this.slider.state.length - this.slider.slidesToShow && !this.slider.options.centerMode) {
+ this._ui.previous.classList.remove('is-hidden');
+ this._ui.next.classList.add('is-hidden');
+ } else if (this.slider.state.next >= this.slider.state.length - 1 && this.slider.options.centerMode) {
+ this._ui.previous.classList.remove('is-hidden');
+ this._ui.next.classList.add('is-hidden');
+ }
+ } else {
+ this._ui.previous.classList.add('is-hidden');
+ this._ui.next.classList.add('is-hidden');
+ }
+ }
+ }
+ }, {
+ key: 'render',
+ value: function render() {
+ return this.node;
+ }
+ }]);
+
+ return Navigation;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (Navigation);
+
+/***/ }),
+/* 14 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony default export */ __webpack_exports__["a"] = (function (icons) {
+ return "" + icons.previous + "
\n" + icons.next + "
";
+});
+
+/***/ }),
+/* 15 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__templates_pagination__ = __webpack_require__(16);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_1__templates_pagination_page__ = __webpack_require__(17);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_2__utils_detect_supportsPassive__ = __webpack_require__(1);
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+
+
+
+
+var Pagination = function () {
+ function Pagination(slider) {
+ _classCallCheck(this, Pagination);
+
+ this.slider = slider;
+
+ this._clickEvents = ['click', 'touch'];
+ this._supportsPassive = Object(__WEBPACK_IMPORTED_MODULE_2__utils_detect_supportsPassive__["a" /* default */])();
+
+ this.onPageClick = this.onPageClick.bind(this);
+ this.onResize = this.onResize.bind(this);
+ }
+
+ _createClass(Pagination, [{
+ key: 'init',
+ value: function init() {
+ this._pages = [];
+ this.node = document.createRange().createContextualFragment(Object(__WEBPACK_IMPORTED_MODULE_0__templates_pagination__["a" /* default */])());
+ this._ui = {
+ container: this.node.firstChild
+ };
+
+ this._count = Math.ceil((this.slider.state.length - this.slider.slidesToShow) / this.slider.slidesToScroll);
+
+ this._draw();
+ this.refresh();
+
+ return this;
+ }
+ }, {
+ key: 'destroy',
+ value: function destroy() {
+ this._unbindEvents();
+ }
+ }, {
+ key: '_bindEvents',
+ value: function _bindEvents() {
+ var _this = this;
+
+ window.addEventListener('resize', this.onResize);
+ window.addEventListener('orientationchange', this.onResize);
+
+ this._clickEvents.forEach(function (clickEvent) {
+ _this._pages.forEach(function (page) {
+ return page.addEventListener(clickEvent, _this.onPageClick);
+ });
+ });
+ }
+ }, {
+ key: '_unbindEvents',
+ value: function _unbindEvents() {
+ var _this2 = this;
+
+ window.removeEventListener('resize', this.onResize);
+ window.removeEventListener('orientationchange', this.onResize);
+
+ this._clickEvents.forEach(function (clickEvent) {
+ _this2._pages.forEach(function (page) {
+ return page.removeEventListener(clickEvent, _this2.onPageClick);
+ });
+ });
+ }
+ }, {
+ key: '_draw',
+ value: function _draw() {
+ this._ui.container.innerHTML = '';
+ if (this.slider.options.pagination && this.slider.state.length > this.slider.slidesToShow) {
+ for (var i = 0; i <= this._count; i++) {
+ var newPageNode = document.createRange().createContextualFragment(Object(__WEBPACK_IMPORTED_MODULE_1__templates_pagination_page__["a" /* default */])()).firstChild;
+ newPageNode.dataset.index = i * this.slider.slidesToScroll;
+ this._pages.push(newPageNode);
+ this._ui.container.appendChild(newPageNode);
+ }
+ this._bindEvents();
+ }
+ }
+ }, {
+ key: 'onPageClick',
+ value: function onPageClick(e) {
+ if (!this._supportsPassive) {
+ e.preventDefault();
+ }
+
+ this.slider.state.next = e.currentTarget.dataset.index;
+ this.slider.show();
+ }
+ }, {
+ key: 'onResize',
+ value: function onResize() {
+ this._draw();
+ }
+ }, {
+ key: 'refresh',
+ value: function refresh() {
+ var _this3 = this;
+
+ var newCount = void 0;
+
+ if (this.slider.options.infinite) {
+ newCount = Math.ceil(this.slider.state.length - 1 / this.slider.slidesToScroll);
+ } else {
+ newCount = Math.ceil((this.slider.state.length - this.slider.slidesToShow) / this.slider.slidesToScroll);
+ }
+ if (newCount !== this._count) {
+ this._count = newCount;
+ this._draw();
+ }
+
+ this._pages.forEach(function (page) {
+ page.classList.remove('is-active');
+ if (parseInt(page.dataset.index, 10) === _this3.slider.state.next % _this3.slider.state.length) {
+ page.classList.add('is-active');
+ }
+ });
+ }
+ }, {
+ key: 'render',
+ value: function render() {
+ return this.node;
+ }
+ }]);
+
+ return Pagination;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (Pagination);
+
+/***/ }),
+/* 16 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony default export */ __webpack_exports__["a"] = (function () {
+ return "";
+});
+
+/***/ }),
+/* 17 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony default export */ __webpack_exports__["a"] = (function () {
+ return "
";
+});
+
+/***/ }),
+/* 18 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__utils_coordinate__ = __webpack_require__(4);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_1__utils_detect_supportsPassive__ = __webpack_require__(1);
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+
+
+
+var Swipe = function () {
+ function Swipe(slider) {
+ _classCallCheck(this, Swipe);
+
+ this.slider = slider;
+
+ this._supportsPassive = Object(__WEBPACK_IMPORTED_MODULE_1__utils_detect_supportsPassive__["a" /* default */])();
+
+ this.onStartDrag = this.onStartDrag.bind(this);
+ this.onMoveDrag = this.onMoveDrag.bind(this);
+ this.onStopDrag = this.onStopDrag.bind(this);
+
+ this._init();
+ }
+
+ _createClass(Swipe, [{
+ key: '_init',
+ value: function _init() {}
+ }, {
+ key: 'bindEvents',
+ value: function bindEvents() {
+ var _this = this;
+
+ this.slider.container.addEventListener('dragstart', function (e) {
+ if (!_this._supportsPassive) {
+ e.preventDefault();
+ }
+ });
+ this.slider.container.addEventListener('mousedown', this.onStartDrag);
+ this.slider.container.addEventListener('touchstart', this.onStartDrag);
+
+ window.addEventListener('mousemove', this.onMoveDrag);
+ window.addEventListener('touchmove', this.onMoveDrag);
+
+ window.addEventListener('mouseup', this.onStopDrag);
+ window.addEventListener('touchend', this.onStopDrag);
+ window.addEventListener('touchcancel', this.onStopDrag);
+ }
+ }, {
+ key: 'unbindEvents',
+ value: function unbindEvents() {
+ var _this2 = this;
+
+ this.slider.container.removeEventListener('dragstart', function (e) {
+ if (!_this2._supportsPassive) {
+ e.preventDefault();
+ }
+ });
+ this.slider.container.removeEventListener('mousedown', this.onStartDrag);
+ this.slider.container.removeEventListener('touchstart', this.onStartDrag);
+
+ window.removeEventListener('mousemove', this.onMoveDrag);
+ window.removeEventListener('touchmove', this.onMoveDrag);
+
+ window.removeEventListener('mouseup', this.onStopDrag);
+ window.removeEventListener('mouseup', this.onStopDrag);
+ window.removeEventListener('touchcancel', this.onStopDrag);
+ }
+
+ /**
+ * @param {MouseEvent|TouchEvent}
+ */
+
+ }, {
+ key: 'onStartDrag',
+ value: function onStartDrag(e) {
+ if (e.touches) {
+ if (e.touches.length > 1) {
+ return;
+ } else {
+ e = e.touches[0];
+ }
+ }
+
+ this._origin = new __WEBPACK_IMPORTED_MODULE_0__utils_coordinate__["a" /* default */](e.screenX, e.screenY);
+ this.width = this.slider.wrapperWidth;
+ this.slider.transitioner.disable();
+ }
+
+ /**
+ * @param {MouseEvent|TouchEvent}
+ */
+
+ }, {
+ key: 'onMoveDrag',
+ value: function onMoveDrag(e) {
+ if (this._origin) {
+ var point = e.touches ? e.touches[0] : e;
+ this._lastTranslate = new __WEBPACK_IMPORTED_MODULE_0__utils_coordinate__["a" /* default */](point.screenX - this._origin.x, point.screenY - this._origin.y);
+ if (e.touches) {
+ if (Math.abs(this._lastTranslate.x) > Math.abs(this._lastTranslate.y)) {
+ if (!this._supportsPassive) {
+ e.preventDefault();
+ }
+ e.stopPropagation();
+ }
+ }
+ }
+ }
+
+ /**
+ * @param {MouseEvent|TouchEvent}
+ */
+
+ }, {
+ key: 'onStopDrag',
+ value: function onStopDrag(e) {
+ if (this._origin && this._lastTranslate) {
+ if (Math.abs(this._lastTranslate.x) > 0.2 * this.width) {
+ if (this._lastTranslate.x < 0) {
+ this.slider.next();
+ } else {
+ this.slider.previous();
+ }
+ } else {
+ this.slider.show(true);
+ }
+ }
+ this._origin = null;
+ this._lastTranslate = null;
+ }
+ }]);
+
+ return Swipe;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (Swipe);
+
+/***/ }),
+/* 19 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__transitions_fade__ = __webpack_require__(20);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_1__transitions_translate__ = __webpack_require__(21);
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+
+
+
+var Transitioner = function () {
+ function Transitioner(slider) {
+ _classCallCheck(this, Transitioner);
+
+ this.slider = slider;
+ this.options = slider.options;
+
+ this._animating = false;
+ this._animation = undefined;
+
+ this._translate = new __WEBPACK_IMPORTED_MODULE_1__transitions_translate__["a" /* default */](this, slider, slider.options);
+ this._fade = new __WEBPACK_IMPORTED_MODULE_0__transitions_fade__["a" /* default */](this, slider, slider.options);
+ }
+
+ _createClass(Transitioner, [{
+ key: 'init',
+ value: function init() {
+ this._fade.init();
+ this._translate.init();
+ return this;
+ }
+ }, {
+ key: 'isAnimating',
+ value: function isAnimating() {
+ return this._animating;
+ }
+ }, {
+ key: 'enable',
+ value: function enable() {
+ this._animation && this._animation.enable();
+ }
+ }, {
+ key: 'disable',
+ value: function disable() {
+ this._animation && this._animation.disable();
+ }
+ }, {
+ key: 'apply',
+ value: function apply(force, callback) {
+ // If we don't force refresh and animation in progress then return
+ if (this._animating && !force) {
+ return;
+ }
+
+ switch (this.options.effect) {
+ case 'fade':
+ this._animation = this._fade;
+ break;
+ case 'translate':
+ default:
+ this._animation = this._translate;
+ break;
+ }
+
+ this._animationCallback = callback;
+
+ if (force) {
+ this._animation && this._animation.disable();
+ } else {
+ this._animation && this._animation.enable();
+ this._animating = true;
+ }
+
+ this._animation && this._animation.apply();
+
+ if (force) {
+ this.end();
+ }
+ }
+ }, {
+ key: 'end',
+ value: function end() {
+ this._animating = false;
+ this._animation = undefined;
+ this.slider.state.index = this.slider.state.next;
+ if (this._animationCallback) {
+ this._animationCallback();
+ }
+ }
+ }]);
+
+ return Transitioner;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (Transitioner);
+
+/***/ }),
+/* 20 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__utils_css__ = __webpack_require__(0);
+var _extends = Object.assign || function (target) { for (var i = 1; i < arguments.length; i++) { var source = arguments[i]; for (var key in source) { if (Object.prototype.hasOwnProperty.call(source, key)) { target[key] = source[key]; } } } return target; };
+
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+
+
+var Fade = function () {
+ function Fade(transitioner, slider) {
+ var options = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};
+
+ _classCallCheck(this, Fade);
+
+ this.transitioner = transitioner;
+ this.slider = slider;
+ this.options = _extends({}, options);
+ }
+
+ _createClass(Fade, [{
+ key: 'init',
+ value: function init() {
+ var _this = this;
+
+ if (this.options.effect === 'fade') {
+ this.slider.slides.forEach(function (slide, index) {
+ Object(__WEBPACK_IMPORTED_MODULE_0__utils_css__["a" /* css */])(slide, {
+ position: 'absolute',
+ left: 0,
+ top: 0,
+ bottom: 0,
+ 'z-index': slide.dataset.sliderIndex == _this.slider.state.index ? 0 : -2,
+ opacity: slide.dataset.sliderIndex == _this.slider.state.index ? 1 : 0
+ });
+ });
+ }
+ return this;
+ }
+ }, {
+ key: 'enable',
+ value: function enable() {
+ var _this2 = this;
+
+ this._oldSlide = this.slider.slides.filter(function (slide) {
+ return slide.dataset.sliderIndex == _this2.slider.state.index;
+ })[0];
+ this._newSlide = this.slider.slides.filter(function (slide) {
+ return slide.dataset.sliderIndex == _this2.slider.state.next;
+ })[0];
+ if (this._newSlide) {
+ this._newSlide.addEventListener('transitionend', this.onTransitionEnd.bind(this));
+ this._newSlide.style.transition = this.options.duration + 'ms ' + this.options.timing;
+ if (this._oldSlide) {
+ this._oldSlide.addEventListener('transitionend', this.onTransitionEnd.bind(this));
+ this._oldSlide.style.transition = this.options.duration + 'ms ' + this.options.timing;
+ }
+ }
+ }
+ }, {
+ key: 'disable',
+ value: function disable() {
+ var _this3 = this;
+
+ this._oldSlide = this.slider.slides.filter(function (slide) {
+ return slide.dataset.sliderIndex == _this3.slider.state.index;
+ })[0];
+ this._newSlide = this.slider.slides.filter(function (slide) {
+ return slide.dataset.sliderIndex == _this3.slider.state.next;
+ })[0];
+ if (this._newSlide) {
+ this._newSlide.removeEventListener('transitionend', this.onTransitionEnd.bind(this));
+ this._newSlide.style.transition = 'none';
+ if (this._oldSlide) {
+ this._oldSlide.removeEventListener('transitionend', this.onTransitionEnd.bind(this));
+ this._oldSlide.style.transition = 'none';
+ }
+ }
+ }
+ }, {
+ key: 'apply',
+ value: function apply(force) {
+ var _this4 = this;
+
+ this._oldSlide = this.slider.slides.filter(function (slide) {
+ return slide.dataset.sliderIndex == _this4.slider.state.index;
+ })[0];
+ this._newSlide = this.slider.slides.filter(function (slide) {
+ return slide.dataset.sliderIndex == _this4.slider.state.next;
+ })[0];
+
+ if (this._oldSlide && this._newSlide) {
+ Object(__WEBPACK_IMPORTED_MODULE_0__utils_css__["a" /* css */])(this._oldSlide, {
+ opacity: 0
+ });
+ Object(__WEBPACK_IMPORTED_MODULE_0__utils_css__["a" /* css */])(this._newSlide, {
+ opacity: 1,
+ 'z-index': force ? 0 : -1
+ });
+ }
+ }
+ }, {
+ key: 'onTransitionEnd',
+ value: function onTransitionEnd(e) {
+ if (this.options.effect === 'fade') {
+ if (this.transitioner.isAnimating() && e.target == this._newSlide) {
+ if (this._newSlide) {
+ Object(__WEBPACK_IMPORTED_MODULE_0__utils_css__["a" /* css */])(this._newSlide, {
+ 'z-index': 0
+ });
+ this._newSlide.removeEventListener('transitionend', this.onTransitionEnd.bind(this));
+ }
+ if (this._oldSlide) {
+ Object(__WEBPACK_IMPORTED_MODULE_0__utils_css__["a" /* css */])(this._oldSlide, {
+ 'z-index': -2
+ });
+ this._oldSlide.removeEventListener('transitionend', this.onTransitionEnd.bind(this));
+ }
+ }
+ this.transitioner.end();
+ }
+ }
+ }]);
+
+ return Fade;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (Fade);
+
+/***/ }),
+/* 21 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__utils_coordinate__ = __webpack_require__(4);
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_1__utils_css__ = __webpack_require__(0);
+var _extends = Object.assign || function (target) { for (var i = 1; i < arguments.length; i++) { var source = arguments[i]; for (var key in source) { if (Object.prototype.hasOwnProperty.call(source, key)) { target[key] = source[key]; } } } return target; };
+
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+
+
+
+var Translate = function () {
+ function Translate(transitioner, slider) {
+ var options = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};
+
+ _classCallCheck(this, Translate);
+
+ this.transitioner = transitioner;
+ this.slider = slider;
+ this.options = _extends({}, options);
+
+ this.onTransitionEnd = this.onTransitionEnd.bind(this);
+ }
+
+ _createClass(Translate, [{
+ key: 'init',
+ value: function init() {
+ this._position = new __WEBPACK_IMPORTED_MODULE_0__utils_coordinate__["a" /* default */](this.slider.container.offsetLeft, this.slider.container.offsetTop);
+ this._bindEvents();
+ return this;
+ }
+ }, {
+ key: 'destroy',
+ value: function destroy() {
+ this._unbindEvents();
+ }
+ }, {
+ key: '_bindEvents',
+ value: function _bindEvents() {
+ this.slider.container.addEventListener('transitionend', this.onTransitionEnd);
+ }
+ }, {
+ key: '_unbindEvents',
+ value: function _unbindEvents() {
+ this.slider.container.removeEventListener('transitionend', this.onTransitionEnd);
+ }
+ }, {
+ key: 'enable',
+ value: function enable() {
+ this.slider.container.style.transition = this.options.duration + 'ms ' + this.options.timing;
+ }
+ }, {
+ key: 'disable',
+ value: function disable() {
+ this.slider.container.style.transition = 'none';
+ }
+ }, {
+ key: 'apply',
+ value: function apply() {
+ var _this = this;
+
+ var maxOffset = void 0;
+ if (this.options.effect === 'translate') {
+ var slide = this.slider.slides.filter(function (slide) {
+ return slide.dataset.sliderIndex == _this.slider.state.next;
+ })[0];
+ var slideOffset = new __WEBPACK_IMPORTED_MODULE_0__utils_coordinate__["a" /* default */](slide.offsetLeft, slide.offsetTop);
+ if (this.options.centerMode) {
+ maxOffset = new __WEBPACK_IMPORTED_MODULE_0__utils_coordinate__["a" /* default */](Math.round(Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["e" /* width */])(this.slider.container)), Math.round(Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["b" /* height */])(this.slider.container)));
+ } else {
+ maxOffset = new __WEBPACK_IMPORTED_MODULE_0__utils_coordinate__["a" /* default */](Math.round(Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["e" /* width */])(this.slider.container) - Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["e" /* width */])(this.slider.wrapper)), Math.round(Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["b" /* height */])(this.slider.container) - Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["b" /* height */])(this.slider.wrapper)));
+ }
+ var nextOffset = new __WEBPACK_IMPORTED_MODULE_0__utils_coordinate__["a" /* default */](Math.min(Math.max(slideOffset.x * -1, maxOffset.x * -1), 0), Math.min(Math.max(slideOffset.y * -1, maxOffset.y * -1), 0));
+ if (this.options.loop) {
+ if (!this.options.vertical && Math.abs(this._position.x) > maxOffset.x) {
+ nextOffset.x = 0;
+ this.slider.state.next = 0;
+ } else if (this.options.vertical && Math.abs(this._position.y) > maxOffset.y) {
+ nextOffset.y = 0;
+ this.slider.state.next = 0;
+ }
+ }
+
+ this._position.x = nextOffset.x;
+ this._position.y = nextOffset.y;
+ if (this.options.centerMode) {
+ this._position.x = this._position.x + this.slider.wrapperWidth / 2 - Object(__WEBPACK_IMPORTED_MODULE_1__utils_css__["e" /* width */])(slide) / 2;
+ }
+
+ if (this.slider.direction === 'rtl') {
+ this._position.x = -this._position.x;
+ this._position.y = -this._position.y;
+ }
+ this.slider.container.style.transform = 'translate3d(' + this._position.x + 'px, ' + this._position.y + 'px, 0)';
+
+ /**
+ * update the index with the nextIndex only if
+ * the offset of the nextIndex is in the range of the maxOffset
+ */
+ if (slideOffset.x > maxOffset.x) {
+ this.slider.transitioner.end();
+ }
+ }
+ }
+ }, {
+ key: 'onTransitionEnd',
+ value: function onTransitionEnd(e) {
+ if (this.options.effect === 'translate') {
+
+ if (this.transitioner.isAnimating() && e.target == this.slider.container) {
+ if (this.options.infinite) {
+ this.slider._infinite.onTransitionEnd(e);
+ }
+ }
+ this.transitioner.end();
+ }
+ }
+ }]);
+
+ return Translate;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (Translate);
+
+/***/ }),
+/* 22 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+var defaultOptions = {
+ initialSlide: 0,
+ slidesToScroll: 1,
+ slidesToShow: 1,
+
+ navigation: true,
+ navigationKeys: true,
+ navigationSwipe: true,
+
+ pagination: true,
+
+ loop: false,
+ infinite: false,
+
+ effect: 'translate',
+ duration: 300,
+ timing: 'ease',
+
+ autoplay: false,
+ autoplaySpeed: 3000,
+ pauseOnHover: true,
+ breakpoints: [{
+ changePoint: 480,
+ slidesToShow: 1,
+ slidesToScroll: 1
+ }, {
+ changePoint: 640,
+ slidesToShow: 2,
+ slidesToScroll: 2
+ }, {
+ changePoint: 768,
+ slidesToShow: 3,
+ slidesToScroll: 3
+ }],
+
+ onReady: null,
+ icons: {
+ 'previous': '\n \n ',
+ 'next': '\n \n '
+ }
+};
+
+/* harmony default export */ __webpack_exports__["a"] = (defaultOptions);
+
+/***/ }),
+/* 23 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony default export */ __webpack_exports__["a"] = (function (id) {
+ return "";
+});
+
+/***/ }),
+/* 24 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+/* harmony default export */ __webpack_exports__["a"] = (function () {
+ return "
";
+});
+
+/***/ })
+/******/ ])["default"];
+});
diff --git a/docs/project_page/static/js/bulma-carousel.min.js b/docs/project_page/static/js/bulma-carousel.min.js
new file mode 100644
index 0000000..f7cea5a
--- /dev/null
+++ b/docs/project_page/static/js/bulma-carousel.min.js
@@ -0,0 +1 @@
+!function(t,e){"object"==typeof exports&&"object"==typeof module?module.exports=e():"function"==typeof define&&define.amd?define([],e):"object"==typeof exports?exports.bulmaCarousel=e():t.bulmaCarousel=e()}("undefined"!=typeof self?self:this,function(){return function(i){var n={};function s(t){if(n[t])return n[t].exports;var e=n[t]={i:t,l:!1,exports:{}};return i[t].call(e.exports,e,e.exports,s),e.l=!0,e.exports}return s.m=i,s.c=n,s.d=function(t,e,i){s.o(t,e)||Object.defineProperty(t,e,{configurable:!1,enumerable:!0,get:i})},s.n=function(t){var e=t&&t.__esModule?function(){return t.default}:function(){return t};return s.d(e,"a",e),e},s.o=function(t,e){return Object.prototype.hasOwnProperty.call(t,e)},s.p="",s(s.s=5)}([function(t,e,i){"use strict";i.d(e,"d",function(){return s}),i.d(e,"e",function(){return r}),i.d(e,"b",function(){return o}),i.d(e,"c",function(){return a}),i.d(e,"a",function(){return l});var n=i(2),s=function(e,t){(t=Array.isArray(t)?t:t.split(" ")).forEach(function(t){e.classList.remove(t)})},r=function(t){return t.getBoundingClientRect().width||t.offsetWidth},o=function(t){return t.getBoundingClientRect().height||t.offsetHeight},a=function(t){var e=1=t._x&&this._x<=e._x&&this._y>=t._y&&this._y<=e._y}},{key:"constrain",value:function(t,e){if(t._x>e._x||t._y>e._y)return this;var i=this._x,n=this._y;return null!==t._x&&(i=Math.max(i,t._x)),null!==e._x&&(i=Math.min(i,e._x)),null!==t._y&&(n=Math.max(n,t._y)),null!==e._y&&(n=Math.min(n,e._y)),new s(i,n)}},{key:"reposition",value:function(t){t.style.top=this._y+"px",t.style.left=this._x+"px"}},{key:"toString",value:function(){return"("+this._x+","+this._y+")"}},{key:"x",get:function(){return this._x},set:function(){var t=0this.state.length-this.slidesToShow&&!this.options.centerMode?this.state.next=this.state.index:this.state.next=this.state.index+this.slidesToScroll,this.show()}},{key:"previous",value:function(){this.options.loop||this.options.infinite||0!==this.state.index?this.state.next=this.state.index-this.slidesToScroll:this.state.next=this.state.index,this.show()}},{key:"start",value:function(){this._autoplay.start()}},{key:"pause",value:function(){this._autoplay.pause()}},{key:"stop",value:function(){this._autoplay.stop()}},{key:"show",value:function(t){var e=1this.options.slidesToShow&&(this.options.slidesToScroll=this.slidesToShow),this._breakpoint.init(),this.state.index>=this.state.length&&0!==this.state.index&&(this.state.index=this.state.index-this.slidesToScroll),this.state.length<=this.slidesToShow&&(this.state.index=0),this._ui.wrapper.appendChild(this._navigation.init().render()),this._ui.wrapper.appendChild(this._pagination.init().render()),this.options.navigationSwipe?this._swipe.bindEvents():this._swipe._bindEvents(),this._breakpoint.apply(),this._slides.forEach(function(t){return e._ui.container.appendChild(t)}),this._transitioner.init().apply(!0,this._setHeight.bind(this)),this.options.autoplay&&this._autoplay.init().start()}},{key:"destroy",value:function(){var e=this;this._unbindEvents(),this._items.forEach(function(t){e.element.appendChild(t)}),this.node.remove()}},{key:"id",get:function(){return this._id}},{key:"index",set:function(t){this._index=t},get:function(){return this._index}},{key:"length",set:function(t){this._length=t},get:function(){return this._length}},{key:"slides",get:function(){return this._slides},set:function(t){this._slides=t}},{key:"slidesToScroll",get:function(){return"translate"===this.options.effect?this._breakpoint.getSlidesToScroll():1}},{key:"slidesToShow",get:function(){return"translate"===this.options.effect?this._breakpoint.getSlidesToShow():1}},{key:"direction",get:function(){return"rtl"===this.element.dir.toLowerCase()||"rtl"===this.element.style.direction?"rtl":"ltr"}},{key:"wrapper",get:function(){return this._ui.wrapper}},{key:"wrapperWidth",get:function(){return this._wrapperWidth||0}},{key:"container",get:function(){return this._ui.container}},{key:"containerWidth",get:function(){return this._containerWidth||0}},{key:"slideWidth",get:function(){return this._slideWidth||0}},{key:"transitioner",get:function(){return this._transitioner}}],[{key:"attach",value:function(){var i=this,t=0>t/4).toString(16)})}},function(t,e,i){"use strict";var n=i(3),s=i(8),r=function(){function n(t,e){for(var i=0;i=t.slider.state.length-t.slider.slidesToShow&&!t.slider.options.loop&&!t.slider.options.infinite?t.stop():t.slider.next())},this.slider.options.autoplaySpeed))}},{key:"stop",value:function(){this._interval=clearInterval(this._interval),this.emit("stop",this)}},{key:"pause",value:function(){var t=this,e=0parseInt(e.changePoint,10)}),this._currentBreakpoint=this._getActiveBreakpoint(),this}},{key:"destroy",value:function(){this._unbindEvents()}},{key:"_bindEvents",value:function(){window.addEventListener("resize",this[s]),window.addEventListener("orientationchange",this[s])}},{key:"_unbindEvents",value:function(){window.removeEventListener("resize",this[s]),window.removeEventListener("orientationchange",this[s])}},{key:"_getActiveBreakpoint",value:function(){var t=!0,e=!1,i=void 0;try{for(var n,s=this.options.breakpoints[Symbol.iterator]();!(t=(n=s.next()).done);t=!0){var r=n.value;if(r.changePoint>=window.innerWidth)return r}}catch(t){e=!0,i=t}finally{try{!t&&s.return&&s.return()}finally{if(e)throw i}}return this._defaultBreakpoint}},{key:"getSlidesToShow",value:function(){return this._currentBreakpoint?this._currentBreakpoint.slidesToShow:this._defaultBreakpoint.slidesToShow}},{key:"getSlidesToScroll",value:function(){return this._currentBreakpoint?this._currentBreakpoint.slidesToScroll:this._defaultBreakpoint.slidesToScroll}},{key:"apply",value:function(){this.slider.state.index>=this.slider.state.length&&0!==this.slider.state.index&&(this.slider.state.index=this.slider.state.index-this._currentBreakpoint.slidesToScroll),this.slider.state.length<=this._currentBreakpoint.slidesToShow&&(this.slider.state.index=0),this.options.loop&&this.slider._loop.init().apply(),this.options.infinite&&this.slider._infinite.init().apply(),this.slider._setDimensions(),this.slider._transitioner.init().apply(!0,this.slider._setHeight.bind(this.slider)),this.slider._setClasses(),this.slider._navigation.refresh(),this.slider._pagination.refresh()}},{key:s,value:function(t){var e=this._getActiveBreakpoint();e.slidesToShow!==this._currentBreakpoint.slidesToShow&&(this._currentBreakpoint=e,this.apply())}}]),e}();e.a=r},function(t,e,i){"use strict";var n=function(){function n(t,e){for(var i=0;ithis.slider.state.length-1-this._infiniteCount;i-=1)e=i-1,t.unshift(this._cloneSlide(this.slider.slides[e],e-this.slider.state.length));for(var n=[],s=0;s=this.slider.state.length?(this.slider.state.index=this.slider.state.next=this.slider.state.next-this.slider.state.length,this.slider.transitioner.apply(!0)):this.slider.state.next<0&&(this.slider.state.index=this.slider.state.next=this.slider.state.length+this.slider.state.next,this.slider.transitioner.apply(!0)))}},{key:"_cloneSlide",value:function(t,e){var i=t.cloneNode(!0);return i.dataset.sliderIndex=e,i.dataset.cloned=!0,(i.querySelectorAll("[id]")||[]).forEach(function(t){t.setAttribute("id","")}),i}}]),e}();e.a=s},function(t,e,i){"use strict";var n=i(12),s=function(){function n(t,e){for(var i=0;ithis.slider.state.length-this.slider.slidesToShow&&Object(n.a)(this.slider._slides[this.slider.state.length-1],this.slider.wrapper)?this.slider.state.next=0:this.slider.state.next=Math.min(Math.max(this.slider.state.next,0),this.slider.state.length-this.slider.slidesToShow):this.slider.state.next=0:this.slider.state.next<=0-this.slider.slidesToScroll?this.slider.state.next=this.slider.state.length-this.slider.slidesToShow:this.slider.state.next=0)}}]),e}();e.a=r},function(t,e,i){"use strict";i.d(e,"a",function(){return n});var n=function(t,e){var i=t.getBoundingClientRect();return e=e||document.documentElement,0<=i.top&&0<=i.left&&i.bottom<=(window.innerHeight||e.clientHeight)&&i.right<=(window.innerWidth||e.clientWidth)}},function(t,e,i){"use strict";var n=i(14),s=i(1),r=function(){function n(t,e){for(var i=0;ithis.slider.slidesToShow?(this._ui.previous.classList.remove("is-hidden"),this._ui.next.classList.remove("is-hidden"),0===this.slider.state.next?(this._ui.previous.classList.add("is-hidden"),this._ui.next.classList.remove("is-hidden")):this.slider.state.next>=this.slider.state.length-this.slider.slidesToShow&&!this.slider.options.centerMode?(this._ui.previous.classList.remove("is-hidden"),this._ui.next.classList.add("is-hidden")):this.slider.state.next>=this.slider.state.length-1&&this.slider.options.centerMode&&(this._ui.previous.classList.remove("is-hidden"),this._ui.next.classList.add("is-hidden"))):(this._ui.previous.classList.add("is-hidden"),this._ui.next.classList.add("is-hidden")))}},{key:"render",value:function(){return this.node}}]),e}();e.a=o},function(t,e,i){"use strict";e.a=function(t){return''+t.previous+'
\n'+t.next+"
"}},function(t,e,i){"use strict";var n=i(16),s=i(17),r=i(1),o=function(){function n(t,e){for(var i=0;ithis.slider.slidesToShow){for(var t=0;t<=this._count;t++){var e=document.createRange().createContextualFragment(Object(s.a)()).firstChild;e.dataset.index=t*this.slider.slidesToScroll,this._pages.push(e),this._ui.container.appendChild(e)}this._bindEvents()}}},{key:"onPageClick",value:function(t){this._supportsPassive||t.preventDefault(),this.slider.state.next=t.currentTarget.dataset.index,this.slider.show()}},{key:"onResize",value:function(){this._draw()}},{key:"refresh",value:function(){var e=this,t=void 0;(t=this.slider.options.infinite?Math.ceil(this.slider.state.length-1/this.slider.slidesToScroll):Math.ceil((this.slider.state.length-this.slider.slidesToShow)/this.slider.slidesToScroll))!==this._count&&(this._count=t,this._draw()),this._pages.forEach(function(t){t.classList.remove("is-active"),parseInt(t.dataset.index,10)===e.slider.state.next%e.slider.state.length&&t.classList.add("is-active")})}},{key:"render",value:function(){return this.node}}]),e}();e.a=a},function(t,e,i){"use strict";e.a=function(){return''}},function(t,e,i){"use strict";e.a=function(){return'
'}},function(t,e,i){"use strict";var n=i(4),s=i(1),r=function(){function n(t,e){for(var i=0;iMath.abs(this._lastTranslate.y)&&(this._supportsPassive||t.preventDefault(),t.stopPropagation())}}},{key:"onStopDrag",value:function(t){this._origin&&this._lastTranslate&&(Math.abs(this._lastTranslate.x)>.2*this.width?this._lastTranslate.x<0?this.slider.next():this.slider.previous():this.slider.show(!0)),this._origin=null,this._lastTranslate=null}}]),e}();e.a=o},function(t,e,i){"use strict";var n=i(20),s=i(21),r=function(){function n(t,e){for(var i=0;it.x?(s.x=0,this.slider.state.next=0):this.options.vertical&&Math.abs(this._position.y)>t.y&&(s.y=0,this.slider.state.next=0)),this._position.x=s.x,this._position.y=s.y,this.options.centerMode&&(this._position.x=this._position.x+this.slider.wrapperWidth/2-Object(o.e)(i)/2),"rtl"===this.slider.direction&&(this._position.x=-this._position.x,this._position.y=-this._position.y),this.slider.container.style.transform="translate3d("+this._position.x+"px, "+this._position.y+"px, 0)",n.x>t.x&&this.slider.transitioner.end()}}},{key:"onTransitionEnd",value:function(t){"translate"===this.options.effect&&(this.transitioner.isAnimating()&&t.target==this.slider.container&&this.options.infinite&&this.slider._infinite.onTransitionEnd(t),this.transitioner.end())}}]),n}();e.a=n},function(t,e,i){"use strict";e.a={initialSlide:0,slidesToScroll:1,slidesToShow:1,navigation:!0,navigationKeys:!0,navigationSwipe:!0,pagination:!0,loop:!1,infinite:!1,effect:"translate",duration:300,timing:"ease",autoplay:!1,autoplaySpeed:3e3,pauseOnHover:!0,breakpoints:[{changePoint:480,slidesToShow:1,slidesToScroll:1},{changePoint:640,slidesToShow:2,slidesToScroll:2},{changePoint:768,slidesToShow:3,slidesToScroll:3}],onReady:null,icons:{previous:'\n \n ',next:'\n \n '}}},function(t,e,i){"use strict";e.a=function(t){return''}},function(t,e,i){"use strict";e.a=function(){return'
'}}]).default});
diff --git a/docs/project_page/static/js/bulma-slider.js b/docs/project_page/static/js/bulma-slider.js
new file mode 100644
index 0000000..d7a3fea
--- /dev/null
+++ b/docs/project_page/static/js/bulma-slider.js
@@ -0,0 +1,461 @@
+(function webpackUniversalModuleDefinition(root, factory) {
+ if(typeof exports === 'object' && typeof module === 'object')
+ module.exports = factory();
+ else if(typeof define === 'function' && define.amd)
+ define([], factory);
+ else if(typeof exports === 'object')
+ exports["bulmaSlider"] = factory();
+ else
+ root["bulmaSlider"] = factory();
+})(typeof self !== 'undefined' ? self : this, function() {
+return /******/ (function(modules) { // webpackBootstrap
+/******/ // The module cache
+/******/ var installedModules = {};
+/******/
+/******/ // The require function
+/******/ function __webpack_require__(moduleId) {
+/******/
+/******/ // Check if module is in cache
+/******/ if(installedModules[moduleId]) {
+/******/ return installedModules[moduleId].exports;
+/******/ }
+/******/ // Create a new module (and put it into the cache)
+/******/ var module = installedModules[moduleId] = {
+/******/ i: moduleId,
+/******/ l: false,
+/******/ exports: {}
+/******/ };
+/******/
+/******/ // Execute the module function
+/******/ modules[moduleId].call(module.exports, module, module.exports, __webpack_require__);
+/******/
+/******/ // Flag the module as loaded
+/******/ module.l = true;
+/******/
+/******/ // Return the exports of the module
+/******/ return module.exports;
+/******/ }
+/******/
+/******/
+/******/ // expose the modules object (__webpack_modules__)
+/******/ __webpack_require__.m = modules;
+/******/
+/******/ // expose the module cache
+/******/ __webpack_require__.c = installedModules;
+/******/
+/******/ // define getter function for harmony exports
+/******/ __webpack_require__.d = function(exports, name, getter) {
+/******/ if(!__webpack_require__.o(exports, name)) {
+/******/ Object.defineProperty(exports, name, {
+/******/ configurable: false,
+/******/ enumerable: true,
+/******/ get: getter
+/******/ });
+/******/ }
+/******/ };
+/******/
+/******/ // getDefaultExport function for compatibility with non-harmony modules
+/******/ __webpack_require__.n = function(module) {
+/******/ var getter = module && module.__esModule ?
+/******/ function getDefault() { return module['default']; } :
+/******/ function getModuleExports() { return module; };
+/******/ __webpack_require__.d(getter, 'a', getter);
+/******/ return getter;
+/******/ };
+/******/
+/******/ // Object.prototype.hasOwnProperty.call
+/******/ __webpack_require__.o = function(object, property) { return Object.prototype.hasOwnProperty.call(object, property); };
+/******/
+/******/ // __webpack_public_path__
+/******/ __webpack_require__.p = "";
+/******/
+/******/ // Load entry module and return exports
+/******/ return __webpack_require__(__webpack_require__.s = 0);
+/******/ })
+/************************************************************************/
+/******/ ([
+/* 0 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+Object.defineProperty(__webpack_exports__, "__esModule", { value: true });
+/* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "isString", function() { return isString; });
+/* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__events__ = __webpack_require__(1);
+var _extends = Object.assign || function (target) { for (var i = 1; i < arguments.length; i++) { var source = arguments[i]; for (var key in source) { if (Object.prototype.hasOwnProperty.call(source, key)) { target[key] = source[key]; } } } return target; };
+
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+var _typeof = typeof Symbol === "function" && typeof Symbol.iterator === "symbol" ? function (obj) { return typeof obj; } : function (obj) { return obj && typeof Symbol === "function" && obj.constructor === Symbol && obj !== Symbol.prototype ? "symbol" : typeof obj; };
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+function _possibleConstructorReturn(self, call) { if (!self) { throw new ReferenceError("this hasn't been initialised - super() hasn't been called"); } return call && (typeof call === "object" || typeof call === "function") ? call : self; }
+
+function _inherits(subClass, superClass) { if (typeof superClass !== "function" && superClass !== null) { throw new TypeError("Super expression must either be null or a function, not " + typeof superClass); } subClass.prototype = Object.create(superClass && superClass.prototype, { constructor: { value: subClass, enumerable: false, writable: true, configurable: true } }); if (superClass) Object.setPrototypeOf ? Object.setPrototypeOf(subClass, superClass) : subClass.__proto__ = superClass; }
+
+
+
+var isString = function isString(unknown) {
+ return typeof unknown === 'string' || !!unknown && (typeof unknown === 'undefined' ? 'undefined' : _typeof(unknown)) === 'object' && Object.prototype.toString.call(unknown) === '[object String]';
+};
+
+var bulmaSlider = function (_EventEmitter) {
+ _inherits(bulmaSlider, _EventEmitter);
+
+ function bulmaSlider(selector) {
+ var options = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};
+
+ _classCallCheck(this, bulmaSlider);
+
+ var _this = _possibleConstructorReturn(this, (bulmaSlider.__proto__ || Object.getPrototypeOf(bulmaSlider)).call(this));
+
+ _this.element = typeof selector === 'string' ? document.querySelector(selector) : selector;
+ // An invalid selector or non-DOM node has been provided.
+ if (!_this.element) {
+ throw new Error('An invalid selector or non-DOM node has been provided.');
+ }
+
+ _this._clickEvents = ['click'];
+ /// Set default options and merge with instance defined
+ _this.options = _extends({}, options);
+
+ _this.onSliderInput = _this.onSliderInput.bind(_this);
+
+ _this.init();
+ return _this;
+ }
+
+ /**
+ * Initiate all DOM element containing selector
+ * @method
+ * @return {Array} Array of all slider instances
+ */
+
+
+ _createClass(bulmaSlider, [{
+ key: 'init',
+
+
+ /**
+ * Initiate plugin
+ * @method init
+ * @return {void}
+ */
+ value: function init() {
+ this._id = 'bulmaSlider' + new Date().getTime() + Math.floor(Math.random() * Math.floor(9999));
+ this.output = this._findOutputForSlider();
+
+ this._bindEvents();
+
+ if (this.output) {
+ if (this.element.classList.contains('has-output-tooltip')) {
+ // Get new output position
+ var newPosition = this._getSliderOutputPosition();
+
+ // Set output position
+ this.output.style['left'] = newPosition.position;
+ }
+ }
+
+ this.emit('bulmaslider:ready', this.element.value);
+ }
+ }, {
+ key: '_findOutputForSlider',
+ value: function _findOutputForSlider() {
+ var _this2 = this;
+
+ var result = null;
+ var outputs = document.getElementsByTagName('output') || [];
+
+ Array.from(outputs).forEach(function (output) {
+ if (output.htmlFor == _this2.element.getAttribute('id')) {
+ result = output;
+ return true;
+ }
+ });
+ return result;
+ }
+ }, {
+ key: '_getSliderOutputPosition',
+ value: function _getSliderOutputPosition() {
+ // Update output position
+ var newPlace, minValue;
+
+ var style = window.getComputedStyle(this.element, null);
+ // Measure width of range input
+ var sliderWidth = parseInt(style.getPropertyValue('width'), 10);
+
+ // Figure out placement percentage between left and right of input
+ if (!this.element.getAttribute('min')) {
+ minValue = 0;
+ } else {
+ minValue = this.element.getAttribute('min');
+ }
+ var newPoint = (this.element.value - minValue) / (this.element.getAttribute('max') - minValue);
+
+ // Prevent bubble from going beyond left or right (unsupported browsers)
+ if (newPoint < 0) {
+ newPlace = 0;
+ } else if (newPoint > 1) {
+ newPlace = sliderWidth;
+ } else {
+ newPlace = sliderWidth * newPoint;
+ }
+
+ return {
+ 'position': newPlace + 'px'
+ };
+ }
+
+ /**
+ * Bind all events
+ * @method _bindEvents
+ * @return {void}
+ */
+
+ }, {
+ key: '_bindEvents',
+ value: function _bindEvents() {
+ if (this.output) {
+ // Add event listener to update output when slider value change
+ this.element.addEventListener('input', this.onSliderInput, false);
+ }
+ }
+ }, {
+ key: 'onSliderInput',
+ value: function onSliderInput(e) {
+ e.preventDefault();
+
+ if (this.element.classList.contains('has-output-tooltip')) {
+ // Get new output position
+ var newPosition = this._getSliderOutputPosition();
+
+ // Set output position
+ this.output.style['left'] = newPosition.position;
+ }
+
+ // Check for prefix and postfix
+ var prefix = this.output.hasAttribute('data-prefix') ? this.output.getAttribute('data-prefix') : '';
+ var postfix = this.output.hasAttribute('data-postfix') ? this.output.getAttribute('data-postfix') : '';
+
+ // Update output with slider value
+ this.output.value = prefix + this.element.value + postfix;
+
+ this.emit('bulmaslider:ready', this.element.value);
+ }
+ }], [{
+ key: 'attach',
+ value: function attach() {
+ var _this3 = this;
+
+ var selector = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : 'input[type="range"].slider';
+ var options = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};
+
+ var instances = new Array();
+
+ var elements = isString(selector) ? document.querySelectorAll(selector) : Array.isArray(selector) ? selector : [selector];
+ elements.forEach(function (element) {
+ if (typeof element[_this3.constructor.name] === 'undefined') {
+ var instance = new bulmaSlider(element, options);
+ element[_this3.constructor.name] = instance;
+ instances.push(instance);
+ } else {
+ instances.push(element[_this3.constructor.name]);
+ }
+ });
+
+ return instances;
+ }
+ }]);
+
+ return bulmaSlider;
+}(__WEBPACK_IMPORTED_MODULE_0__events__["a" /* default */]);
+
+/* harmony default export */ __webpack_exports__["default"] = (bulmaSlider);
+
+/***/ }),
+/* 1 */
+/***/ (function(module, __webpack_exports__, __webpack_require__) {
+
+"use strict";
+var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }();
+
+function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } }
+
+var EventEmitter = function () {
+ function EventEmitter() {
+ var listeners = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : [];
+
+ _classCallCheck(this, EventEmitter);
+
+ this._listeners = new Map(listeners);
+ this._middlewares = new Map();
+ }
+
+ _createClass(EventEmitter, [{
+ key: "listenerCount",
+ value: function listenerCount(eventName) {
+ if (!this._listeners.has(eventName)) {
+ return 0;
+ }
+
+ var eventListeners = this._listeners.get(eventName);
+ return eventListeners.length;
+ }
+ }, {
+ key: "removeListeners",
+ value: function removeListeners() {
+ var _this = this;
+
+ var eventName = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : null;
+ var middleware = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : false;
+
+ if (eventName !== null) {
+ if (Array.isArray(eventName)) {
+ name.forEach(function (e) {
+ return _this.removeListeners(e, middleware);
+ });
+ } else {
+ this._listeners.delete(eventName);
+
+ if (middleware) {
+ this.removeMiddleware(eventName);
+ }
+ }
+ } else {
+ this._listeners = new Map();
+ }
+ }
+ }, {
+ key: "middleware",
+ value: function middleware(eventName, fn) {
+ var _this2 = this;
+
+ if (Array.isArray(eventName)) {
+ name.forEach(function (e) {
+ return _this2.middleware(e, fn);
+ });
+ } else {
+ if (!Array.isArray(this._middlewares.get(eventName))) {
+ this._middlewares.set(eventName, []);
+ }
+
+ this._middlewares.get(eventName).push(fn);
+ }
+ }
+ }, {
+ key: "removeMiddleware",
+ value: function removeMiddleware() {
+ var _this3 = this;
+
+ var eventName = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : null;
+
+ if (eventName !== null) {
+ if (Array.isArray(eventName)) {
+ name.forEach(function (e) {
+ return _this3.removeMiddleware(e);
+ });
+ } else {
+ this._middlewares.delete(eventName);
+ }
+ } else {
+ this._middlewares = new Map();
+ }
+ }
+ }, {
+ key: "on",
+ value: function on(name, callback) {
+ var _this4 = this;
+
+ var once = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : false;
+
+ if (Array.isArray(name)) {
+ name.forEach(function (e) {
+ return _this4.on(e, callback);
+ });
+ } else {
+ name = name.toString();
+ var split = name.split(/,|, | /);
+
+ if (split.length > 1) {
+ split.forEach(function (e) {
+ return _this4.on(e, callback);
+ });
+ } else {
+ if (!Array.isArray(this._listeners.get(name))) {
+ this._listeners.set(name, []);
+ }
+
+ this._listeners.get(name).push({ once: once, callback: callback });
+ }
+ }
+ }
+ }, {
+ key: "once",
+ value: function once(name, callback) {
+ this.on(name, callback, true);
+ }
+ }, {
+ key: "emit",
+ value: function emit(name, data) {
+ var _this5 = this;
+
+ var silent = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : false;
+
+ name = name.toString();
+ var listeners = this._listeners.get(name);
+ var middlewares = null;
+ var doneCount = 0;
+ var execute = silent;
+
+ if (Array.isArray(listeners)) {
+ listeners.forEach(function (listener, index) {
+ // Start Middleware checks unless we're doing a silent emit
+ if (!silent) {
+ middlewares = _this5._middlewares.get(name);
+ // Check and execute Middleware
+ if (Array.isArray(middlewares)) {
+ middlewares.forEach(function (middleware) {
+ middleware(data, function () {
+ var newData = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : null;
+
+ if (newData !== null) {
+ data = newData;
+ }
+ doneCount++;
+ }, name);
+ });
+
+ if (doneCount >= middlewares.length) {
+ execute = true;
+ }
+ } else {
+ execute = true;
+ }
+ }
+
+ // If Middleware checks have been passed, execute
+ if (execute) {
+ if (listener.once) {
+ listeners[index] = null;
+ }
+ listener.callback(data);
+ }
+ });
+
+ // Dirty way of removing used Events
+ while (listeners.indexOf(null) !== -1) {
+ listeners.splice(listeners.indexOf(null), 1);
+ }
+ }
+ }
+ }]);
+
+ return EventEmitter;
+}();
+
+/* harmony default export */ __webpack_exports__["a"] = (EventEmitter);
+
+/***/ })
+/******/ ])["default"];
+});
diff --git a/docs/project_page/static/js/bulma-slider.min.js b/docs/project_page/static/js/bulma-slider.min.js
new file mode 100644
index 0000000..0aaea8e
--- /dev/null
+++ b/docs/project_page/static/js/bulma-slider.min.js
@@ -0,0 +1 @@
+!function(t,e){"object"==typeof exports&&"object"==typeof module?module.exports=e():"function"==typeof define&&define.amd?define([],e):"object"==typeof exports?exports.bulmaSlider=e():t.bulmaSlider=e()}("undefined"!=typeof self?self:this,function(){return function(n){var r={};function i(t){if(r[t])return r[t].exports;var e=r[t]={i:t,l:!1,exports:{}};return n[t].call(e.exports,e,e.exports,i),e.l=!0,e.exports}return i.m=n,i.c=r,i.d=function(t,e,n){i.o(t,e)||Object.defineProperty(t,e,{configurable:!1,enumerable:!0,get:n})},i.n=function(t){var e=t&&t.__esModule?function(){return t.default}:function(){return t};return i.d(e,"a",e),e},i.o=function(t,e){return Object.prototype.hasOwnProperty.call(t,e)},i.p="",i(i.s=0)}([function(t,e,n){"use strict";Object.defineProperty(e,"__esModule",{value:!0}),n.d(e,"isString",function(){return l});var r=n(1),i=Object.assign||function(t){for(var e=1;e=l.length&&(s=!0)):s=!0),s&&(t.once&&(u[e]=null),t.callback(r))});-1!==u.indexOf(null);)u.splice(u.indexOf(null),1)}}]),e}();e.a=i}]).default});
diff --git a/docs/project_page/static/js/fontawesome.all.min.js b/docs/project_page/static/js/fontawesome.all.min.js
new file mode 100644
index 0000000..2f726e8
--- /dev/null
+++ b/docs/project_page/static/js/fontawesome.all.min.js
@@ -0,0 +1,5 @@
+/*!
+ * Font Awesome Free 5.15.1 by @fontawesome - https://fontawesome.com
+ * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)
+ */
+!function(){"use strict";var c={},l={};try{"undefined"!=typeof window&&(c=window),"undefined"!=typeof document&&(l=document)}catch(c){}var h=(c.navigator||{}).userAgent,z=void 0===h?"":h,a=c,v=l,m=(a.document,!!v.documentElement&&!!v.head&&"function"==typeof v.addEventListener&&v.createElement,~z.indexOf("MSIE")||z.indexOf("Trident/"),"___FONT_AWESOME___"),e=function(){try{return!0}catch(c){return!1}}();var s=a||{};s[m]||(s[m]={}),s[m].styles||(s[m].styles={}),s[m].hooks||(s[m].hooks={}),s[m].shims||(s[m].shims=[]);var t=s[m];function M(c,z){var l=(2>>0;h--;)l[h]=c[h];return l}function Ac(c){return c.classList?bc(c.classList):(c.getAttribute("class")||"").split(" ").filter(function(c){return c})}function gc(c,l){var h,z=l.split("-"),a=z[0],v=z.slice(1).join("-");return a!==c||""===v||(h=v,~T.indexOf(h))?null:v}function Sc(c){return"".concat(c).replace(/&/g,"&").replace(/"/g,""").replace(/'/g,"'").replace(//g,">")}function yc(h){return Object.keys(h||{}).reduce(function(c,l){return c+"".concat(l,": ").concat(h[l],";")},"")}function wc(c){return c.size!==Lc.size||c.x!==Lc.x||c.y!==Lc.y||c.rotate!==Lc.rotate||c.flipX||c.flipY}function Zc(c){var l=c.transform,h=c.containerWidth,z=c.iconWidth,a={transform:"translate(".concat(h/2," 256)")},v="translate(".concat(32*l.x,", ").concat(32*l.y,") "),m="scale(".concat(l.size/16*(l.flipX?-1:1),", ").concat(l.size/16*(l.flipY?-1:1),") "),e="rotate(".concat(l.rotate," 0 0)");return{outer:a,inner:{transform:"".concat(v," ").concat(m," ").concat(e)},path:{transform:"translate(".concat(z/2*-1," -256)")}}}var kc={x:0,y:0,width:"100%",height:"100%"};function xc(c){var l=!(1").concat(m.map(Jc).join(""),"").concat(l,">")}var $c=function(){};function cl(c){return"string"==typeof(c.getAttribute?c.getAttribute(cc):null)}var ll={replace:function(c){var l=c[0],h=c[1].map(function(c){return Jc(c)}).join("\n");if(l.parentNode&&l.outerHTML)l.outerHTML=h+(lc.keepOriginalSource&&"svg"!==l.tagName.toLowerCase()?"\x3c!-- ".concat(l.outerHTML," Font Awesome fontawesome.com --\x3e"):"");else if(l.parentNode){var z=document.createElement("span");l.parentNode.replaceChild(z,l),z.outerHTML=h}},nest:function(c){var l=c[0],h=c[1];if(~Ac(l).indexOf(lc.replacementClass))return ll.replace(c);var z=new RegExp("".concat(lc.familyPrefix,"-.*"));delete h[0].attributes.style,delete h[0].attributes.id;var a=h[0].attributes.class.split(" ").reduce(function(c,l){return l===lc.replacementClass||l.match(z)?c.toSvg.push(l):c.toNode.push(l),c},{toNode:[],toSvg:[]});h[0].attributes.class=a.toSvg.join(" ");var v=h.map(function(c){return Jc(c)}).join("\n");l.setAttribute("class",a.toNode.join(" ")),l.setAttribute(cc,""),l.innerHTML=v}};function hl(c){c()}function zl(h,c){var z="function"==typeof c?c:$c;if(0===h.length)z();else{var l=hl;lc.mutateApproach===y&&(l=o.requestAnimationFrame||hl),l(function(){var c=!0===lc.autoReplaceSvg?ll.replace:ll[lc.autoReplaceSvg]||ll.replace,l=_c.begin("mutate");h.map(c),l(),z()})}}var al=!1;function vl(){al=!1}var ml=null;function el(c){if(t&&lc.observeMutations){var a=c.treeCallback,v=c.nodeCallback,m=c.pseudoElementsCallback,l=c.observeMutationsRoot,h=void 0===l?C:l;ml=new t(function(c){al||bc(c).forEach(function(c){if("childList"===c.type&&0 {
+ console.log(state);
+ });
+ }
+
+ // Access to bulmaCarousel instance of an element
+ var element = document.querySelector('#my-element');
+ if (element && element.bulmaCarousel) {
+ // bulmaCarousel instance is available as element.bulmaCarousel
+ element.bulmaCarousel.on('before-show', function(state) {
+ console.log(state);
+ });
+ }
+
+ bulmaSlider.attach();
+
+})
diff --git a/docs/project_page/static/videos/compass_sim2real_improve_full.mp4 b/docs/project_page/static/videos/compass_sim2real_improve_full.mp4
new file mode 100644
index 0000000..44facf7
--- /dev/null
+++ b/docs/project_page/static/videos/compass_sim2real_improve_full.mp4
@@ -0,0 +1,3 @@
+version https://git-lfs.github.com/spec/v1
+oid sha256:7685895a877ce9e9521f088655351ae145b2eb35629fabd23adfd855afa45925
+size 47731550
diff --git a/docs/project_page/static/videos/corl_groot_fine_tune.mp4 b/docs/project_page/static/videos/corl_groot_fine_tune.mp4
new file mode 100644
index 0000000..c27049f
--- /dev/null
+++ b/docs/project_page/static/videos/corl_groot_fine_tune.mp4
@@ -0,0 +1,3 @@
+version https://git-lfs.github.com/spec/v1
+oid sha256:c105f3f17241693a12f2912b250a3ca1f12c08778ef957cc0c772f883775fdf0
+size 27797345
diff --git a/docs/project_page/static/videos/locate3d_compass_w_side.mp4 b/docs/project_page/static/videos/locate3d_compass_w_side.mp4
new file mode 100644
index 0000000..9aab822
--- /dev/null
+++ b/docs/project_page/static/videos/locate3d_compass_w_side.mp4
@@ -0,0 +1,3 @@
+version https://git-lfs.github.com/spec/v1
+oid sha256:47338fac67e2771499766c8f4a17b081635568261748853229e458d85d287f66
+size 11599706
diff --git a/docs/project_page/static/videos/merged_grid.mp4 b/docs/project_page/static/videos/merged_grid.mp4
new file mode 100644
index 0000000..492bd4e
--- /dev/null
+++ b/docs/project_page/static/videos/merged_grid.mp4
@@ -0,0 +1,3 @@
+version https://git-lfs.github.com/spec/v1
+oid sha256:b168030060890aeda253422b9ea00e4c846ea709ab4a2ecca9e0e999124c7e4f
+size 15437836
diff --git a/osmo/run_osmo.py b/osmo/run_osmo.py
new file mode 100755
index 0000000..03f51fd
--- /dev/null
+++ b/osmo/run_osmo.py
@@ -0,0 +1,270 @@
+#!/usr/bin/env python3
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+"""Submit COMPASS training/eval/record/distill workflows to OSMO.
+
+Replaces the interactive shell launcher used in the internal repo with a
+non-interactive Python CLI. Reads credentials from environment variables
+(``WANDB_API_KEY``, ``HF_TOKEN``) with an opt-in ``--prompt`` fallback.
+
+Usage:
+ # Pre-built image, env vars already exported. The X-Mobility base
+ # checkpoint and the COMPASS USDs are downloaded inside the workflow
+ # from huggingface.co/nvidia/X-Mobility and huggingface.co/nvidia/COMPASS
+ # respectively, so no --base-policy-ckpt flag is needed.
+ python osmo/run_osmo.py train \\
+ --experiment-name pilot \\
+ --wandb-project compass-rl \\
+ --image nvcr.io//compass_pilot:
+
+ # Build+push the image automatically
+ export COMPASS_OSMO_REGISTRY=nvcr.io//
+ python osmo/run_osmo.py train --experiment-name pilot --wandb-project compass-rl
+
+ # Inspect the would-be submit command without executing it
+ python osmo/run_osmo.py train --experiment-name pilot --wandb-project compass-rl \\
+ --image nvcr.io//img:tag --dry-run
+
+See https://nvlabs.github.io/COMPASS/docs/osmo.html for the full prerequisites
+and per-subcommand examples.
+"""
+
+import argparse
+import getpass
+import os
+import shlex
+import subprocess
+import sys
+import uuid
+from pathlib import Path
+
+REPO_ROOT = Path(__file__).resolve().parent.parent
+WORKFLOWS_DIR = Path(__file__).resolve().parent / "workflows"
+
+# subcommand -> (workflow YAML filename, Dockerfile path relative to REPO_ROOT)
+SUBCOMMAND_CONFIG = {
+ "train": ("rl_es_train_workflow.yaml", "docker/Dockerfile.rl"),
+ "eval": ("rl_es_eval_workflow.yaml", "docker/Dockerfile.rl"),
+ "record": ("rl_es_record_workflow.yaml", "docker/Dockerfile.rl"),
+ "distill": ("distillation_train_workflow.yaml", "docker/Dockerfile.distillation"),
+}
+
+
+def parse_args():
+ parser = argparse.ArgumentParser(
+ description="Submit a COMPASS workflow to OSMO.",
+ formatter_class=argparse.ArgumentDefaultsHelpFormatter,
+ )
+ sub = parser.add_subparsers(dest="subcommand", required=True)
+
+ def add_common(sp):
+ sp.add_argument("--experiment-name",
+ required=True,
+ help="Short identifier; used in workflow_name and image tag.")
+ sp.add_argument(
+ "--image",
+ default="",
+ help="Pre-built docker image. If empty, build+push using --registry-prefix.")
+ sp.add_argument("--registry-prefix",
+ default=os.environ.get("COMPASS_OSMO_REGISTRY", ""),
+ help="Registry prefix for build+push (e.g. nvcr.io//); "
+ "defaults to $COMPASS_OSMO_REGISTRY.")
+ sp.add_argument("--dry-run",
+ action="store_true",
+ help="Print the osmo workflow submit command without executing it.")
+ sp.add_argument("--prompt",
+ action="store_true",
+ help="Interactively prompt for missing credentials.")
+
+ train = sub.add_parser("train", help="Submit residual RL training.")
+ add_common(train)
+ train.add_argument("--wandb-project",
+ required=True,
+ help="wandb project to log into (e.g. compass-rl).")
+ train.add_argument("--resume-ckpt",
+ default="",
+ help="wandb artifact for resuming from a prior residual checkpoint.")
+ train.add_argument("--no-residual",
+ action="store_true",
+ help="Skip the residual head (use base policy only).")
+
+ evl = sub.add_parser("eval", help="Submit residual RL evaluation.")
+ add_common(evl)
+ evl.add_argument("--wandb-project",
+ required=True,
+ help="wandb project to log into (e.g. compass-rl).")
+ evl.add_argument("--checkpoint",
+ required=True,
+ help="wandb artifact for the residual checkpoint to evaluate.")
+ evl.add_argument("--distillation-ckpt",
+ default="",
+ help="wandb artifact for an optional distillation checkpoint.")
+ evl.add_argument("--no-residual",
+ action="store_true",
+ help="Evaluate without the residual head (base policy only).")
+ evl.add_argument("--embodiment", default="", help="Override the gin-config embodiment.")
+ evl.add_argument("--environment", default="", help="Override the gin-config environment.")
+
+ rec = sub.add_parser("record", help="Submit distillation-data recording.")
+ add_common(rec)
+ rec.add_argument("--dataset-name",
+ required=True,
+ help="OSMO output dataset name for recorded specialist data.")
+
+ dis = sub.add_parser("distill", help="Submit generalist distillation training.")
+ add_common(dis)
+ dis.add_argument("--wandb-project",
+ required=True,
+ help="wandb project to log into (e.g. compass-distill).")
+ dis.add_argument("--dataset-name",
+ required=True,
+ help="OSMO input dataset name (specialist rollouts).")
+ dis.add_argument("--checkpoint",
+ default="",
+ help="wandb artifact for an optional resume checkpoint.")
+ dis.add_argument("--train-config",
+ default="distillation_config",
+ help="Gin config name without .gin (default: distillation_config).")
+
+ return parser.parse_args()
+
+
+def get_credential(name: str, prompt: bool) -> str:
+ val = os.environ.get(name, "")
+ if val:
+ return val
+ if prompt:
+ return getpass.getpass(f"Enter {name}: ")
+ sys.stderr.write(f"ERROR: ${name} is not set. Either export it or pass --prompt.\n")
+ sys.exit(2)
+
+
+def build_and_push_image(experiment: str, registry_prefix: str, dockerfile: str,
+ dry_run: bool) -> str:
+ if not registry_prefix:
+ sys.stderr.write("ERROR: --image not given and --registry-prefix is empty "
+ "(also $COMPASS_OSMO_REGISTRY).\n")
+ sys.exit(2)
+ image = f"{registry_prefix.rstrip('/')}/compass_{experiment}:{uuid.uuid4().hex[:8]}"
+ cmds = [
+ ["docker", "build", "--network=host", "-t", image, "-f", dockerfile,
+ str(REPO_ROOT)],
+ ["docker", "push", image],
+ ]
+ for cmd in cmds:
+ print(f"+ {' '.join(shlex.quote(c) for c in cmd)}")
+ if not dry_run:
+ subprocess.check_call(cmd)
+ return image
+
+
+def submit_workflow(yaml_path: Path, set_args: dict, dry_run: bool) -> None:
+ cmd = ["osmo", "workflow", "submit", str(yaml_path), "--set"]
+ cmd += [f"{k}={v}" for k, v in set_args.items()]
+ print(f"+ {' '.join(shlex.quote(c) for c in cmd)}")
+ if not dry_run:
+ subprocess.check_call(cmd)
+
+
+def cmd_train(args, image: str, wandb_key: str, hf_token: str) -> None:
+ yaml_path = WORKFLOWS_DIR / SUBCOMMAND_CONFIG["train"][0]
+ set_args = {
+ "workflow_name": f"compass_rl_es_{args.experiment_name}",
+ "image": image,
+ "wandb_api_key": wandb_key,
+ "wandb_project_name": args.wandb_project,
+ "wandb_run_name": args.experiment_name,
+ "hf_token": hf_token,
+ "resume_ckpt_artifact": args.resume_ckpt,
+ "no_residual": "1" if args.no_residual else "",
+ }
+ submit_workflow(yaml_path, set_args, args.dry_run)
+
+
+def cmd_eval(args, image: str, wandb_key: str, hf_token: str) -> None:
+ yaml_path = WORKFLOWS_DIR / SUBCOMMAND_CONFIG["eval"][0]
+ set_args = {
+ "workflow_name": f"compass_rl_es_{args.experiment_name}",
+ "image": image,
+ "wandb_api_key": wandb_key,
+ "wandb_project_name": args.wandb_project,
+ "wandb_run_name": args.experiment_name,
+ "hf_token": hf_token,
+ "checkpoint_artifact": args.checkpoint,
+ "distillation_ckpt_artifact": args.distillation_ckpt,
+ "no_residual": "1" if args.no_residual else "",
+ "embodiment": args.embodiment,
+ "environment": args.environment,
+ }
+ submit_workflow(yaml_path, set_args, args.dry_run)
+
+
+def cmd_record(args, image: str, wandb_key: str, hf_token: str) -> None:
+ yaml_path = WORKFLOWS_DIR / SUBCOMMAND_CONFIG["record"][0]
+ set_args = {
+ "workflow_name": f"compass_rl_es_{args.experiment_name}",
+ "image": image,
+ "wandb_api_key": wandb_key,
+ "hf_token": hf_token,
+ "dataset_name": args.dataset_name,
+ }
+ submit_workflow(yaml_path, set_args, args.dry_run)
+
+
+def cmd_distill(args, image: str, wandb_key: str, hf_token: str) -> None:
+ del hf_token # distillation workflow doesn't need HF auth
+ yaml_path = WORKFLOWS_DIR / SUBCOMMAND_CONFIG["distill"][0]
+ set_args = {
+ "workflow_name": f"compass_distillation_{args.experiment_name}",
+ "image": image,
+ "wandb_api_key": wandb_key,
+ "wandb_project_name": args.wandb_project,
+ "wandb_run_name": args.experiment_name,
+ "dataset_name": args.dataset_name,
+ "checkpoint_artifact": args.checkpoint,
+ "train_config": args.train_config,
+ }
+ submit_workflow(yaml_path, set_args, args.dry_run)
+
+
+SUBCOMMAND_DISPATCH = {
+ "train": cmd_train,
+ "eval": cmd_eval,
+ "record": cmd_record,
+ "distill": cmd_distill,
+}
+
+
+def main() -> None:
+ args = parse_args()
+
+ wandb_key = get_credential("WANDB_API_KEY", args.prompt)
+ # HF_TOKEN is consumed by RL workflows; distillation doesn't need it.
+ hf_token = ""
+ if args.subcommand in ("train", "eval", "record"):
+ hf_token = get_credential("HF_TOKEN", args.prompt)
+
+ if args.image:
+ image = args.image
+ else:
+ dockerfile = SUBCOMMAND_CONFIG[args.subcommand][1]
+ image = build_and_push_image(args.experiment_name, args.registry_prefix, dockerfile,
+ args.dry_run)
+
+ SUBCOMMAND_DISPATCH[args.subcommand](args, image, wandb_key, hf_token)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/osmo/workflows/distillation_train_workflow.yaml b/osmo/workflows/distillation_train_workflow.yaml
new file mode 100644
index 0000000..f06df14
--- /dev/null
+++ b/osmo/workflows/distillation_train_workflow.yaml
@@ -0,0 +1,71 @@
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+version: 2
+workflow:
+ name: {{workflow_name}}
+ resources:
+ default:
+ cpu: 80
+ gpu: 4
+ memory: 800Gi
+ storage: 800Gi
+ platform: dgx-h100
+ tasks:
+ - name: train
+ image: {{image}}
+ command: ["/bin/bash"]
+ args: ["/tmp/entry.sh"]
+ files:
+ - path: /tmp/entry.sh
+ contents: |
+ set -ex
+
+ # Generate your W&B API key: https://wandb.ai/authorize
+ export WANDB_API_KEY={{wandb_api_key}}
+
+ # Create directory to store the trainning outputs.
+ OUTPUT_DIR="{{output}}/outputs"
+ mkdir -p $OUTPUT_DIR
+ mkdir -p $OUTPUT_DIR/tensorboard_logs/lightning_logs
+
+ # Get dataset folder.
+ DATASET_FOLDER_NAME=$(echo {{dataset_name}} | cut -d'/' -f2 | cut -d':' -f1)
+
+ TRAIN_CMD="python3 distillation_train.py -c configs/{{train_config}}.gin -o $OUTPUT_DIR -d {{input:0}}/$DATASET_FOLDER_NAME/data -n {{wandb_project_name}} -r {{wandb_run_name}} --logger wandb"
+
+ # Get pretrained checkpoint if provided.
+ if [ -z "{{checkpoint_artifact}}" ]; then
+ echo "No pretrained checkpoint, train from scratch."
+ else
+ echo "Downloading checkpoint: {{checkpoint_artifact}}"
+ wandb artifact get {{checkpoint_artifact}} --root ./
+ TRAIN_CMD="$TRAIN_CMD -p ./model.ckpt"
+ fi
+
+ eval $TRAIN_CMD
+
+ inputs:
+ - dataset:
+ name: {{dataset_name}}
+ outputs:
+ - dataset:
+ name: ml_nav_outputs:{{workflow_id}}
+ path: outputs
+
+default-values:
+ image: ""
+ workflow_name: compass_distillation
+ train_config: distillation_config
+ checkpoint_artifact: ""
diff --git a/osmo/workflows/rl_es_eval_workflow.yaml b/osmo/workflows/rl_es_eval_workflow.yaml
new file mode 100644
index 0000000..8d69ec0
--- /dev/null
+++ b/osmo/workflows/rl_es_eval_workflow.yaml
@@ -0,0 +1,119 @@
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+version: 2
+workflow:
+ name: {{workflow_name}}
+ resources:
+ default:
+ cpu: 20
+ gpu: 2
+ memory: 200Gi
+ platform: ovx-l40
+ storage: 400Gi
+ tasks:
+ - name: train
+ image: {{image}}
+ command: ["/bin/bash"]
+ args: ["/tmp/entry.sh"]
+ environment:
+ ACCEPT_EULA: Y
+ files:
+ - contents: |
+ # Set up environment
+ apt update
+
+ set -e
+ # Hide conflicting Vulkan files, if needed
+ if [ -e "/usr/share/vulkan" ] && [ -e "/etc/vulkan" ]; then
+ mv /usr/share/vulkan /usr/share/vulkan_hidden
+ fi
+
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m huggingface_hub.commands.huggingface_cli login --token {{hf_token}}
+
+ # Generate your W&B API key: https://wandb.ai/authorize
+ export WANDB_API_KEY={{wandb_api_key}}
+
+ # Download and unpack the COMPASS USDs from HuggingFace.
+ echo "Downloading compass_usds.zip from huggingface.co/nvidia/COMPASS"
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m huggingface_hub.commands.huggingface_cli \
+ download nvidia/COMPASS compass_usds.zip --local-dir ./
+ unzip -q -o compass_usds.zip
+ mv groot_mobility_rl_es_usds/usd ./compass/rl_env/exts/mobility_es/mobility_es/
+ rm -rf groot_mobility_rl_es_usds compass_usds.zip
+
+ # Create directory to store the training outputs.
+ OUTPUT_DIR="{{output}}/outputs"
+ mkdir -p $OUTPUT_DIR
+
+ # Download X-Mobility base-policy checkpoint from HuggingFace.
+ echo "Downloading X-Mobility checkpoint from huggingface.co/nvidia/X-Mobility"
+ mkdir -p ./base_policy
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m huggingface_hub.commands.huggingface_cli \
+ download nvidia/X-Mobility x_mobility-nav2-semantic_action_path.ckpt --local-dir ./base_policy
+ mv ./base_policy/x_mobility-nav2-semantic_action_path.ckpt ./base_policy/model.ckpt
+
+ # Download residual policy.
+ echo "Downloading residual policy checkpoint: {{checkpoint_artifact}}"
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m wandb artifact get {{checkpoint_artifact}} --root ./residual_policy/
+ EVAL_CKPT=$(ls ./residual_policy/model_*.pt | sort -V | tail -n 1)
+
+ # Download distillation policy if given.
+ DESTILLATION_CKPT_ARTIFACT={{distillation_ckpt_artifact}}
+ if [[ -n $DESTILLATION_CKPT_ARTIFACT ]]; then
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m wandb artifact get $DESTILLATION_CKPT_ARTIFACT --root ./destillation_policy/
+ DESTILLATION_CKPT=./destillation_policy/model.ckpt
+ fi
+
+ # Launch evaluation.
+ CMD="${ISAACLAB_PATH}/isaaclab.sh -p run.py -c configs/eval_config.gin --enable_cameras -o $OUTPUT_DIR -p $EVAL_CKPT -n {{wandb_project_name}} -r {{wandb_run_name}} --logger wandb --headless --video --video_interval 1"
+
+ EMBODIMENT={{embodiment}}
+ if [[ -n $EMBODIMENT ]]; then
+ CMD+=" --embodiment $EMBODIMENT"
+ fi
+
+ ENVIRONMENT={{environment}}
+ if [[ -n $ENVIRONMENT ]]; then
+ CMD+=" --environment $ENVIRONMENT"
+ fi
+
+ if [[ -n $DESTILLATION_CKPT_ARTIFACT ]]; then
+ CMD+=" -d $DESTILLATION_CKPT"
+ fi
+
+ NO_RESIDUAL={{no_residual}}
+ if [[ -z $NO_RESIDUAL ]]; then
+ CMD+=" -b ./base_policy/model.ckpt"
+ fi
+
+ echo $CMD
+ eval $CMD
+
+ path: /tmp/entry.sh
+ - contents: |
+ {
+ "launch_config": {
+ "headless": true
+ }
+ }
+ path: /tmp/config.json
+
+default-values:
+ image: ""
+ workflow_name: compass_rl_es
+ no_residual: ""
+ distillation_ckpt_artifact: ""
+ embodiment: ""
+ environment: ""
diff --git a/osmo/workflows/rl_es_record_workflow.yaml b/osmo/workflows/rl_es_record_workflow.yaml
new file mode 100644
index 0000000..605fd05
--- /dev/null
+++ b/osmo/workflows/rl_es_record_workflow.yaml
@@ -0,0 +1,91 @@
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+version: 2
+workflow:
+ name: {{workflow_name}}
+ resources:
+ default:
+ cpu: 20
+ gpu: 2
+ memory: 200Gi
+ platform: ovx-l40
+ storage: 1200Gi
+ tasks:
+ - name: train
+ image: {{image}}
+ command: ["/bin/bash"]
+ args: ["/tmp/entry.sh"]
+ environment:
+ ACCEPT_EULA: Y
+ files:
+ - contents: |
+ # Set up environment
+ apt update
+
+ set -e
+ # Hide conflicting Vulkan files, if needed
+ if [ -e "/usr/share/vulkan" ] && [ -e "/etc/vulkan" ]; then
+ mv /usr/share/vulkan /usr/share/vulkan_hidden
+ fi
+
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m huggingface_hub.commands.huggingface_cli login --token {{hf_token}}
+
+ # Generate your W&B API key: https://wandb.ai/authorize
+ export WANDB_API_KEY={{wandb_api_key}}
+
+ # Download and unpack the COMPASS USDs from HuggingFace.
+ echo "Downloading compass_usds.zip from huggingface.co/nvidia/COMPASS"
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m huggingface_hub.commands.huggingface_cli \
+ download nvidia/COMPASS compass_usds.zip --local-dir ./
+ unzip -q -o compass_usds.zip
+ mv groot_mobility_rl_es_usds/usd ./compass/rl_env/exts/mobility_es/mobility_es/
+ rm -rf groot_mobility_rl_es_usds compass_usds.zip
+
+ # Create directory to store the training outputs.
+ OUTPUT_DIR="{{output}}/outputs"
+ mkdir -p $OUTPUT_DIR
+
+ # Download X-Mobility base-policy checkpoint from HuggingFace.
+ echo "Downloading X-Mobility checkpoint from huggingface.co/nvidia/X-Mobility"
+ mkdir -p ./base_policy
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m huggingface_hub.commands.huggingface_cli \
+ download nvidia/X-Mobility x_mobility-nav2-semantic_action_path.ckpt --local-dir ./base_policy
+ mv ./base_policy/x_mobility-nav2-semantic_action_path.ckpt ./base_policy/model.ckpt
+
+ # Launch recording.
+ CMD="${ISAACLAB_PATH}/isaaclab.sh -p record.py -c configs/distillation_dataset_config.yaml -o $OUTPUT_DIR -b ./base_policy/model.ckpt --dataset-name {{dataset_name}}"
+
+ echo $CMD
+ eval $CMD
+
+ path: /tmp/entry.sh
+ - contents: |
+ {
+ "launch_config": {
+ "headless": true
+ }
+ }
+ path: /tmp/config.json
+
+ outputs:
+ - dataset:
+ name: {{dataset_name}}:{{workflow_id}}
+ path: outputs/{{dataset_name}}/data
+
+
+default-values:
+ image: ""
+ workflow_name: compass_rl_es
+ dataset_name: compass_rl_es_experts
diff --git a/osmo/workflows/rl_es_train_workflow.yaml b/osmo/workflows/rl_es_train_workflow.yaml
new file mode 100644
index 0000000..b905759
--- /dev/null
+++ b/osmo/workflows/rl_es_train_workflow.yaml
@@ -0,0 +1,113 @@
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+version: 2
+workflow:
+ name: {{workflow_name}}
+ resources:
+ default:
+ cpu: 20
+ gpu: 2
+ memory: 200Gi
+ platform: ovx-l40
+ storage: 400Gi
+ tasks:
+ - name: train
+ image: {{image}}
+ command: ["/bin/bash"]
+ args: ["/tmp/entry.sh"]
+ environment:
+ ACCEPT_EULA: Y
+ files:
+ - contents: |
+ # Set up environment
+ apt update
+
+ set -e
+ # Hide conflicting Vulkan files, if needed
+ if [ -e "/usr/share/vulkan" ] && [ -e "/etc/vulkan" ]; then
+ mv /usr/share/vulkan /usr/share/vulkan_hidden
+ fi
+
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m huggingface_hub.commands.huggingface_cli login --token {{hf_token}}
+
+ # Generate your W&B API key: https://wandb.ai/authorize
+ export WANDB_API_KEY={{wandb_api_key}}
+
+ # Download and unpack the COMPASS USDs from HuggingFace.
+ echo "Downloading compass_usds.zip from huggingface.co/nvidia/COMPASS"
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m huggingface_hub.commands.huggingface_cli \
+ download nvidia/COMPASS compass_usds.zip --local-dir ./
+ unzip -q -o compass_usds.zip
+ mv groot_mobility_rl_es_usds/usd ./compass/rl_env/exts/mobility_es/mobility_es/
+ rm -rf groot_mobility_rl_es_usds compass_usds.zip
+
+ # Create directory to store the training outputs.
+ OUTPUT_DIR="{{output}}/outputs"
+ mkdir -p $OUTPUT_DIR
+
+ # Download X-Mobility base-policy checkpoint from HuggingFace.
+ echo "Downloading X-Mobility checkpoint from huggingface.co/nvidia/X-Mobility"
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m huggingface_hub.commands.huggingface_cli \
+ download nvidia/X-Mobility x_mobility-nav2-semantic_action_path.ckpt --local-dir ./
+ mv x_mobility-nav2-semantic_action_path.ckpt model.ckpt
+
+ # Download resume checkpoint if provided.
+ RESUME_CKPT_ARTIFACT={{resume_ckpt_artifact}}
+ if [[ -n $RESUME_CKPT_ARTIFACT ]]; then
+ echo "Downloading resume checkpoint: $RESUME_CKPT_ARTIFACT"
+ ${ISAACLAB_PATH}/isaaclab.sh -p -m wandb artifact get $RESUME_CKPT_ARTIFACT --root ./resume_ckpt/
+ RESUME_CKPT=$(ls ./resume_ckpt/model_*.pt | sort -V | tail -n 1)
+ fi
+
+ # Launch training.
+ TRAIN_CMD="${ISAACLAB_PATH}/isaaclab.sh -p run.py -c configs/train_config.gin --enable_cameras -o $OUTPUT_DIR -n {{wandb_project_name}} -r {{wandb_run_name}} --logger wandb --headless --video"
+
+ NO_RESIDUAL={{no_residual}}
+ if [[ -z $NO_RESIDUAL ]]; then
+ TRAIN_CMD+=" -b ./model.ckpt"
+ fi
+
+ if [[ -n $RESUME_CKPT_ARTIFACT ]]; then
+ TRAIN_CMD+=" -p $RESUME_CKPT"
+ fi
+
+ echo $TRAIN_CMD
+ eval $TRAIN_CMD
+
+ # Launch evaluation of last checkpoint.
+ eval_ckpt=$(ls $OUTPUT_DIR/model_*.pt | sort -V | tail -n 1)
+ ckpt_name=$(basename "$eval_ckpt")
+ EVAL_CMD="${ISAACLAB_PATH}/isaaclab.sh -p run.py -c configs/eval_config.gin --enable_cameras -o $OUTPUT_DIR -p $eval_ckpt -n {{wandb_project_name}} -r eval_{{wandb_run_name}}_$ckpt_name --logger wandb --headless --video --video_interval 1"
+ if [[ -z $NO_RESIDUAL ]]; then
+ EVAL_CMD+=" -b ./model.ckpt"
+ fi
+
+ echo $EVAL_CMD
+ eval $EVAL_CMD
+
+ path: /tmp/entry.sh
+ - contents: |
+ {
+ "launch_config": {
+ "headless": true
+ }
+ }
+ path: /tmp/config.json
+
+default-values:
+ image: ""
+ workflow_name: compass_rl_es
+ no_residual: ""
+ resume_ckpt_artifact: ""
diff --git a/release_tracker.md b/release_tracker.md
new file mode 100644
index 0000000..0e6214a
--- /dev/null
+++ b/release_tracker.md
@@ -0,0 +1,245 @@
+# COMPASS 2.0 Release Tracker
+
+> Working tracker for the next release. Distilled into `CHANGELOG.md` at ship time; do not duplicate that history here.
+
+**Target version:** `2.0.0` (TBD — confirm vs `1.6.0`; major bump assumed because of Isaac Lab 3.0 break)
+**Target date:** TBD
+**Release manager:** @liuw
+**Status legend:** ⬜ not started · 🟡 in progress · 🟢 done · 🔴 blocked · ⚪ deferred
+
+## Summary
+
+| # | Workstream | Priority | Status | Owner |
+|---|-----------|----------|--------|-------|
+| 1 | OSMO code migration (training runnable on OSMO) | P0 | ⬜ | TBD |
+| 2 & 3 | Isaac Lab 2.1 → 3.0+ upgrade **+** NuRec official support (single branch) | P0 | ⬜ | @samc + @liuw |
+| 4 | Agentic skills for automatic model training (also enables SAGE) | P1 | ⬜ | TBD |
+| 5 | Auto OMap generation from USDs | P1 | 🟡 | @liuw |
+| 6 | GitHub Pages docs site (X-Mobility → COMPASS) | P1 | 🟡 | @liuw |
+| 7 | Docker-as-venv dev environment (`docker/run.sh` + `docker/activate`) | P1 | 🟡 | @liuw |
+| 8 | Pre-release leak audit + sanitization | P0 | 🟡 | @liuw |
+| 9 | CI/CD setup + dependency pinning | P1 | 🟡 | @liuw |
+| — | No-regression benchmark (gate) | P0 | ⬜ | TBD |
+| — | CHANGELOG + version bump + tag | P0 | ⬜ | @liuw |
+
+## Dependencies
+
+```
+#2&3 cherry-pick from samc/support_nurec_assets_isaaclab_3.0:
+ PR-1 (Isaac Lab 3.0 migration) ──► PR-2 (NuRec assets + occupancy_map) ──┐
+ │
+OSMO (#1) ──────────────────────────────────────────────────────────────────┤
+Agentic skills (#4) ────────────────────────────────────────────────────────┼──► Benchmark ──► Release
+Auto-OMap (#5) ─────────────────────────────────────────────────────────────┘
+Docs (#6), Dev environment (#7) — parallel; finalized before tag
+PR-FOLLOWUP (multi-cam recorder + video upload + debug images) — post-release, outside critical path
+```
+
+**SAGE note:** SAGE training is enabled by the agentic skills (#4). The only SAGE-specific gap is auto OMap generation (#5), which makes SAGE-driven training smoother. No standalone "SAGE integration" workstream.
+
+---
+
+## 1. OSMO code migration — P0
+
+Bring OSMO training-launch code from internal `gitlab-master.nvidia.com/ml_nav/compass` to public `NVlabs/COMPASS`. Existing public repo already references OSMO dataset names (`record.py:147` `--dataset-name`).
+
+- [ ] Inventory OSMO-specific files in internal repo (launch scripts, configs, manifests)
+- [ ] Sanitize for public release (strip internal paths, secrets, unsupported clusters)
+- [ ] Decide landing directory (`scripts/osmo/` or `osmo/`)
+- [ ] Port docs / README section explaining OSMO submission flow
+- [ ] Smoke test: launch one specialist training run end-to-end on OSMO
+- [ ] Smoke test: launch one distillation run end-to-end on OSMO
+- [ ] PR:
+
+**Internal source:** `gitlab-master.nvidia.com/ml_nav/compass` — OSMO directory TBD
+
+## 2 & 3. Isaac Lab 3.0+ upgrade **+** NuRec official support — P0
+
+The source branch `origin/samc/support_nurec_assets_isaaclab_3.0` (5 commits, ~1818 LOC) bundles unrelated work and **will not be merged whole**. We cherry-pick into two PRs for this release; the rest defers to a follow-up PR after the release tag.
+
+### Branch decomposition (cherry-pick plan)
+
+| Bucket | What it is | LOC | Lands in |
+|--------|-----------|-----|----------|
+| **A** | Isaac Lab 3.0 API migration: env_cfg signatures, ActionTerm import path, Warp interop (`wp.to_torch()`), PhysxCfg restructure, separate `write_root_pose_to_sim_index` / `write_root_velocity_to_sim_index`, `num_rerenders_on_reset`, **global quaternion convention flip in `environments.py` (wxyz → xyzw)**. Touches env_cfg.py, MDP terms, robots, scene_assets, *_env_cfg.py, pyproject.toml, Dockerfile.rl. | ~150 | **PR-1** |
+| **B** | NuRec real2sim asset support: 41-line `environments.py` block (NuRec USD path + occupancy entry + `nova_carter_galileo_nurec` cfg), `configs/{train,eval}_config_real2sim.gin`, `run.py` registration. | ~95 | **PR-2** |
+| **C** | New file `compass/utils/multi_camera_video_recorder.py` (689 LOC). General-purpose `gym.Wrapper` recording viewport + camera side-by-side. | 689 | Deferred |
+| **D** | `residual_ppo_trainer.py` video upload dedup (`_find_video_files`, rewritten `_upload_video`, dedup sets). Pairs with C. | ~140 | Deferred |
+| **E** | `occupancy_map.py` 429-line refactor: origin-convention support (top-left vs ROS bottom-left) **+** `precompute_valid_poses()` that buffers obstacles via scipy.ndimage and caches valid start/goal locations. **NOT USD-derived** — independent of #5. | 429 | **PR-2** (origin convention is required to parse NuRec's occupancy entry; precompute rides along, gated by opt-in flag) |
+| **F** | Browser-compatible video: ffmpeg H.264 re-encode + `+faststart`, libx264 preset/crf tuning. Commits `ede049d` and `c34645f`. | ~80 | Deferred |
+| **G** | Debug images / logger: `compass/utils/logger.py:74-91` adds `log_image()`; trainer `_save_debug_images()` + `_create_image_grid()` write PNG grids of obs every N iters. Commit `bafac90`. | ~190 | Deferred |
+| **H** | Cleanups (run.py duplicated lines 244-246/247-250; `EnvSceneAssetCfgMap['nova_carter-galileo']` overrides existing `warehouse_multi_rack` mapping). | small | **PR-2** |
+
+### PR-1 — Isaac Lab 3.0 API migration (Bucket A) — P0
+
+Foundation. No new features; pure 2.1 → 3.0 compat. Off `main`.
+
+- [ ] Extract A-only hunks from commit `3e6dcd9`
+- [ ] Survey Isaac Lab 2.1 → 3.0 release notes / migration guide; confirm branch covers them
+- [ ] Update version pins: README badges, `docs/handbook/extending.md` (bare-metal install section)
+- [ ] Update `docker/Dockerfile.distillation` base image if needed (`Dockerfile.rl` already on branch)
+- [ ] **Reviewer spot-check**: quaternion convention flip across all rows of `environments.py` (wxyz → xyzw) — confirm no Y-up vs Z-up assumption breaks
+- [ ] Re-validate USD assets load under 3.0 (`compass/rl_env/exts/mobility_es/mobility_es/usd/`)
+- [ ] Smoke test: one short training per supported embodiment (H1, Carter, Spot, G1, Digit)
+- [ ] PR:
+
+### PR-2 — NuRec real2sim assets + occupancy_map plumbing (Buckets B + E + H fixes) — P0
+
+Off PR-1. NuRec asset support, the `occupancy_map.py` refactor it depends on, and cleanups in the same files.
+
+- [ ] Cherry-pick `environments.py` NuRec block + `configs/train_config_real2sim.gin` + `configs/eval_config_real2sim.gin`
+- [ ] Cherry-pick `compass/rl_env/exts/mobility_es/mobility_es/utils/occupancy_map.py` refactor (origin convention + `precompute_valid_poses`)
+- [ ] **Cleanup**: collapse duplicated `run.py` lines 244-246 / 247-250
+- [ ] **Cleanup**: register `'nova_carter-galileo'` as a *new* `EnvSceneAssetCfgMap` key alongside the existing `warehouse_multi_rack` (do not overwrite — fixes commit `86f9664`)
+- [ ] Add NuRec asset section to `docs/handbook/extending.md` (or a new handbook page if the section grows)
+- [ ] Add NuRec entry under "External assets that must be downloaded manually" in `README.md`
+- [ ] Smoke test: training run with NuRec asset
+- [ ] Smoke test: confirm a non-NuRec run on a `warehouse_multi_rack` scene still works (regression check)
+- [ ] PR:
+
+### Deferred to follow-up PR (Buckets C + F + D + G)
+
+Not on the release critical path. Ship after the release tag as one coherent observability PR.
+
+- Multi-camera video recorder (`compass/utils/multi_camera_video_recorder.py`) — **C**
+- Browser-compat video re-encoding (ffmpeg H.264 + faststart) — **F**
+- Trainer video upload dedup (viewport + combined uploads) — **D**
+- Debug image grid logging (`logger.log_image()` + `_save_debug_images()`) — **G**
+
+Rationale: C + F record videos to disk; without D's wandb upload plumbing they're half-baked. G is the same observability stack. All four ship together post-release. Also revisit `bafac90`'s `debug_image_interval` default at that time so output dirs don't fill up.
+
+**Branch:** `origin/samc/support_nurec_assets_isaaclab_3.0` (5 commits, ~1818 LOC)
+**Predecessor branch:** `origin/samc/support_nurec_assets_isaaclab_2.3.1` (kept for reference; not merged)
+**Owners:** @samc (NuRec) + @liuw (Isaac Lab integration review)
+
+## 4. Agentic skills for automatic model training — P1
+
+Migrate the agentic-skills tooling that automates training-loop execution from the internal repo. **This already enables SAGE training** — no separate SAGE workstream is needed; the skills cover it. (Scope to be sharpened — do these run as Claude Code skills, as a CLI orchestrator, or as OSMO-side jobs?)
+
+- [ ] Identify scope: skill manifests vs. orchestrator code vs. both
+- [ ] Decide landing directory (`.claude/skills/`? `agentic/`?)
+- [ ] Sanitize for public release
+- [ ] Hook into training entry points (`run.py`, `distillation_train.py`)
+- [ ] Document trigger commands and expected behavior
+- [ ] Demo: end-to-end automated specialist training using one skill
+- [ ] Demo: SAGE-driven training using the migrated skills
+- [ ] PR:
+
+**Internal source:** `gitlab-master.nvidia.com/ml_nav/compass` — agentic-skills directory TBD
+
+## 5. Auto OMap generation from USDs — P1
+
+Replace the manual occupancy-map authoring step with a USD-derived generator so SAGE-driven training (and any new scene) can ramp up without hand-tuned omaps. The auto-gen flow is documented at https://nvlabs.github.io/COMPASS/docs/omap.html and consumed by `compass/rl_env/exts/mobility_es/mobility_es/utils/occupancy_map.py`.
+
+> **Relationship with #2&3:** Complementary, not overlapping. The NuRec branch's `occupancy_map.py` change is precomputation + origin convention (loads pre-baked YAML faster), not USD generation. #5 is genuinely separate work that produces the YAML automatically from a USD.
+
+- [x] Add CLI/script `scripts/generate_omap_from_usd.py` that produces the omap PNG+YAML directly from a USD scene (wraps `isaacsim.asset.gen.omap.bindings._omap.Generator`)
+- [x] Update `compass/rl_env/exts/mobility_es/mobility_es/utils/occupancy_map.py` so a scene without an `OMAP_PATHS` entry auto-discovers `/omap/occupancy_map.yaml` (no breaking change to existing entries)
+- [x] Update `compass/rl_env/README.md` and `.claude/skills/compass/SKILL.md` to point at the auto-generation flow
+- [x] Verify generation + collision-free sampling on representative USDs:
+ - `office.usd` — ✅ 200/200 free samples in unoccupied regions
+ - `combined_simple_warehouse/combined.usd` (default training scene) — ✅ 253/300 free samples; visually free dots avoid obstacles
+ - `sample_small_footprint_one_rack_obst_sdg.usd` — ✅ 145/300 free samples; same
+- [ ] Regenerate OMaps for all bundled scenes (optional follow-up; current loader auto-discovers when no `OMAP_PATHS` entry)
+- [ ] Measure training-throughput delta vs. manual OMaps; record in benchmark report
+- [ ] PR:
+
+**Branch:** `liuw/auto_omap_from_usd` (off `liuw/agentic_skills_migration`)
+**Key fix:** wait on `omni.usd.get_context().get_stage_loading_status()` until `to_load == 0` before invoking `generate2d()` — without this, kit crashes on USDs with external references (e.g. `combined_simple_warehouse` referencing `galileo_lab.usd`) when the omap generator queries fabric for prims whose references are still resolving. Mirrors the pattern Isaac Sim's own `isaacsim.asset.gen.omap` tests use.
+
+## 6. GitHub Pages docs site — P1
+
+End-to-end docs site auto-deployed from `main/docs/` via GitHub Actions. Academic landing stays at `nvlabs.github.io/COMPASS/`; new **Sphinx handbook with the NVIDIA theme** (matching `agentic_model_training/docs/` and the rest of NVIDIA OSS) serves at `nvlabs.github.io/COMPASS/docs/`. Replaces the hand-served `gh_page` branch.
+
+- [x] Stack decided: **Sphinx 7.x + nvidia-sphinx-theme + myst-parser** (markdown survives; matches NVIDIA house style)
+- [x] Source location: `main/docs/` (so doc edits go through normal PRs); `gh_page` left as a frozen archive
+- [x] URL layout: academic at `/`, handbook at `/docs/`
+- [x] Migrate `gh_page` → `docs/project_page/` (264 files; mp4/png LFS-tracked, rest as Git blobs) — landed in commit `305c3a1`
+- [x] Add `docs/handbook/{conf.py, Makefile, requirements.txt, _static/, docs/}` with `{toctree}` nav (Installation / Workflows / Deployment / Reference)
+- [x] Transclude existing READMEs (Docker, OSMO, ROS2, mobility_es, CONTRIBUTING) via MyST `` ```{include} `` directives; no copy-paste of content
+- [x] Add Documentation CTA on academic landing (`docs/project_page/index.html` → `./docs/`)
+- [x] Wire `.github/workflows/docs.yml` (`make html` / `sphinx-build -W`, copy academic landing to root, deploy via `actions/deploy-pages@v4`)
+- [ ] Local build verification: `make html` runs clean; all 16 handbook pages render; both `/` and `/docs/` serve correctly from `_site/`
+- [ ] Repo settings: **Settings → Pages → Source = "GitHub Actions"** (one-time owner action; documented in PR description)
+- [ ] Push to main + watch first deploy succeed
+- [ ] PR:
+
+**Branch:** `liuw/docs_site` (off `liuw/dev_environment`, latest in the stack).
+**Status:** files written; local Sphinx build pending; Pages source switch + push pending.
+
+## 7. Docker-as-venv dev environment — P1
+
+Quality-of-life: cut first-time UX from "30–60 min, 6 manual steps" to **"3 commands, ~3 min"**, and make the steady-state dev loop feel like a Python venv (host-side editor, host-side shell, but every `python`/`pip`/`tensorboard` invocation transparently routed through the container via `source ./docker/activate`). Reuses `docker/Dockerfile.rl` (single image, +5 lines). Detailed plan at [`dev_env_plan.md`](dev_env_plan.md).
+
+- [x] Add `docker/run.sh` (subcommands: build / assets / up / down / exec / shell / status)
+- [x] Add `docker/activate` (sourceable — venv-like; shim PATH for python/pip/tensorboard/etc., CWD translation, deactivate)
+- [x] Add `docker/prepare_assets.sh` (USDs + X-Mobility ckpt → `./assets/`, cache-aware)
+- [x] Add `docker/README.md` (subcommand reference, multi-checkout / multi-GPU notes, troubleshooting)
+- [x] Modify `docker/Dockerfile.rl`: install COMPASS at `/workspace/COMPASS` (so `/workspace/isaaclab` survives the bind-mount); add a `python`/`python3` wrapper that exec's Isaac Sim's bundled `python.sh`
+- [x] Update `.dockerignore` (`./assets/`, `./.cache/`, `./.git/`) and `.gitignore` (`/assets/`, `/.cache/`)
+- [x] Update root `README.md` to lead with the Docker quick-start; bare-metal moved under "Manual install"
+- [ ] Verify: `./docker/run.sh build && ./docker/run.sh assets && source ./docker/activate && python run.py … --num_envs 1 --headless` reaches first PPO iteration
+- [ ] Verify: `git commit -s` from an activated shell triggers pre-commit through the shim and signs cleanly
+- [ ] Verify: `osmo/run_osmo.py train` still works against the same image (regression)
+- [ ] PR:
+
+**Branch:** `liuw/dev_environment` (off `liuw/auto_omap_from_usd`, latest in the stack).
+**Status:** files written; verification + commit pending.
+
+## 8. Pre-release leak audit + sanitization — P0
+
+Scrub all internal-only references before tagging 2.0. Inventory in the
+planning round; the meaningful work is in the OSMO entry script.
+
+- [x] OSMO workflows: replace `groot_mobility_rl_es_usds` dataset input with HF download `nvidia/COMPASS / compass_usds.zip` (3 YAMLs)
+- [x] OSMO workflows: replace `wandb artifact get …base_policy_ckpt…` with HF download `nvidia/X-Mobility / x_mobility-nav2-semantic_action_path.ckpt` (3 YAMLs)
+- [x] `osmo/run_osmo.py`: drop `nvidia-isaac` wandb-project defaults (`compass_rl_enhance`, `afm_train`); make `--wandb-project` required; drop `--base-policy-ckpt` flag (workflow now hardcodes the HF source)
+- [x] Update `docs/handbook/osmo.md` to reflect HF-sourced assets + required `--wandb-project`
+- [ ] `ros2_deployment/compass_navigator/setup.py`: review maintainer attribution (flag for @liuw; team alias preferred)
+- [ ] OSMO smoke test: resubmit `compass_rl_es_g1_official` with the rebuilt image; confirm HF download steps succeed and training reaches first PPO iter
+- [ ] Repo-wide grep gate: `grep -rnE "groot_mobility_rl_es_usds|nvidia-isaac/|afm_train" --include='*.py' --include='*.sh' --include='*.yaml' --include='*.gin' --include='*.html' .` returns no live-source hits
+- [ ] Distill `release_tracker.md` + `dev_env_plan.md` into `CHANGELOG.md` and remove from the repo at tag time (existing gate row)
+- [ ] PR:
+
+**Branch:** `liuw/sanitize_for_public` (off `liuw/docs_site`, latest in the stack).
+
+## 9. CI/CD setup + dependency pinning — P1
+
+Bring the public repo up to a "first-line" CI posture before tagging:
+
+- [x] Add `.github/workflows/pre-commit.yml` (yapf / pylint / nbstripout / clang-format / large-files / trailing-whitespace / EOF / requirements-txt-fixer)
+- [x] Pin `requirements.txt` to versions verified inside `compass-rl:latest` (the image used for the just-passed OSMO smoke). 17 unpinned → 17 pinned; `diffusers==0.29.2` was already pinned.
+- [ ] First run of the workflow on PR-9: confirm pre-commit passes `--all-files` against the current branch. If legacy violations surface, fix in a follow-up commit on the same branch.
+- [ ] Decide later whether to add a Sphinx-handbook `linkcheck` job (out of scope for now; tracked under #6 docs).
+- [ ] PR:
+
+**Branch:** `liuw/ci_setup` (off `liuw/sanitize_for_public`, latest in the stack).
+
+## Pre-release gates
+
+- [ ] **No-regression benchmark** — run all supported embodiments × scenes on `main` post-merge, compare success rate / SPL / collision rate to 1.5.0 baselines, post results in this tracker
+- [ ] All P0 items 🟢
+- [ ] CHANGELOG.md `[2.0.0]` entry drafted (Added / Changed / Fixed / Removed)
+- [ ] Version bump committed
+- [ ] X-Mobility wheel updated if needed
+- [ ] Pre-commit clean: `pre-commit run --all-files`
+- [ ] Docs site builds without warnings
+- [ ] Release notes drafted
+
+## Release
+
+- [ ] Tag `v2.0.0` and push
+- [ ] GitHub Release published with notes
+- [ ] HuggingFace assets (USDs, checkpoints) updated/uploaded if changed
+- [ ] Internal announcement posted
+
+## Out of scope / deferred
+
+_Move items here with a one-line reason once cut. Empty at planning start._
+
+## Notes
+
+- DCO sign-off (`git commit -s`) is required for every commit — see `CONTRIBUTING.md`
+- Internal repo: `gitlab-master.nvidia.com/ml_nav/compass`
+- Public repo: `github.com/NVlabs/COMPASS`
+- Existing `gh_page` branch hosts the academic project page (Bulma static site) — do not confuse with the new docs site
diff --git a/requirements.txt b/requirements.txt
index d48bfc8..cc93b69 100644
--- a/requirements.txt
+++ b/requirements.txt
@@ -1,18 +1,18 @@
diffusers==0.29.2
-einops
-gin-config
-h5py
-matplotlib
-moviepy
-msgpack
-numpy
-onnx
-onnxruntime-gpu
-pandas
-pytorch-lightning
-timm
-torcheval
-transformers
-wandb
-wheel
-zmq
+einops==0.8.2
+gin-config==0.5.0
+h5py==3.16.0
+matplotlib==3.10.8
+moviepy==2.2.1
+msgpack==1.1.2
+numpy==1.26.4
+onnx==1.20.1
+onnxruntime-gpu==1.25.1
+pandas==3.0.1
+pytorch-lightning==2.6.1
+timm==1.0.26
+torcheval==0.0.7
+transformers==4.57.6
+wandb==0.25.1
+wheel==0.47.0
+zmq==0.0.0
diff --git a/ros2_deployment/ISAACSIM_README.md b/ros2_deployment/ISAACSIM_README.md
deleted file mode 100644
index 5343041..0000000
--- a/ros2_deployment/ISAACSIM_README.md
+++ /dev/null
@@ -1,236 +0,0 @@
-# Compass Navigator ROS2 Deployment in ISAAC SIM
-
-## Overview
-
-**Standalone ROS2 deployment** for Compass Navigator with Isaac Sim integration.
-
-### What's Included
-
-**`compass_container.py`** - Container management script that:
-- Manages **two separate Docker containers**: Compass Navigator and Isaac Sim
-- Controls container lifecycle: start, stop, enter, and monitor both containers
-- Handles TensorRT model conversion automatically
-- Launches Isaac Sim container with ROS2 bridge
-- Provides easy container entry and debugging
-
-**`Dockerfile.deploy`** - Creates a container with:
-- ROS2 Humble + CUDA 11.8 + TensorRT
-- Compass Navigator package and dependencies
-- Non-root user setup for development
-- Proper FastDDS configuration for inter-container communication
-
-## Quick Setup & Run
-
-### 1. Build the Container
-```bash
-export COMPASS_PATH=/path/to/compass
-export HUGGINGFACE_TOKEN=hf_your_token_here
-cd $COMPASS_PATH/ros2_deployment
-./build_compass_docker.sh
-```
-
-### 2. Launch Isaac Sim (Terminal 1)
-```bash
-./compass_container.py launch_isaac_sim
-```
-- **In Isaac Sim GUI:** Go to `Windows` → `Examples` → `Robotics Examples` → `ROS2` → `Navigation`
-- **Load a robot scene** (e.g., Carter)
-- **Press Play (▶️)** to start simulation
-
-### 3. Launch Compass Navigator with GUI (Terminal 2)
-```bash
-./compass_container.py --rviz launch_nav
-```
-- Automatically converts ONNX to TensorRT (first time only)
-- Builds ROS2 workspace and launches navigator
-- Opens RViz2 with robot visualization
-
-### 3.b Navigate the Robot
-- **In RViz2:** Use the **2D Nav Goal** tool in the toolbar
-- **Click anywhere on the map** to set navigation targets
-- **Robot navigates autonomously** using AI-powered path planning
-
-## 4. Alternative: Headless Mode (No GUI)
-
-### 4.a Launch Compass Navigator
-```bash
-./compass_container.py launch_nav
-```
-- Runs navigator without RViz2 GUI (saves resources)
-- All ROS2 topics still available for external tools
-
-### 4.b Send Navigation Goals
-```bash
-# Enter the compass container
-./compass_container.py enter
-
-# Inside container, publish a goal pose
-ros2 topic pub --once /goal_pose geometry_msgs/msg/PoseStamped "
-header:
- frame_id: 'odom'
-pose:
- position:
- x: 2.0
- y: 0.0
- z: 0.0
- orientation:
- x: 0.0
- y: 0.0
- z: 0.0
- w: 1.0
-"
-
-# Monitor navigation progress
-ros2 topic echo /cmd_vel --once # Check robot commands
-ros2 topic echo /chassis/odom --once # Check robot position
-or visualize in Isaac-Sim
-```
-
-## Container Commands
-
-```bash
-# Compass Navigator container lifecycle
-./compass_container.py start # Start compass container headless (background)
-./compass_container.py --rviz start # Start compass container with RViz GUI
-./compass_container.py enter # Enter running compass container
-./compass_container.py stop # Stop compass container
-./compass_container.py logs # View compass container logs
-./compass_container.py status # Check compass container status
-
-# Isaac Sim container (separate)
-./compass_container.py launch_isaac_sim # Start Isaac Sim container (interactive)
-
-# Combined launch options
-./compass_container.py launch_nav # Quick headless launch
-./compass_container.py --rviz launch_nav # Quick launch with RViz GUI
-./compass_container.py launch_nav --force-trt-conversion # Rebuild TensorRT engine (headless)
-./compass_container.py --rviz launch_nav --force-trt-conversion # Rebuild engine + GUI
-
-# Development
-./compass_container.py enter # Enter headless container
-./compass_container.py --rviz enter # Enter container with RViz support
-
-# Troubleshooting
-./compass_container.py debug_network_setup # Debug ROS2 network setup
-```
-
-## Container Lifecycle
-
-### Compass Navigator Container
-- **Starts in detached mode** (runs in background)
-- **Persists after `launch_nav` command exits** - container keeps running
-- **Runs ROS2 nodes and RViz2** inside the container
-- **Must be manually stopped** with `./compass_container.py stop`
-
-```bash
-./compass_container.py launch_nav
-# Command exits, but container + ROS2 nodes continue running
-
-./compass_container.py status # Check if still running
-./compass_container.py enter # Access running container
-./compass_container.py stop # Stop container
-```
-
-### Isaac Sim Container
-- **Starts in interactive mode** (blocks terminal)
-- **Container exits when Isaac Sim GUI closes**
-- **Auto-removes itself** when terminated
-- **Command blocks until you close Isaac Sim**
-
-```bash
-./compass_container.py launch_isaac_sim
-# Command blocks, shows Isaac Sim GUI
-# Close Isaac Sim → container exits → command exits
-# Container is automatically removed
-```
-
-### Typical Workflow
-```bash
-# Terminal 1: Start Isaac Sim (interactive, blocks)
-./compass_container.py launch_isaac_sim
-
-# Terminal 2: Start Compass (detached, returns immediately)
-./compass_container.py launch_nav
-
-# Use both systems...
-
-# Terminal 1: Close Isaac Sim GUI (container auto-exits)
-# Terminal 2: Stop Compass container
-./compass_container.py stop
-```
-
-## Troubleshooting
-
-**No GUI / Black screen:**
-```bash
-# X11 permissions are checked automatically when launching Isaac Sim
-# If launch fails with X11 errors, fix permissions:
-xhost +local:docker
-export DISPLAY=:0
-```
-
-**Topics not visible between containers:**
-```bash
-# Verify ROS2 domain consistency
-echo $ROS_DOMAIN_ID # Should be same (0 by default)
-```
-
-**Package not found errors:**
-```bash
-# Force workspace rebuild
-./compass_container.py enter
-# Inside container: rm -rf build install log && colcon build --symlink-install
-```
-
-**Model updated (need TensorRT conversion):**
-```bash
-# If you manually changed the ONNX model in assets/models/
-./compass_container.py launch_nav --force-trt-conversion
-```
-
-**Manual workspace build (inside container):**
-```bash
-cd /home/compassuser/compass_ws
-source /opt/ros/humble/setup.bash
-colcon build --symlink-install
-```
-
-**Build Issues:**
-
-**HUGGINGFACE_TOKEN not set:**
-```bash
-# Get token from https://huggingface.co/settings/tokens after requesting access to nvidia/COMPASS
-export HUGGINGFACE_TOKEN=hf_your_token_here
-./build_compass_docker.sh
-```
-
-**TensorRT conversion fails:**
-```bash
-# Check GPU memory usage
-nvidia-smi
-# Stop other GPU processes if needed
-./compass_container.py stop
-./compass_container.py launch_nav --force-trt-conversion
-```
-
-**ROS2 Communication Issues:**
-
-**Robot doesn't respond to navigation commands:**
-```bash
-# Verify Isaac Sim is running and scene is playing (Play ▶️ button pressed)
-# Inside compass navigator container:
-./compass_container.py enter
-# Inside container:
-ros2 topic list | grep -E "(cmd_vel|odom|image)"
-ros2 topic echo /cmd_vel --once # Should show navigation commands when you set goals
-```
-
-**Network troubleshooting:**
-```bash
-# Automated network diagnostics (recommended)
-./compass_container.py debug_network_setup
-# This checks environment variables, network mode, and ROS2 topic discovery in both containers
-
-# Manual checks (if needed):
-docker inspect compass-ros2-navigator | grep NetworkMode # Should show: "NetworkMode": "host"
-```
diff --git a/ros2_deployment/README.md b/ros2_deployment/README.md
deleted file mode 100644
index 0fcf496..0000000
--- a/ros2_deployment/README.md
+++ /dev/null
@@ -1,38 +0,0 @@
-# COMPASS ROS2 Deployment
-
-This directory contains ROS2 packages for deploying **COMPASS** across both simulation and real-world environments.
-
-## Provided ROS2 Nodes
-
-- **compass_inference**: Consumes camera images, target poses, and robot speed inputs, then outputs velocity commands by running TensorRT inference with COMPASS engines.
-- **obj_target_generator**: Receives object localization bounding boxes and generates navigation target poses for the COMPASS navigator.
-
-These nodes enable a variety of integration workflows, including the following examples:
-
----
-
-## 1. Isaac Sim Integration
-
-The `compass_navigator` package is fully compatible with [NVIDIA Isaac Sim](https://developer.nvidia.com/isaac-sim), leveraging its robotics environments and ROS2 bridge for seamless simulation.
-
-For detailed setup instructions and a step-by-step Isaac Sim integration guide, see [ISAACSIM_README.md](./ISAACSIM_README.md) in this directory.
-
----
-
-## 2. Zero-Shot Sim2Real Transfer
-
-The **compass_inference** node can also be deployed directly on real robots, enabling a seamless transition from simulation to real-world operation. By integrating visual SLAM solutions such as [cuVSLAM](https://nvidia-isaac-ros.github.io/concepts/visual_slam/cuvslam/index.html) for robot state estimation, the COMPASS model can support zero-shot Sim2Real transfer.
-
-https://github.com/user-attachments/assets/141af4f6-c915-4254-b6a0-00706e4aea5f
-
----
-
-## 3. Object Navigation Integration
-
-
-By integrating an object localization module (e.g., [Locate3D](https://locate3d.atmeta.com/)), we can also enable object navigation with COMPASS. The **obj_target_generator** node can convert localized object bounding boxes into navigation goals, allowing the robot to autonomously approach specified objects.
-
-
-https://github.com/user-attachments/assets/3928e9fd-f78d-4b8e-8bbc-9932b386ae6b
-
----
diff --git a/ros2_deployment/compass_container.py b/ros2_deployment/compass_container.py
index c7f625d..83bc963 100755
--- a/ros2_deployment/compass_container.py
+++ b/ros2_deployment/compass_container.py
@@ -3,7 +3,6 @@
# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
# SPDX-License-Identifier: Apache-2.0
-
# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
# SPDX-License-Identifier: Apache-2.0
#
diff --git a/ros2_deployment/compass_navigator/compass_navigator/__init__.py b/ros2_deployment/compass_navigator/compass_navigator/__init__.py
index 7ab23ee..3159bfe 100644
--- a/ros2_deployment/compass_navigator/compass_navigator/__init__.py
+++ b/ros2_deployment/compass_navigator/compass_navigator/__init__.py
@@ -12,4 +12,3 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
diff --git a/ros2_deployment/compass_navigator/compass_navigator/obj_target_generator.py b/ros2_deployment/compass_navigator/compass_navigator/obj_target_generator.py
index ff26db5..5be71c0 100644
--- a/ros2_deployment/compass_navigator/compass_navigator/obj_target_generator.py
+++ b/ros2_deployment/compass_navigator/compass_navigator/obj_target_generator.py
@@ -15,7 +15,6 @@
# See the License for the specific language governing permissions and
# limitations under the License.
-
# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
# SPDX-License-Identifier: Apache-2.0
#
diff --git a/scripts/generate_omap_from_usd.py b/scripts/generate_omap_from_usd.py
new file mode 100755
index 0000000..ef3cddb
--- /dev/null
+++ b/scripts/generate_omap_from_usd.py
@@ -0,0 +1,308 @@
+#!/usr/bin/env python3
+# SPDX-FileCopyrightText: Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+"""Generate a 2D occupancy map (PNG + ROS YAML) from a USD scene.
+
+Wraps Isaac Sim's ``isaacsim.asset.gen.omap.bindings._omap.Generator`` and emits
+files compatible with ``OccupancyMapCollisionChecker``.
+
+Output convention matches the existing bundled maps (top-left origin): the YAML
+``origin`` is the world-coordinate of the *top-left* of the image (i.e. y =
+ymax), and image row 0 is at y = ymax.
+
+Run via the Isaac Lab Python wrapper:
+
+ ${ISAACLAB_PATH}/isaaclab.sh -p scripts/generate_omap_from_usd.py \
+ compass/rl_env/exts/mobility_es/mobility_es/usd/office/office.usd
+
+By default the PNG + YAML land at ``/omap/`` next to the USD, which is
+where ``OccupancyMapCollisionChecker``'s sibling-fallback looks first.
+"""
+
+import argparse
+import sys
+from pathlib import Path
+
+# Initialize Isaac Sim before importing pxr / omni.physx.
+# Match the headless-boot pattern used by .claude/skills/compass/scripts/sage10k_to_usd.py.
+from isaacsim import SimulationApp # pylint: disable=import-error
+
+_app = SimulationApp({"headless": True})
+
+# pylint: disable=wrong-import-position
+import numpy as np
+import omni.kit.app
+import omni.physx
+import omni.timeline
+import omni.usd
+import PIL.Image
+
+# isaacsim.asset.gen.omap is not auto-loaded by the standalone Isaac Sim app
+# config; enable it explicitly before importing the bindings.
+_OMAP_EXT_NAME = "isaacsim.asset.gen.omap"
+_ext_manager = omni.kit.app.get_app().get_extension_manager()
+_ext_manager.set_extension_enabled_immediate(_OMAP_EXT_NAME, True)
+
+from isaacsim.asset.gen.omap.bindings import _omap # pylint: disable=ungrouped-imports
+from pxr import Sdf, Usd, UsdGeom, UsdPhysics
+
+# Buffer values written by Generator.update_settings(...) below.
+# Generator.get_buffer() returns these integer codes per cell.
+OCCUPIED_VALUE = 4
+FREE_VALUE = 5
+UNKNOWN_VALUE = 6
+
+# Grayscale pixel values written into the output PNG. ROS map_server expects
+# a near-white free pixel, near-black occupied pixel, and a mid-gray unknown.
+PNG_OCCUPIED = 0
+PNG_FREE = 254
+PNG_UNKNOWN = 205
+
+# ROS thresholds (matching the existing maps and Isaac Sim defaults).
+ROS_OCCUPIED_THRESH = 0.65
+ROS_FREE_THRESH = 0.196
+
+
+def parse_args() -> argparse.Namespace:
+ parser = argparse.ArgumentParser(
+ description=__doc__.split("\n\n", maxsplit=1)[0],
+ formatter_class=argparse.ArgumentDefaultsHelpFormatter,
+ )
+ parser.add_argument("usd_path", type=str, help="Path to the input USD scene.")
+ parser.add_argument(
+ "-o",
+ "--out-dir",
+ type=str,
+ default=None,
+ help="Output directory. Default: /omap/ (next to the USD).",
+ )
+ parser.add_argument(
+ "--map-name",
+ type=str,
+ default=None,
+ help="Stem for the output PNG and YAML. Default: .",
+ )
+ parser.add_argument(
+ "--cell-size",
+ type=float,
+ default=0.05,
+ help="Grid cell size in meters (matches existing bundled maps).",
+ )
+ parser.add_argument(
+ "--z-min",
+ type=float,
+ default=0.1,
+ help="Lower height (meters) of the slab used for 2D rasterization.",
+ )
+ parser.add_argument(
+ "--z-max",
+ type=float,
+ default=0.62,
+ help="Upper height (meters) of the slab used for 2D rasterization.",
+ )
+ parser.add_argument(
+ "--bounds",
+ type=float,
+ nargs=4,
+ metavar=("XMIN", "XMAX", "YMIN", "YMAX"),
+ default=None,
+ help="World-space (x,y) bounds in meters. Default: derived from USD bbox + 1m padding.",
+ )
+ parser.add_argument(
+ "--padding",
+ type=float,
+ default=1.0,
+ help="Padding (meters) added around the auto-derived bbox. Ignored when --bounds is given.",
+ )
+ return parser.parse_args()
+
+
+def compute_xy_bounds_from_stage(stage, padding: float):
+ """Compute world-space (xmin, xmax, ymin, ymax) bounds from the stage's bbox.
+
+ Mirrors the policy used by Isaac Sim's omap UI "Auto Bound" button
+ (isaacsim.asset.gen.omap.ui/.../extension.py around line 350): only
+ Tokens.default_ purpose, no extent-hint short-circuit, fresh cache.
+ Some USDs ship stale extent hints that mislead BBoxCache into returning
+ garbage bounds, so we don't trust them.
+ """
+ bbox_cache = UsdGeom.BBoxCache(
+ Usd.TimeCode.Default(),
+ includedPurposes=[UsdGeom.Tokens.default_],
+ )
+ bbox_cache.Clear()
+ # Prefer /World if it exists (USD assembly convention); fall back to root.
+ world_prim = stage.GetPrimAtPath("/World")
+ if not world_prim or not world_prim.IsValid():
+ world_prim = stage.GetPseudoRoot()
+ world_bbox = bbox_cache.ComputeWorldBound(world_prim)
+ aligned = world_bbox.ComputeAlignedRange()
+ if aligned.IsEmpty():
+ raise RuntimeError("USD bbox is empty; pass --bounds explicitly.")
+ minp = aligned.GetMin()
+ maxp = aligned.GetMax()
+ return (
+ float(minp[0]) - padding,
+ float(maxp[0]) + padding,
+ float(minp[1]) - padding,
+ float(maxp[1]) + padding,
+ )
+
+
+def ensure_physics_scene(stage) -> None:
+ """The occupancy generator queries PhysX. Ensure a UsdPhysics.Scene exists."""
+ physics_path = Sdf.Path("/World/physicsScene")
+ if not stage.GetPrimAtPath(physics_path):
+ UsdPhysics.Scene.Define(stage, physics_path)
+
+
+def buffer_to_grayscale_png(buffer, dims) -> np.ndarray:
+ """Convert the Generator's flat int buffer into a (H, W) uint8 grayscale image.
+
+ The buffer is row-major with width = dims[0], height = dims[1]. Free pixels
+ map to ``PNG_FREE`` (white), occupied to ``PNG_OCCUPIED`` (black), unknown
+ to ``PNG_UNKNOWN`` (gray). The image is then flipped vertically so row 0 of
+ the PNG corresponds to y = ymax (the *top* of the world) — matches the
+ top-left origin convention used by the existing bundled OMaps.
+ """
+ arr = np.array(buffer, dtype=np.int32)
+ expected = dims[0] * dims[1]
+ if arr.size != expected:
+ raise RuntimeError(
+ f"Buffer size {arr.size} != dims[0]*dims[1] = {expected} ({dims[0]}x{dims[1]})")
+ grid = arr.reshape((dims[1], dims[0])) # (H, W)
+ img = np.full_like(grid, PNG_UNKNOWN, dtype=np.uint8)
+ img[grid == OCCUPIED_VALUE] = PNG_OCCUPIED
+ img[grid == FREE_VALUE] = PNG_FREE
+ # Generator's buffer row 0 is at y = ymin (bottom). Flip so PNG row 0 = ymax
+ # (top), matching the existing top-left origin convention.
+ return np.flipud(img)
+
+
+def write_yaml(yaml_path: Path, image_filename: str, resolution: float, origin_xy):
+ """Write a ROS-compatible map_server YAML.
+
+ ``origin`` is the world (x, y) of the *top-left* corner of the image, matching
+ the COMPASS bundled-map convention consumed by ``OccupancyMapCollisionChecker``.
+ """
+ text = (f"image: {image_filename}\n"
+ f"resolution: {resolution}\n"
+ f"origin: [{origin_xy[0]:.6f}, {origin_xy[1]:.6f}, 0.0]\n"
+ f"negate: 0\n"
+ f"occupied_thresh: {ROS_OCCUPIED_THRESH}\n"
+ f"free_thresh: {ROS_FREE_THRESH}\n")
+ yaml_path.write_text(text)
+
+
+def main() -> int:
+ args = parse_args()
+
+ usd_path = Path(args.usd_path).resolve()
+ if not usd_path.exists():
+ print(f"ERROR: USD not found: {usd_path}", file=sys.stderr)
+ return 2
+
+ out_dir = Path(args.out_dir) if args.out_dir else usd_path.parent / "omap"
+ out_dir = out_dir.resolve()
+ out_dir.mkdir(parents=True, exist_ok=True)
+
+ map_name = args.map_name or usd_path.stem
+ png_path = out_dir / f"{map_name}.png"
+ yaml_path = out_dir / "occupancy_map.yaml"
+
+ print(f"[generate_omap] Loading USD: {usd_path}")
+ ctx = omni.usd.get_context()
+ ctx.open_stage(str(usd_path))
+ # Wait for all references / textures / MDL shaders to finish loading before
+ # we rasterize. The `get_stage_loading_status()` tuple is (assets_loaded,
+ # assets_loading, assets_to_load); we block until the third element drops
+ # to zero, capped at ~5 minutes so we don't hang forever on a broken USD.
+ # Without this guard, generate2d() can crash kit when it queries fabric
+ # for prims whose references are still resolving (mirrors the
+ # `tearDown`-side wait in isaacsim.asset.gen.omap's own tests).
+ max_load_ticks = 6000
+ for tick in range(max_load_ticks):
+ omni.kit.app.get_app().update()
+ loaded, loading, to_load = ctx.get_stage_loading_status()
+ if to_load == 0 and loading == 0:
+ print(f"[generate_omap] Stage fully loaded after {tick + 1} ticks "
+ f"(loaded={loaded}, loading={loading}, to_load={to_load})")
+ break
+ else:
+ print(f"[generate_omap] WARNING: stage still loading after {max_load_ticks} ticks; "
+ "proceeding anyway — generate2d() may rasterize a partially loaded scene.")
+
+ stage = ctx.get_stage()
+ ensure_physics_scene(stage)
+ for _ in range(5):
+ omni.kit.app.get_app().update()
+
+ if args.bounds is not None:
+ xmin, xmax, ymin, ymax = args.bounds
+ else:
+ print(f"[generate_omap] Computing bounds from USD bbox (padding {args.padding} m)")
+ xmin, xmax, ymin, ymax = compute_xy_bounds_from_stage(stage, args.padding)
+
+ print(f"[generate_omap] Bounds (m): x=[{xmin:.3f}, {xmax:.3f}] "
+ f"y=[{ymin:.3f}, {ymax:.3f}] slab z=[{args.z_min:.3f}, {args.z_max:.3f}]")
+ print(f"[generate_omap] Cell size: {args.cell_size} m")
+
+ # Drive the generator. Origin is the slab's mid-z, which is what update_location does.
+ z_mid = 0.5 * (args.z_min + args.z_max)
+ timeline = omni.timeline.get_timeline_interface()
+ timeline.play()
+ omni.kit.app.get_app().update()
+
+ physx = omni.physx.get_physx_interface()
+ stage_id = omni.usd.get_context().get_stage_id()
+ generator = _omap.Generator(physx, stage_id)
+ generator.update_settings(args.cell_size, OCCUPIED_VALUE, FREE_VALUE, UNKNOWN_VALUE)
+ generator.set_transform(
+ (0.0, 0.0, z_mid),
+ (xmin, ymin, args.z_min),
+ (xmax, ymax, args.z_max),
+ )
+
+ # The C++ generator needs at least one app-update tick before generate2d.
+ omni.kit.app.get_app().update()
+ print("[generate_omap] Running generate2d() ...")
+ generator.generate2d()
+ omni.kit.app.get_app().update()
+
+ timeline.stop()
+
+ buffer = generator.get_buffer()
+ dims = generator.get_dimensions()
+ print(f"[generate_omap] Output dims (W x H): {dims[0]} x {dims[1]} "
+ f"(buffer size {len(buffer)})")
+
+ img = buffer_to_grayscale_png(buffer, dims)
+ # Save as RGBA to match the existing bundled PNGs — OccupancyMapCollisionChecker
+ # accesses img[:, :, 0] regardless of the grayscale value.
+ rgba = np.stack([img, img, img, np.full_like(img, 255)], axis=-1)
+ PIL.Image.fromarray(rgba).save(png_path)
+ # Top-left origin convention: write (xmin, ymax) so YAML's `origin[1]` is
+ # the world Y of image row 0 (the top of the map).
+ write_yaml(yaml_path, png_path.name, args.cell_size, (xmin, ymax))
+
+ print(f"[generate_omap] Wrote PNG : {png_path}")
+ print(f"[generate_omap] Wrote YAML: {yaml_path}")
+ return 0
+
+
+if __name__ == "__main__":
+ rc = main()
+ _app.close()
+ sys.exit(rc)
diff --git a/scripts/hdf5_to_lerobot_episodic.py b/scripts/hdf5_to_lerobot_episodic.py
index ec2b81c..2cc7eb4 100755
--- a/scripts/hdf5_to_lerobot_episodic.py
+++ b/scripts/hdf5_to_lerobot_episodic.py
@@ -14,7 +14,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""
HDF5 to LeRobot Data Format Converter for Episodic Data