diff --git a/.dockerignore b/.dockerignore
new file mode 100644
index 0000000..38a7478
--- /dev/null
+++ b/.dockerignore
@@ -0,0 +1,92 @@
+# Git
+# .git
+# .gitignore
+.gitattributes
+
+
+# CI
+.codeclimate.yml
+.travis.yml
+.taskcluster.yml
+
+# Docker
+docker-compose.yml
+Dockerfile
+.docker
+.dockerignore
+
+# Byte-compiled / optimized / DLL files
+**/__pycache__/
+**/*.py[cod]
+
+# C extensions
+*.so
+
+# Distribution / packaging
+.Python
+env/
+build/
+develop-eggs/
+dist/
+downloads/
+eggs/
+lib/
+lib64/
+parts/
+sdist/
+var/
+*.egg-info/
+.installed.cfg
+*.egg
+
+# PyInstaller
+# Usually these files are written by a python script from a template
+# before PyInstaller builds the exe, so as to inject date/other infos into it.
+*.manifest
+*.spec
+
+# Installer logs
+pip-log.txt
+pip-delete-this-directory.txt
+
+# Unit test / coverage reports
+htmlcov/
+.tox/
+.coverage
+.cache
+nosetests.xml
+coverage.xml
+
+# Translations
+*.mo
+*.pot
+
+# Django stuff:
+*.log
+
+# Sphinx documentation
+docs/_build/
+
+# PyBuilder
+target/
+
+# Virtual environment
+.env
+.venv/
+venv/
+
+# PyCharm
+.idea
+
+# Python mode for VIM
+.ropeproject
+**/.ropeproject
+
+# Vim swap files
+**/*.swp
+
+# VS Code
+.vscode/
+
+# Server config file
+**/web_config.ini
diff --git a/.github/workflows/automerge.yml b/.github/workflows/automerge.yml
index a6a50a9..9b893e1 100644
--- a/.github/workflows/automerge.yml
+++ b/.github/workflows/automerge.yml
@@ -1,6 +1,6 @@
name: Automerge master into alberobotics
-on:
+on:
push:
branches:
- "master"
@@ -8,22 +8,24 @@ on:
jobs:
merge-master-into-alberobotics:
runs-on: ubuntu-20.04
- env:
- CI_COMMIT_MESSAGE: Continuous Integration Build Artifacts
- CI_COMMIT_AUTHOR: Continuous Integration
steps:
- - uses: actions/checkout@v3
+ - name: Checkout
+ uses: actions/checkout@v3
- - name: Set Git config
+ - name: Set up git
run: |
- git config --global user.name "${{ env.CI_COMMIT_AUTHOR }}"
- git config --global user.email "marcoruzzon@users.noreply.github.com"
-
+ git config --global user.name $USER_NAME
+ git config --global user.email $USER_EMAIL
+ env:
+ # see https://github.com/orgs/community/discussions/26560#discussioncomment-3531273
+ USER_NAME: 'github-actions[bot]'
+ USER_EMAIL: '41898282+github-actions[bot]@users.noreply.github.com'
+
- name: Get changed files
id: changed-files
uses: tj-actions/changed-files@v35
-
+
- name: Merge master into alberobotics
run: |
@@ -39,14 +41,14 @@ jobs:
"src/modular/modular_data/cartesio/ModularBot_cartesio_multichain_config.yaml"
)
- git fetch --unshallow
+ git fetch --unshallow
git checkout alberobotics
git merge --no-ff --no-commit master
for file in "${to_keep[@]}"; do
git reset HEAD $file
- git checkout -- $file
+ git checkout -- $file
done
- git commit -m "merged master"
+ git commit -m "merged master"
git push
diff --git a/.github/workflows/create_pr.yaml b/.github/workflows/create_pr.yaml
new file mode 100644
index 0000000..4321c50
--- /dev/null
+++ b/.github/workflows/create_pr.yaml
@@ -0,0 +1,65 @@
+name: Open PR for new modular_frontend version
+# see https://github.com/orgs/community/discussions/26286#discussioncomment-3251208
+# on:
+# create:
+# branches:
+# - 'ci/deps/modular_frontend-v[0-9]+.[0-9]+.[0-9]+*'
+on: create
+
+jobs:
+ create-pr:
+ runs-on: ubuntu-latest
+ name: Create PR to update modular_frontend
+ # see https://github.com/orgs/community/discussions/26771#discussioncomment-3253330
+ if: startsWith(github.ref_name, 'ci/deps/modular_frontend-')
+ env:
+ TARGET_BRANCH: feat/linfization
+ steps:
+ - name: Checkout
+ uses: actions/checkout@v3
+
+ - name: Set up git
+ run: |
+ git config --global user.name $USER_NAME
+ git config --global user.email $USER_EMAIL
+ env:
+ # see https://github.com/orgs/community/discussions/26560#discussioncomment-3531273
+ USER_NAME: 'github-actions[bot]'
+ USER_EMAIL: '41898282+github-actions[bot]@users.noreply.github.com'
+
+ # - name: Updated static docs
+ # run: |
+ # RELEASE_VERSION=$(echo $GITHUB_REF_NAME | sed -e s/.*modular_frontend-//)
+ # sed -i '/version/c\ \"version\" : \"'RELEASE_VERSION'\",' package.json
+ # npm ci
+ # npm run build:swagger
+ # git add docs
+ # git commit -m "📝 docs(Swagger): update static swagger docs"
+
+ # - name: Commit version bump
+ # run: |
+ # RELEASE_VERSION=$(echo $GITHUB_REF_NAME | sed -e s/.*modular_frontend-//)
+ # sed -i '/version/c\ \"version\" : \"'RELEASE_VERSION'\",' package.json
+ # git add package.json
+ # git commit -m "📦 chore: bump version to RELEASE_VERSION"
+
+ # - name: Push changes
+ # run: |
+ # git push -u origin HEAD
+
+ - name: Open new PR
+ run: |
+ RELEASE_VERSION=$(echo $GITHUB_REF_NAME | sed -e s/.*modular_frontend-//)
+ gh pr create \
+ --title "⬆️ chore(gui): Bump modular_frontend to $RELEASE_VERSION" \
+ --body-file ./src/modular/web/modular_frontend/frontend_release_notes/CHANGELOG.$RELEASE_VERSION.md \
+ --base ${{ env.TARGET_BRANCH }} \
+ --label refactor \
+ --assignee "m-tartari" \
+ --reviewer "EdoardoRomiti"
+ env:
+ GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }}
+
+ - name: Cleanup ssh configs
+ run: |
+ rm -rf ~/.ssh
diff --git a/.gitignore b/.gitignore
index 4c21ba0..36f5375 100644
--- a/.gitignore
+++ b/.gitignore
@@ -160,3 +160,6 @@ venv.bak/
# VS Code folder
.vscode/*
+
+# Custom setting for API
+src/modular/web/web_config.ini
diff --git a/Dockerfile b/Dockerfile
new file mode 100644
index 0000000..171785f
--- /dev/null
+++ b/Dockerfile
@@ -0,0 +1,41 @@
+ARG BASE_IMAGE
+FROM ${BASE_IMAGE}
+
+ARG RECIPES_BRANCH=master
+ARG RECIPES_PROVIDER=https://github.com/ADVRHumanoids/multidof_recipes.git
+
+ARG FOREST_WS=$HOME/modular_ws
+ARG USER_PWD=user
+ARG MODE=&NoNe&
+ARG JOBS=1
+
+# run apt update as root
+USER root
+SHELL ["/bin/bash", "-ic"]
+RUN sudo apt-get update
+
+USER user
+
+# Add github.com to known hosts
+RUN mkdir -p -m 0700 $HOME/.ssh && ssh-keyscan github.com >> $HOME/.ssh/known_hosts
+
+# Initialize forest workspace
+WORKDIR ${FOREST_WS}
+RUN forest init
+RUN echo "source $FOREST_WS/setup.bash" >> ~/.bashrc
+
+# Add recipes to forest workspace
+RUN forest add-recipes https://github.com/ADVRHumanoids/multidof_recipes.git --tag $RECIPES_BRANCH
+
+# Install dependencies using forest
+RUN --mount=type=ssh,uid=${USER_ID} forest grow concert_description -m ${MODE} -j${JOBS} --pwd ${USER_PWD} --clone-depth 1 \
+ && forest grow iit-dagana-ros-pkg -m ${MODE} -j${JOBS} --pwd ${USER_PWD} --clone-depth 1 \
+ && rm -fr $FOREST_WS/build
+
+# Build local version of modular
+WORKDIR ${FOREST_WS}/src/modular
+COPY --chown=user:user . ${FOREST_WS}/src/modular
+RUN pip install -e .
+
+# Set entrypoint
+CMD ./scripts/entrypoint.sh
diff --git a/README.md b/README.md
index b1ed3ec..c1e54a1 100644
--- a/README.md
+++ b/README.md
@@ -61,7 +61,7 @@
## About The Project
This project focuses on the development of an app for rapid model generation of modular robots, starting from a set of basic robotic modules.
-This app will genereate URDF, SRDF and a complete ROS package, which can be used to simulate and control the robot.
+This app will genereate URDF, SRDF and a complete ROS package, which can be used to simulate and control the robot.
![reconfigurable_pino](https://alberobotics.it/templates/yootheme/cache/reconfigurable_pino-2e1209e8.png)
@@ -108,6 +108,29 @@ Get the `RobotBuilder` app from the latest release and make it executable (`chmo
## Usage
+### Configs
+
+Several configurations can be modified for each deployment by creating a config file `src/modular/web/web_config.ini`. The most important ones are:
+
+```ini
+[MODULAR_API] # Mandatory section
+
+# version of the API
+version = 1
+
+# When deploying the robot, return a zip file with the generated ROS package
+download_on_deploy = true
+
+# Use flash sessions to have multiple users on a single server
+enable_sessions = true
+
+# secret_key is used to sign the session cookie, it should be a random string
+secret_key = FOO_BAR_BAZ
+
+# base_route adds a prefix to all API routes, it is best to leave it commented
+# base_route = /linfa/api/v${MODULAR_API:version}/modular
+```
+
### Run the GUI
To use modular you need to start the python server.
@@ -133,7 +156,7 @@ Then open from a browser to acces the graphical interface
### Use the python API
Examples of how to use the python API are provided in the [scripts](https://github.com/ADVRHumanoids/modular_hhcm/tree/master/scripts) folder.
- `create_modularbot.ipynb` shows an example of how to build a 6-DOF robot using Alberobotics modules and deploy URDF, SRDF, etc. into a ROS package
-- `generate_concert_robot.ipynb` shows how to build and deploy the CONCERT modular robot
+- `generate_concert_robot.ipynb` shows how to build and deploy the CONCERT modular robot
## Documentation
diff --git a/docker-compose.yml b/docker-compose.yml
new file mode 100644
index 0000000..6052d94
--- /dev/null
+++ b/docker-compose.yml
@@ -0,0 +1,26 @@
+version: "3.8"
+services:
+
+ modular:
+ image: "${TARGET_IMAGE}"
+ container_name: modular
+ restart: 'unless-stopped'
+ build:
+ context: ./
+ dockerfile: Dockerfile
+ ssh:
+ # mount the default ssh agent
+ - default
+ args:
+ - BASE_IMAGE
+ - RECIPES_BRANCH
+ - RECIPES_PROVIDER
+ - FOREST_WS
+ - USER_PWD
+ - MODE
+ - JOBS
+ ports:
+ - "5003:5003"
+ volumes:
+ # We might want to change the local path of the web_config.ini file
+ - ./src/modular/web/web_config.ini:${FOREST_WS}/src/modular/src/modular/web/web_config.ini
diff --git a/scripts/entrypoint.sh b/scripts/entrypoint.sh
new file mode 100755
index 0000000..1ec376f
--- /dev/null
+++ b/scripts/entrypoint.sh
@@ -0,0 +1,13 @@
+#!/bin/bash
+
+# Start detached roscore
+nohup roscore &
+
+# Start Modular Server
+gunicorn --workers 1 --threads 4 --bind '0.0.0.0:5003' wsgi:app
+
+# Wait for any process to exit
+wait -n
+
+# Exit with status of process that exited first
+exit $?
diff --git a/scripts/generate_concert_robot.ipynb b/scripts/generate_concert_robot.ipynb
index 901eae3..b2b61a9 100644
--- a/scripts/generate_concert_robot.ipynb
+++ b/scripts/generate_concert_robot.ipynb
@@ -29,7 +29,7 @@
"outputs": [],
"source": [
"#add mobile base\n",
- "urdf_writer.add_mobile_platform()\n"
+ "urdf_writer.add_module('concert/mobile_platform_concert.json', 0, False)\n"
]
},
{
@@ -119,7 +119,7 @@
},
"outputs": [],
"source": [
- "urdf_writer.remove_connectors()\n",
+ "urdf_writer.remove_all_connectors()\n",
"\n",
"# get srdf and joint_map\n",
"urdf_writer.write_urdf()\n",
diff --git a/scripts/generate_concert_robot_JSON.ipynb b/scripts/generate_concert_robot_JSON.ipynb
index c2a70e5..bf8f4f9 100644
--- a/scripts/generate_concert_robot_JSON.ipynb
+++ b/scripts/generate_concert_robot_JSON.ipynb
@@ -29,7 +29,7 @@
"outputs": [],
"source": [
"#add mobile base\n",
- "urdf_writer.add_mobile_platform()\n"
+ "urdf_writer.add_module('concert/mobile_platform_concert.json', 0, False)\n"
]
},
{
@@ -119,7 +119,7 @@
},
"outputs": [],
"source": [
- "urdf_writer.remove_connectors()\n",
+ "urdf_writer.remove_all_connectors()\n",
"\n",
"# get srdf and joint_map\n",
"urdf_writer.write_urdf()\n",
diff --git a/scripts/payload_calc.py b/scripts/payload_calc.py
new file mode 100644
index 0000000..350df6b
--- /dev/null
+++ b/scripts/payload_calc.py
@@ -0,0 +1,124 @@
+import pinocchio
+import numpy as np
+import scipy
+import rospkg
+import os
+
+rospack = rospkg.RosPack()
+pkgpath = rospack.get_path('ModularBot')
+urdfpath = os.path.join(pkgpath, 'urdf', 'ModularBot.urdf')
+
+urdf = open(urdfpath, 'r').read()
+
+# Load the urdf model
+model = pinocchio.buildModelFromXML(urdf)
+
+# Create data required by the algorithms
+data = model.createData()
+
+# Get the frame index for the end-effector (hard-coded for now)
+frame_idx = model.getFrameId('TCP_gripper_A')
+
+lower_limits = model.lowerPositionLimit
+upper_limits = model.upperPositionLimit
+
+nq = model.nq
+
+# for i in range(nq):
+# print(model.names[i+1], lower_limits[i], upper_limits[i])
+
+## LinSpace Sampling
+# n_q_samples = 10
+# q_samples = np.empty((nq, n_q_samples))
+# # q_list = []
+
+# for idx, lims in enumerate(zip(lower_limits, upper_limits)):
+# q_idx_samples = np.linspace(lims[0], lims[1], n_q_samples)
+# q_samples[idx] = q_idx_samples
+# # q_list.append(q_idx_samples)
+# print(q_samples)
+# q_configurations = np.array(list(itertools.product(*q_samples)))
+# n_samples = len(q_configurations)
+
+## Random Sampling
+n_samples = 1000
+q_configurations = [pinocchio.randomConfiguration(model) for i in range(n_samples)]
+
+c = np.array([0, 0, -1, 0, 0, 0])
+
+lb = np.zeros((nq))
+ub = np.array([0, 0, np.inf, 0, 0, 0])
+
+worst_case_force = np.array([0, 0, np.inf, 0, 0, 0])
+worst_case_q = np.zeros((nq))
+worst_case_tau = np.zeros((nq))
+worst_case_b = np.zeros((nq))
+worst_case_A = np.zeros((nq, 6))
+
+zeros = np.zeros((nq))
+q = np.zeros((nq))
+A = np.zeros((nq, 6))
+b = np.zeros((nq))
+tau_rated = 162.0
+tau_max = np.ones((nq))*tau_rated
+tau_min = - tau_max
+
+# Compute the jacobian for all the samples
+for idx, q in enumerate(q_configurations):
+ # q = np.array(q)
+ pinocchio.computeJointJacobians(model, data, q)
+ # pinocchio.framesForwardKinematics(model, data, q)
+ A = pinocchio.getFrameJacobian(model, data, frame_idx, pinocchio.ReferenceFrame.LOCAL_WORLD_ALIGNED)[:6].T * 1 # 9.81
+ b = tau_max - np.abs(pinocchio.nonLinearEffects(model, data, q, zeros))
+ tau = pinocchio.nonLinearEffects(model, data, q, zeros)
+ tau_available = []
+ sign_J_z = np.sign(A[:,2])
+ sign_tau = np.sign(tau)
+ ## method 1
+ # for idx, torque in enumerate(tau):
+ # if torque <= tau_rated and sign_tau[idx] in [1]:
+ # tau_tmp = tau_rated - torque
+ # # if sign_J_z[idx] != sign_tau[idx] and sign_J_z[idx] != 0:
+ # # tau_tmp *= -1
+ # if sign_J_z[idx] != 1:
+ # A[idx, 2] *= -1
+ # tau_available.append(tau_tmp)
+ # elif torque >= -tau_rated and sign_tau[idx] in [-1]:
+ # tau_tmp = -tau_rated - torque
+ # # if sign_J_z[idx] != sign_tau[idx] and sign_J_z[idx] != 0:
+ # # tau_tmp *= -1
+ # tau_tmp *= -1
+ # if sign_J_z[idx] != 1:
+ # A[idx, 2] *= -1
+ # tau_available.append(tau_tmp)
+ # elif sign_tau[idx] == 0:
+ # tau_available.append(tau_rated)
+ # else:
+ # tau_available.append(0.0)
+ # b = np.array(tau_available)
+
+ ## method 2
+ b1 = tau_max - tau
+ b2 = - tau_min + tau
+ b = np.concatenate((b1, b2))
+ A1 = A
+ A2 = -A
+ A = np.vstack((A1, A2))
+
+
+ sol = scipy.optimize.linprog(c, A_ub=A, b_ub=b, bounds=list(zip(lb, ub)))
+
+ # print (idx)
+
+ if (sol.success):
+ # print (sol.x / 9.81)
+ if sol.x[2]/9.81 < worst_case_force[2]/9.81:
+ worst_case_force = sol.x
+ worst_case_q = q
+ worst_case_tau = tau
+ worst_case_b = b
+ worst_case_A = A
+
+print (('Payload: ', worst_case_force[2]/9.81))
+print (('q: ', worst_case_q))
+
diff --git a/scripts/payload_calc_test.py b/scripts/payload_calc_test.py
new file mode 100644
index 0000000..fdf093a
--- /dev/null
+++ b/scripts/payload_calc_test.py
@@ -0,0 +1,93 @@
+import pinocchio
+import itertools
+import numpy
+import scipy
+import rospkg
+import os
+
+rospack = rospkg.RosPack()
+pkgpath = rospack.get_path('ModularBot')
+urdfpath = os.path.join(pkgpath, 'urdf', 'ModularBot.urdf')
+
+urdf = open(urdfpath, 'r').read()
+
+# Load the urdf model
+model = pinocchio.buildModelFromUrdf(urdfpath)
+
+# Create data required by the algorithms
+data = model.createData()
+
+# Get the frame index for the end-effector (hard-coded for now)
+frame_idx = model.getFrameId('TCP_gripper_A')
+
+lower_limits = model.lowerPositionLimit
+upper_limits = model.upperPositionLimit
+
+nq = model.nq
+
+n_q_samples = 2
+
+q_samples = numpy.empty((nq, n_q_samples))
+# q_list = []
+
+# for i in range(nq):
+# print(model.names[i+1], lower_limits[i], upper_limits[i])
+
+for idx, lims in enumerate(zip(lower_limits, upper_limits)):
+
+ q_idx_samples = numpy.linspace(lims[0], lims[1], n_q_samples)
+ q_samples[idx] = q_idx_samples
+ # q_list.append(q_idx_samples)
+
+print(q_samples)
+
+q_configurations = list(itertools.product(*q_samples))
+n_samples = len(q_configurations)
+
+# other_qs = numpy.meshgrid(q_samples[0], q_samples[1], q_samples[2], q_samples[3], q_samples[4], q_samples[5])
+# print(other_qs)
+
+# print(n_samples)
+
+# Compute the jacobian for all the samples
+jac_samples = numpy.empty((nq * n_samples, 6))
+tau_samples = numpy.empty((nq* n_samples))
+# jac_samples = numpy.zeros(nq*n_samples*6).reshape((nq * n_samples, 6))
+# tau_samples = numpy.zeros(nq*n_samples).reshape(nq* n_samples)
+for idx, q in enumerate(q_configurations):
+ q = numpy.array(q)
+ pinocchio.computeJointJacobians(model, data, q)
+ pinocchio.framesForwardKinematics(model, data, q)
+ jac_samples[idx*nq:idx*nq+nq, :] = pinocchio.getFrameJacobian(model, data, frame_idx, pinocchio.ReferenceFrame.LOCAL_WORLD_ALIGNED)[:6].T * -9.81
+ tau_samples[idx*nq:idx*nq+nq] = numpy.ones((nq))*162 - pinocchio.nonLinearEffects(model, data, q, numpy.zeros(nq))
+
+ # A = jac_samples[2, :, idx]*9.81
+ # b = 162 - tau_samples[:, idx]
+ # x = b/A
+ # print(x)
+ # print(numpy.linalg.norm(A*x - b))
+
+# A_eq = -jac_samples[:, :, 0].T * 9.81
+# for idx in range(1, n_samples):
+# A_eq = numpy.concatenate((A_eq, -jac_samples[:, :, idx].T * 9.81))
+A_eq = jac_samples
+
+# b_eq = numpy.ones((nq))*162 - tau_samples[:, 0]
+# for idx in range(1, n_samples):
+# b_eq = numpy.concatenate((b_eq, numpy.ones((nq))*162 - tau_samples[:, idx]))
+b_eq = tau_samples
+
+c = numpy.array([0, 0, -1, 0, 0, 0])
+
+lb = numpy.zeros((nq))
+ub = numpy.array([0, 0, numpy.inf, 0, 0, 0])
+
+sol = scipy.optimize.linprog(c, A_ub=A_eq, b_ub=b_eq, bounds=list(zip(lb, ub)))
+# sol = numpy.linalg.solve(A_eq.T, b_eq.T)
+
+print (sol.status)
+print (sol.message)
+print (sol.success)
+print (sol.x)
+
+print (sol.x / 9.81)
\ No newline at end of file
diff --git a/scripts/sim_discovery.py b/scripts/sim_discovery.py
index 0760deb..04461ae 100644
--- a/scripts/sim_discovery.py
+++ b/scripts/sim_discovery.py
@@ -1,13 +1,36 @@
from modular.URDF_writer import *
+import logging
+FORMAT = '[%(levelname)s] [%(module)s]: %(message)s'
+logging.basicConfig(format=FORMAT)
+applogger = logging.getLogger("sim_discovery")
+
urdfwriter_kwargs_dict={
- 'verbose': True
+ 'verbose': True,
+ 'slave_desc_mode': 'use_pos',
+ 'logger': applogger,
}
-# 2nd instance of UrdfWriter class for the robot got from HW
urdf_writer_fromHW = UrdfWriter(**urdfwriter_kwargs_dict)
-reply = "{201: {active_ports: 15, esc_type: 50, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 1, robot_id: 201, topology: 4}, -1: {active_ports: 15, esc_type: 256, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 2, robot_id: -1, topology: 4}, 56: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 3, robot_id: 56, topology: 2}, 53: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 4, robot_id: 53, topology: 2}, 55: {active_ports: 1, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 5, robot_id: 55, topology: 1}, 11: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 6, robot_id: 11, topology: 2}, 12: {active_ports: 1, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 7, robot_id: 12, topology: 1}, 31: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 8, robot_id: 31, topology: 2}, 32: {active_ports: 1, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 9, robot_id: 32, topology: 1}, 41: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 10, robot_id: 41, topology: 2}, 42: {active_ports: 1, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 11, robot_id: 42, topology: 1}, 21: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 12, robot_id: 21, topology: 2}, 22: {active_ports: 1, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 13, robot_id: 22, topology: 1}}"
+# old discovery with ids
+# reply = "{201: {active_ports: 15, esc_type: 50, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 1, robot_id: 201, topology: 4}, -1: {active_ports: 15, esc_type: 256, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 2, robot_id: -1, topology: 4}, 56: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 3, robot_id: 56, topology: 2}, 53: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 4, robot_id: 53, topology: 2}, 55: {active_ports: 1, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 5, robot_id: 55, topology: 1}, 11: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 6, robot_id: 11, topology: 2}, 12: {active_ports: 1, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 7, robot_id: 12, topology: 1}, 31: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 8, robot_id: 31, topology: 2}, 32: {active_ports: 1, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 9, robot_id: 32, topology: 1}, 41: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 10, robot_id: 41, topology: 2}, 42: {active_ports: 1, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 11, robot_id: 42, topology: 1}, 21: {active_ports: 3, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 12, robot_id: 21, topology: 2}, 22: {active_ports: 1, esc_type: 21, mod_id: 0, mod_rev: 0, mod_size: 0, mod_type: 0, position: 13, robot_id: 22, topology: 1}}"
+
+reply = "{1: {active_ports: 15, esc_type: 50, mod_id: 3, mod_rev: 0, mod_size: 0, mod_type: 2, position: 1, robot_id: 201, topology: 4}, 2: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 2, robot_id: -1, topology: 4}, 3: {active_ports: 3, esc_type: 21, mod_id: 8, mod_rev: 0, mod_size: 5, mod_type: 1, position: 3, robot_id: 21, topology: 2}, 4: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 4, robot_id: 22, topology: 1}, 5: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 5, robot_id: 11, topology: 2}, 6: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 6, robot_id: 12, topology: 1}, 7: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 7, robot_id: 31, topology: 2}, 8: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 8, robot_id: 32, topology: 1}, 9: {active_ports: 3, esc_type: 21, mod_id: 8, mod_rev: 0, mod_size: 5, mod_type: 1, position: 9, robot_id: 41, topology: 2}, 10: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 10, robot_id: 42, topology: 1}, 11: {active_ports: 3, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 11, robot_id: 55, topology: 2}, 12: {active_ports: 3, esc_type: 21, mod_id: 6, mod_rev: 0, mod_size: 4, mod_type: 1, position: 12, robot_id: 53, topology: 2}, 13: {active_ports: 3, esc_type: 21, mod_id: 4, mod_rev: 0, mod_size: 4, mod_type: 1, position: 13, robot_id: 51, topology: 2}, 14: {active_ports: 3, esc_type: 1280, mod_id: 6, mod_rev: 0, mod_size: 4, mod_type: 4, position: 14, robot_id: -1, topology: 2}, 15: {active_ports: 3, esc_type: 21, mod_id: 6, mod_rev: 0, mod_size: 4, mod_type: 1, position: 15, robot_id: 52, topology: 2}, 16: {active_ports: 3, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 16, robot_id: 56, topology: 2}, 17: {active_ports: 3, esc_type: 1280, mod_id: 6, mod_rev: 0, mod_size: 4, mod_type: 4, position: 17, robot_id: -1, topology: 2}, 18: {active_ports: 1, esc_type: 21, mod_id: 5, mod_rev: 0, mod_size: 4, mod_type: 1, position: 18, robot_id: 54, topology: 1}}"
+
+# CoNCERT robot without 3 legs
+# reply = "{1: {active_ports: 13, esc_type: 50, mod_id: 3, mod_rev: 0, mod_size: 0, mod_type: 2, position: 1, robot_id: 201, topology: 3}, 2: {active_ports: 3, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 2, robot_id: -1, topology: 2}, 3: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 3, robot_id: 11, topology: 2}, 4: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 4, robot_id: 12, topology: 1}, 5: {active_ports: 3, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 5, robot_id: 55, topology: 2}, 6: {active_ports: 3, esc_type: 21, mod_id: 6, mod_rev: 0, mod_size: 4, mod_type: 1, position: 6, robot_id: 53, topology: 2}, 7: {active_ports: 3, esc_type: 21, mod_id: 4, mod_rev: 0, mod_size: 4, mod_type: 1, position: 7, robot_id: 51, topology: 2}, 8: {active_ports: 3, esc_type: 1280, mod_id: 6, mod_rev: 0, mod_size: 4, mod_type: 4, position: 8, robot_id: -1, topology: 2}, 9: {active_ports: 3, esc_type: 21, mod_id: 6, mod_rev: 0, mod_size: 4, mod_type: 1, position: 9, robot_id: 52, topology: 2}, 10: {active_ports: 3, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 10, robot_id: 56, topology: 2}, 11: {active_ports: 3, esc_type: 1280, mod_id: 6, mod_rev: 0, mod_size: 4, mod_type: 4, position: 11, robot_id: -1, topology: 2}, 12: {active_ports: 1, esc_type: 21, mod_id: 5, mod_rev: 0, mod_size: 4, mod_type: 1, position: 12, robot_id: 54, topology: 1}}"
+
+# multi-hubs tests
+# reply = "{1: {active_ports: 15, esc_type: 50, mod_id: 3, mod_rev: 0, mod_size: 0, mod_type: 2, position: 1, robot_id: 201, topology: 4}, 2: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 2, robot_id: -1, topology: 4}, 3: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 3, robot_id: -1, topology: 4}, 4: {active_ports: 3, esc_type: 21, mod_id: 8, mod_rev: 0, mod_size: 5, mod_type: 1, position: 4, robot_id: 21, topology: 2}, 5: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 5, robot_id: 22, topology: 1}, 6: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 6, robot_id: 11, topology: 2}, 7: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 7, robot_id: 12, topology: 1}, 8: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 8, robot_id: 31, topology: 2}, 9: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 9, robot_id: 32, topology: 1}, 10: {active_ports: 3, esc_type: 21, mod_id: 8, mod_rev: 0, mod_size: 5, mod_type: 1, position: 10, robot_id: 41, topology: 2}, 11: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 11, robot_id: 42, topology: 1}, 12: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 12, robot_id: 55, topology: 1}, 13: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 13, robot_id: -1, topology: 4}, 14: {active_ports: 1, esc_type: 21, mod_id: 6, mod_rev: 0, mod_size: 4, mod_type: 1, position: 14, robot_id: 53, topology: 1}, 15: {active_ports: 1, esc_type: 21, mod_id: 2, mod_rev: 0, mod_size: 2, mod_type: 1, position: 15, robot_id: 51, topology: 1}, 16: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 2, mod_type: 1, position: 16, robot_id: 61, topology: 1}, 17: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 3, position: 17, robot_id: 71, topology: 1}}"
+
+# reply = "{1: {active_ports: 15, esc_type: 50, mod_id: 3, mod_rev: 0, mod_size: 0, mod_type: 2, position: 1, robot_id: 201, topology: 4}, 2: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 2, robot_id: -1, topology: 4}, 3: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 3, robot_id: -1, topology: 4}, 4: {active_ports: 3, esc_type: 21, mod_id: 8, mod_rev: 0, mod_size: 5, mod_type: 1, position: 4, robot_id: 21, topology: 2}, 5: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 5, robot_id: 22, topology: 1}, 6: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 6, robot_id: 11, topology: 2}, 7: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 7, robot_id: 12, topology: 1}, 8: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 8, robot_id: 31, topology: 2}, 9: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 9, robot_id: 32, topology: 1}, 10: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 10, robot_id: -1, topology: 4}, 11: {active_ports: 3, esc_type: 21, mod_id: 8, mod_rev: 0, mod_size: 5, mod_type: 1, position: 11, robot_id: 41, topology: 2}, 12: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 12, robot_id: 42, topology: 1}, 13: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 13, robot_id: 42, topology: 1}, 14: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 14, robot_id: 55, topology: 1}, 15: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 15, robot_id: 55, topology: 1}, 16: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 16, robot_id: -1, topology: 4}, 17: {active_ports: 1, esc_type: 21, mod_id: 6, mod_rev: 0, mod_size: 4, mod_type: 1, position: 17, robot_id: 53, topology: 1}, 18: {active_ports: 1, esc_type: 21, mod_id: 2, mod_rev: 0, mod_size: 2, mod_type: 1, position: 18, robot_id: 51, topology: 1}, 19: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 2, mod_type: 1, position: 19, robot_id: 61, topology: 1}, 20: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 20, robot_id: -1, topology: 4}, 21: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 3, position: 21, robot_id: 71, topology: 1}, 22: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 22, robot_id: 71, topology: 1}, 23: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 23, robot_id: 71, topology: 1}}"
+
+# test scenario with hub tree depth > 2. not working yet!
+# reply = "{1: {active_ports: 13, esc_type: 50, mod_id: 3, mod_rev: 0, mod_size: 0, mod_type: 2, position: 1, robot_id: 201, topology: 3}, 2: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 2, robot_id: -1, topology: 4}, 3: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 3, robot_id: -1, topology: 4}, 4: {active_ports: 3, esc_type: 21, mod_id: 8, mod_rev: 0, mod_size: 5, mod_type: 1, position: 4, robot_id: 21, topology: 2}, 5: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 5, robot_id: 22, topology: 1}, 6: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 6, robot_id: 11, topology: 2}, 7: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 7, robot_id: 12, topology: 1}, 8: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 8, robot_id: 31, topology: 2}, 9: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 9, robot_id: 32, topology: 1}, 10: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 10, robot_id: -1, topology: 4}, 11: {active_ports: 3, esc_type: 21, mod_id: 8, mod_rev: 0, mod_size: 5, mod_type: 1, position: 11, robot_id: 41, topology: 2}, 12: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 12, robot_id: 42, topology: 1}, 13: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 13, robot_id: -1, topology: 4}, 14: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 14, robot_id: 42, topology: 1}, 15: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 15, robot_id: 55, topology: 1}, 16: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 16, robot_id: 55, topology: 1}, 17: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 17, robot_id: 71, topology: 1}, 18: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 18, robot_id: 71, topology: 1}, 19: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 19, robot_id: -1, topology: 4}, 20: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 3, position: 20, robot_id: 71, topology: 1}, 21: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 21, robot_id: 71, topology: 1}, 22: {active_ports: 1, esc_type: 21, mod_id: 3, mod_rev: 0, mod_size: 4, mod_type: 1, position: 22, robot_id: 71, topology: 1}}"
+
+# mobile base only
+# reply = "{1: {active_ports: 11, esc_type: 50, mod_id: 3, mod_rev: 0, mod_size: 0, mod_type: 2, position: 1, robot_id: 201, topology: 4}, 2: {active_ports: 15, esc_type: 256, mod_id: 4, mod_rev: 0, mod_size: 0, mod_type: 2, position: 2, robot_id: -1, topology: 4}, 3: {active_ports: 3, esc_type: 21, mod_id: 8, mod_rev: 0, mod_size: 5, mod_type: 1, position: 3, robot_id: 21, topology: 2}, 4: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 4, robot_id: 22, topology: 1}, 5: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 5, robot_id: 11, topology: 2}, 6: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 6, robot_id: 12, topology: 1}, 7: {active_ports: 3, esc_type: 21, mod_id: 7, mod_rev: 0, mod_size: 5, mod_type: 1, position: 7, robot_id: 31, topology: 2}, 8: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 8, robot_id: 32, topology: 1}, 9: {active_ports: 3, esc_type: 21, mod_id: 8, mod_rev: 0, mod_size: 5, mod_type: 1, position: 9, robot_id: 41, topology: 2}, 10: {active_ports: 1, esc_type: 21, mod_id: 1, mod_rev: 0, mod_size: 5, mod_type: 5, position: 10, robot_id: 42, topology: 1}}"
data = urdf_writer_fromHW.read_from_json(reply)
diff --git a/setup.cfg b/setup.cfg
index 6be53ea..f7dfc3b 100644
--- a/setup.cfg
+++ b/setup.cfg
@@ -29,10 +29,14 @@ install_requires =
defusedxml
PyYaml
rospkg
+ scipy
+ pin
+ apscheduler
+ gunicorn
[options.packages.find]
where = src
[options.entry_points]
console_scripts =
- robot-design-studio = modular.web.RobotDesignStudio:main
\ No newline at end of file
+ robot-design-studio = modular.web.RobotDesignStudio:main
diff --git a/src/modular/ModelStats.py b/src/modular/ModelStats.py
new file mode 100644
index 0000000..31d1e4e
--- /dev/null
+++ b/src/modular/ModelStats.py
@@ -0,0 +1,165 @@
+import pinocchio
+import numpy as np
+import scipy.optimize
+
+from modular.enums import ModuleClass
+class ModelStats:
+ def __init__(self, urdf_writer):
+ self.urdf_writer = urdf_writer
+
+ # ensure the urdf string has been already generated
+ if getattr(self.urdf_writer, 'urdf_string', None) is None:
+ self.urdf_writer.write_urdf()
+
+ self.update_model()
+
+ def update_model(self):
+ # Load the urdf model
+ self.model = pinocchio.buildModelFromXML(self.urdf_writer.urdf_string)
+
+ # Create data required by the algorithms
+ self.data = self.model.createData()
+
+ # Get the tip link name
+ # HACK: we take the last chain in the list of chains. This should be changed to be the one selected by the user
+ if len(self.urdf_writer.listofchains) > 0:
+ self.tip_link_name = self.urdf_writer.find_chain_tip_link(self.urdf_writer.listofchains[-1])
+ else:
+ self.tip_link_name = 'base_link'
+
+ # Get the frame index for the end-effector
+ self.frame_idx = self.model.getFrameId(self.tip_link_name) # 'TCP_gripper_A'
+
+ self.lower_limits = self.model.lowerPositionLimit
+ self.upper_limits = self.model.upperPositionLimit
+
+ self.nq = self.model.nq
+
+ def compute_payload(self, n_samples=10000):
+ ## Random Sampling
+ samples = n_samples
+ q_configurations = [pinocchio.randomConfiguration(self.model) for i in range(samples)]
+
+ # Solve a linear programming problem to get the worst case force and therefore the worst case payload
+ # minimize:
+ # c @ x
+ # such that:
+ # A_ub @ x <= b_ub
+ # A_eq @ x == b_eq
+ # lb <= x <= ub
+
+ c = np.array([0, 0, -1, 0, 0, 0])
+
+ lb = np.zeros(6)
+ ub = np.array([0, 0, np.inf, 0, 0, 0])
+
+ self.worst_case_force = np.array([0, 0, np.inf, 0, 0, 0])
+ self.worst_case_q = np.zeros((self.nq))
+ self.worst_case_tau = np.zeros((self.nq))
+ self.worst_case_b = np.zeros((self.nq))
+ self.worst_case_A = np.zeros((self.nq, 6))
+
+ zeros = np.zeros((self.nq))
+ q = np.zeros((self.nq))
+ A = np.zeros((self.nq, 6))
+ b = np.zeros((self.nq))
+ tau_rated = 162.0
+ tau_max = np.ones((self.nq))*tau_rated
+ tau_min = - tau_max
+
+ # Compute the jacobian and gravity torques for all the samples. Then, compute the worst case force -> overall payload
+ for idx, q in enumerate(q_configurations):
+
+ pinocchio.computeJointJacobians(self.model, self.data, q)
+ # pinocchio.framesForwardKinematics(model, data, q)
+ A = pinocchio.getFrameJacobian(self.model, self.data, self.frame_idx, pinocchio.ReferenceFrame.LOCAL_WORLD_ALIGNED)[:6].T * 1 # 9.81
+ tau = pinocchio.nonLinearEffects(self.model, self.data, q, zeros)
+
+ b1 = tau_max - tau
+ b2 = - tau_min + tau
+ b = np.concatenate((b1, b2))
+ A1 = A
+ A2 = -A
+ A = np.vstack((A1, A2))
+
+ sol = scipy.optimize.linprog(c, A_ub=A, b_ub=b, bounds=list(zip(lb, ub)))
+
+ if (sol.success):
+ # print (sol.x / 9.81)
+ if sol.x[2]/9.81 < self.worst_case_force[2]/9.81:
+ self.worst_case_force = sol.x
+ self.worst_case_q = q
+ self.worst_case_tau = tau
+ self.worst_case_b = b
+ self.worst_case_A = A
+
+ self.payload = self.worst_case_force[2]/9.81
+
+ return self.payload
+
+ def get_payload(self):
+ return self.payload
+
+ def compute_max_reach(self, n_samples=10000):
+ self.max_reach = None
+ return self.max_reach
+
+ def get_max_reach(self):
+ return self.max_reach
+
+ def compute_modules(self):
+ n_modules = 0
+ for chain in self.urdf_writer.listofchains:
+ for module in chain:
+ if module.is_structural:
+ n_modules += 1
+ self.n_modules = n_modules
+ return self.n_modules
+
+ def get_modules(self):
+ return self.n_modules
+
+ def compute_joint_modules(self):
+ n_joint_modules = 0
+ for chain in self.urdf_writer.listofchains:
+ for module in chain:
+ if module in ModuleClass.joint_modules():
+ n_joint_modules += 1
+ self.n_joint_modules = n_joint_modules
+ return self.n_joint_modules
+
+ def get_joint_modules(self):
+ return self.n_joint_modules
+
+ def compute_stats(self, n_samples):
+ try:
+ self.payload = self.compute_payload(n_samples=n_samples)
+ except RuntimeError as e:
+ self.payload = None
+
+ try:
+ self.max_reach = self.compute_max_reach(n_samples=n_samples)
+ except e:
+ self.max_reach = None
+
+ try:
+ self.n_modules = self.compute_modules()
+ except e:
+ self.n_modules = None
+
+ try:
+ self.n_joint_modules = self.compute_modules()
+ except e:
+ self.n_joint_modules = None
+
+ return self.get_stats()
+
+ def get_stats(self):
+ stats={
+ 'modules': self.n_modules,
+ 'joint_modules': self.n_joint_modules,
+ 'payload': self.payload,
+ 'max_reach': self.max_reach
+ }
+
+ return stats
\ No newline at end of file
diff --git a/src/modular/ModuleNode.py b/src/modular/ModuleNode.py
index f19d5d1..3360aa2 100644
--- a/src/modular/ModuleNode.py
+++ b/src/modular/ModuleNode.py
@@ -9,36 +9,10 @@
import sys
import os
import tf
-from enum import Enum
+
import anytree
-from modular.utils import ResourceFinder
-
-class ModuleDescriptionFormat(Enum):
- YAML = 1 # YAML format used internally in HHCM
- JSON = 2 # JSON format used for the CONCERT project
-
-class KinematicsConvention(str, Enum):
- """Kinematic convention used to define the rototranslation between two modules"""
- DH_EXT = 'DH_ext' # extended Denavit-Hartenberg convention. See https://mediatum.ub.tum.de/doc/1280464/file.pdf
- URDF = 'urdf' # URDF convention
- AFFINE = 'affine_tf_matrix' # Affine trasformation matrix convention
-
-class ModuleType(str, Enum):
- """Type of module"""
- LINK = 'link'
- JOINT = 'joint'
- CUBE = 'cube'
- WHEEL = 'wheel'
- TOOL_EXCHANGER = 'tool_exchanger'
- GRIPPER = 'gripper'
- MOBILE_BASE = 'mobile_base'
- BASE_LINK = 'base_link'
- SIZE_ADAPTER = 'size_adapter'
- SIMPLE_EE = 'simple_ee'
- END_EFFECTOR = 'end_effector'
- DRILL = 'drill'
- DAGANA = 'dagana'
+from modular.enums import ModuleDescriptionFormat, KinematicsConvention, ModuleType, ModuleClass
# import collections.abc
def update_nested_dict(d, u):
@@ -105,7 +79,9 @@ def parse_dict(self, d):
def type_dispatcher(self, d):
"""Dispatch the parsing of the dictionary d according to the module type"""
- if self.owner.type in {ModuleType.LINK, ModuleType.GRIPPER, ModuleType.TOOL_EXCHANGER, ModuleType.SIZE_ADAPTER, ModuleType.END_EFFECTOR, ModuleType.DRILL}:
+ header_obj = getattr(self.owner, "header")
+ update_nested_dict(header_obj.__dict__, d['header'])
+ if self.owner.type in ModuleClass.link_modules() | ModuleClass.end_effector_modules() - {ModuleType.DAGANA}:
if len(d['joints']) != 0:
raise ValueError('A link must have no joints')
if len(d['bodies']) != 1:
@@ -136,7 +112,7 @@ def type_dispatcher(self, d):
self.owner.size_in = d['bodies'][0]['connectors'][0]['size']
else:
self.owner.flange_size = output_flange_size
- elif self.owner.type in {ModuleType.JOINT, ModuleType.WHEEL}:
+ elif self.owner.type in ModuleClass.joint_modules():
if len(d['joints']) != 1:
raise ValueError('A joint must have exactly one joint')
if len(d['bodies']) != 2:
@@ -185,7 +161,7 @@ def type_dispatcher(self, d):
self.owner.CentAcESC = Module.Attribute(dict_joint['control_parameters']['xbot'])
# xbot_gz
self.owner.xbot_gz = Module.Attribute(dict_joint['control_parameters']['xbot_gz'])
- elif self.owner.type in {ModuleType.CUBE, ModuleType.MOBILE_BASE}:
+ elif self.owner.type in ModuleClass.hub_modules():
if len(d['joints']) != 0:
raise ValueError('A hub must have no joints')
if len(d['bodies']) != 1:
@@ -469,9 +445,9 @@ def get_homogeneous_matrix(self, reverse):
pass
def get_hub_connections_tf(self, reverse):
- """Computes the homogeneous transformation matrices for the 4 cube connections"""
+ """Computes the homogeneous transformation matrices for the 4 hub connections"""
origin, xaxis, yaxis, zaxis = (0, 0, 0), (1, 0, 0), (0, 1, 0), (0, 0, 1)
- max_num_con = 10
+ max_num_con = 20
for i in range(1, max_num_con):
if hasattr(self.kinematics, "connector_{}".format(i)):
@@ -528,14 +504,15 @@ def get_transform(self, reverse):
'joint': self.get_proximal_distal_matrices,
'wheel': self.get_proximal_distal_matrices,
'link': self.get_homogeneous_matrix,
+ 'socket': self.get_homogeneous_matrix,
'size_adapter': self.get_homogeneous_matrix,
'tool_exchanger': self.get_homogeneous_matrix,
'end_effector': self.get_homogeneous_matrix,
'drill': self.get_homogeneous_matrix,
'dagana': lambda reverse: None,
'gripper': self.get_homogeneous_matrix,
- 'cube': self.get_hub_connections_tf, # self.get_cube_connections_tf,
- 'mobile_base': self.get_hub_connections_tf, # self.get_mobile_base_connections_tf,
+ 'cube': self.get_hub_connections_tf,
+ 'mobile_base': self.get_hub_connections_tf,
'base_link': tf.transformations.identity_matrix()
}
return switcher.get(x, 'Invalid type')(reverse)
@@ -606,11 +583,20 @@ def module_from_yaml(filename, father=None, yaml_template=None, reverse=False):
print(exc)
# Create an instance of a ModuleNode class from the dictionary obtained from YAML
result = ModuleNode(data, filename, format=ModuleDescriptionFormat.YAML, parent=father, template_dictionary=template_data)
- # result.set_type(filename)
result.get_transform(reverse)
return result
-
+#
+def module_from_yaml_dict(yaml_dict, father=None, yaml_template_dict=None, reverse=False):
+ """Function parsing YAML dictionary describing a generic module and returning an instance of a Module class"""
+ if yaml_template_dict:
+ template_dict = yaml_template_dict
+ else:
+ template_dict = {}
+ # Create an instance of a ModuleNode class from the dictionary obtained from YAML
+ result = ModuleNode(yaml_dict, yaml_dict['header']['name'], format=ModuleDescriptionFormat.YAML, parent=father, template_dictionary=template_dict)
+ result.get_transform(reverse)
+ return result
#
def module_from_json(filename, father=None, yaml_template=None, reverse=False):
"""Function parsing JSON file describing a generic module and returning an instance of a Module class"""
@@ -632,6 +618,17 @@ def module_from_json(filename, father=None, yaml_template=None, reverse=False):
result.get_transform(reverse)
return result
+#
+def module_from_json_dict(json_dict, father=None, yaml_template_dict=None, reverse=False):
+ """Function parsing JSON dictionary describing a generic module and returning an instance of a Module class"""
+ if yaml_template_dict:
+ template_dict = yaml_template_dict
+ else:
+ template_dict = {}
+ # Create an instance of a ModuleNode class from the dictionary obtained from JSON
+ result = ModuleNode(json_dict, json_dict['header']['name'], format=ModuleDescriptionFormat.JSON, parent=father, template_dictionary=template_dict)
+ result.get_transform(reverse)
+ return result
def main():
# module = module_from_yaml(sys.argv[1], None, False)
diff --git a/src/modular/URDF_writer.py b/src/modular/URDF_writer.py
index d52534a..9845c12 100644
--- a/src/modular/URDF_writer.py
+++ b/src/modular/URDF_writer.py
@@ -1,3 +1,8 @@
+#!/usr/bin/env python3
+# Disable some of the pylint violations in this file
+# see https://pylint.pycqa.org/en/latest/user_guide/messages/message_control.html#block-disables
+# pylint: disable=line-too-long, missing-function-docstring, missing-module-docstring
+
from __future__ import print_function
from future.utils import iteritems
from abc import ABCMeta, abstractmethod
@@ -24,8 +29,10 @@
import copy
from collections import OrderedDict
-from modular.utils import ResourceFinder
-import modular.ModuleNode as ModuleNode
+from modular.utils import ResourceFinder, ModularResourcesManager
+from modular.enums import ModuleType, ModuleClass
+from modular.ModelStats import ModelStats
+import modular.ModuleNode as ModuleNode
import argparse
import rospy
@@ -66,6 +73,12 @@
# Use /tmp folder to store urdf, srdf, etc.
path_name = "/tmp"
+from enum import Enum
+class SlaveDescMode(str, Enum):
+ """Slave description mode"""
+ USE_POSITIONS = 'use_pos'
+ USE_IDS = 'use_ids'
+
# noinspection PyPep8Naming
def ordered_load(stream, Loader=yaml.SafeLoader, object_pairs_hook=OrderedDict):
class OrderedLoader(Loader):
@@ -166,6 +179,8 @@ def write_srdf(self, builder_joint_map=None):
root = ET.Element('robot', name="ModularBot")
+ active_modules_chains = []
+
groups = []
chains = []
joints = []
@@ -173,64 +188,54 @@ def write_srdf(self, builder_joint_map=None):
end_effectors = []
groups_in_chains_group = []
groups_in_arms_group = []
- i = 0
- self.urdf_writer.print(self.urdf_writer.listofchains)
- for joints_chain in self.urdf_writer.listofchains:
- group_name = "chain" + self.urdf_writer.branch_switcher.get(i + 1)
- # group_name = "arm" + self.urdf_writer.branch_switcher.get(i + 1)
+ active_modules_chains = self.urdf_writer.get_actuated_modules_chains()
+ self.urdf_writer.print(active_modules_chains)
+
+ for idx, joints_chain in enumerate(active_modules_chains):
+ group_name = "chain" + self.urdf_writer.find_chain_tag(joints_chain)
groups.append(ET.SubElement(root, 'group', name=group_name))
base_link = self.urdf_writer.find_chain_base_link(joints_chain)
tip_link = self.urdf_writer.find_chain_tip_link(joints_chain)
- chains.append(ET.SubElement(groups[i], 'chain', base_link=base_link, tip_link=tip_link))
- i += 1
- i = 0
- arms_group = ET.SubElement(root, 'group', name="arms")
+ chains.append(ET.SubElement(groups[idx], 'chain', base_link=base_link, tip_link=tip_link))
+
+ # Create groups for chains, arms and wheels. Also 'group_state' for homing
chains_group = ET.SubElement(root, 'group', name="chains")
+ arms_group = ET.SubElement(root, 'group', name="arms")
wheels_group = self.add_wheel_group_to_srdf(root, "wheels")
group_state = ET.SubElement(root, 'group_state', name="home", group="chains")
- for joints_chain in self.urdf_writer.listofchains:
- group_name = "chain" + self.urdf_writer.branch_switcher.get(i + 1)
+
+ for joints_chain in active_modules_chains:
+ group_name = "chain" + self.urdf_writer.find_chain_tag(joints_chain)
groups_in_chains_group.append(ET.SubElement(chains_group, 'group', name=group_name))
- groups_in_arms_group.append(ET.SubElement(arms_group, 'group', name=group_name))
for joint_module in joints_chain:
- if joint_module.type == 'joint':
- # Homing state
- if builder_joint_map is not None:
- homing_value = float(builder_joint_map[joint_module.name]['angle'])
- else:
- homing_value = 0.1
- # self.urdf_writer.print(homing_value)
- joints.append(ET.SubElement(group_state, 'joint', name=joint_module.name, value=str(homing_value)))
- elif joint_module.type == 'dagana':
- # Homing state
- if builder_joint_map is not None:
- homing_value = float(builder_joint_map[joint_module.dagana_joint_name]['angle'])
- else:
- homing_value = 0.1
- # self.urdf_writer.print(homing_value)
- joints.append(ET.SubElement(group_state, 'joint', name=joint_module.dagana_joint_name, value=str(homing_value)))
- elif joint_module.type == 'wheel':
- # Homing state
+ # add joints chain to srdf end-effectors group
+ if joint_module.type in ModuleClass.end_effector_modules():
+ groups_in_arms_group.append(ET.SubElement(arms_group, 'group', name=group_name))
+ # TODO: add end-effector module to srdf end-effectors group. To be fixed for all end-effector types.
+ # add wheel module to srdf wheels group
+ if joint_module.type is ModuleType.WHEEL:
+ wheels += filter(lambda item: item is not None, [self.add_wheel_to_srdf(wheels_group, joint_module.name)])
+ # add homing state for each joint-like module. Also create custom groups for some end-effectors
+ if joint_module.type in ModuleClass.joint_modules() | {ModuleType.DAGANA}:
+ joint_name = self.urdf_writer.get_joint_name(joint_module)
if builder_joint_map is not None:
- homing_value = float(builder_joint_map[joint_module.name]['angle'])
+ homing_value = float(builder_joint_map[joint_name])
else:
homing_value = 0.1
- # self.urdf_writer.print(homing_value)
- joints.append(ET.SubElement(group_state, 'joint', name=joint_module.name, value=str(homing_value)))
-
- #wheel_name = "wheel" + self.urdf_writer.branch_switcher.get(i + 1) # BUG: this is not correct. Probably better to get the tag from the name
- wheels += filter(lambda item: item is not None, [self.add_wheel_to_srdf(wheels_group, joint_module.name)])
- elif joint_module.type == 'tool_exchanger':
+ joints.append(ET.SubElement(group_state,
+ 'joint',
+ name=joint_name,
+ value=str(homing_value)))
+ elif joint_module.type is ModuleType.TOOL_EXCHANGER:
tool_exchanger_group = ET.SubElement(root, 'group', name="ToolExchanger")
- end_effectors.append(ET.SubElement(tool_exchanger_group, 'joint',
+ end_effectors.append(ET.SubElement(tool_exchanger_group,
+ 'joint',
name=joint_module.name + '_fixed_joint'))
- elif joint_module.type == 'gripper':
- hand_name = "hand" + self.urdf_writer.branch_switcher.get(i + 1)
+ elif joint_module.type is ModuleType.GRIPPER:
+ hand_name = "hand" + self.urdf_writer.find_chain_tag(joints_chain)
self.add_hand_group_to_srdf(root, joint_module.name, hand_name)
- # groups_in_hands_group.append(ET.SubElement(hands_group, 'group', name=hand_name))
end_effectors += filter(lambda item: item is not None, [self.add_gripper_to_srdf(root, joint_module.name, hand_name, group_name)])
- i += 1
xmlstr = xml.dom.minidom.parseString(ET.tostring(root)).toprettyxml(indent=" ")
@@ -256,12 +261,12 @@ def write_joint_map(self, use_robot_id=False):
joint_map['joint_map'][i] = "HUB_" + str(i)
for joints_chain in self.urdf_writer.listofchains:
for joint_module in joints_chain:
- if joint_module.type not in {'joint', 'dagana', 'wheel', 'tool_exchanger', 'gripper', 'drill'}:
+ if joint_module.type in ModuleClass.nonactuated_modules():
continue
i += 1
- if joint_module.type == 'tool_exchanger':
+ if joint_module.type is ModuleType.TOOL_EXCHANGER:
name = joint_module.name + '_fixed_joint'
- elif joint_module.type == 'gripper':
+ elif joint_module.type is ModuleType.GRIPPER:
name = joint_module.name + '_fixed_joint'
else:
name = joint_module.name
@@ -355,7 +360,6 @@ def write_srdf(self, builder_joint_map=None):
groups_in_chains_group = []
groups_in_arms_group = []
# groups_in_hands_group = []
- i = 0
# MoveIt
controller_list = []
@@ -388,15 +392,12 @@ def write_srdf(self, builder_joint_map=None):
ompl.update([('planner_configs', copy.deepcopy(tmp_ompl['planner_configs']))])
self.urdf_writer.print(self.urdf_writer.listofchains)
- for joints_chain in self.urdf_writer.listofchains:
- group_name = "arm" + self.urdf_writer.branch_switcher.get(i + 1)
- #group_name = "chain_"+str(i+1)
+ for idx, joints_chain in enumerate(self.urdf_writer.listofchains):
+ group_name = "arm" + self.urdf_writer.find_chain_tag(joints_chain)
groups.append(ET.SubElement(root, 'group', name=group_name))
base_link = self.urdf_writer.find_chain_base_link(joints_chain)
tip_link = self.urdf_writer.find_chain_tip_link(joints_chain)
- chains.append(ET.SubElement(groups[i], 'chain', base_link=base_link, tip_link=tip_link))
- i += 1
- i = 0
+ chains.append(ET.SubElement(groups[idx], 'chain', base_link=base_link, tip_link=tip_link))
arms_group = ET.SubElement(root, 'group', name="arms")
#chains_group = ET.SubElement(root, 'group', name="chains")
group_state = ET.SubElement(root, 'group_state', name="home", group="chains")
@@ -404,21 +405,21 @@ def write_srdf(self, builder_joint_map=None):
hands_group = ET.SubElement(root, 'group', name="hands")
# MoveIt
initial_poses.append(OrderedDict([('group', 'arms'), ('pose', 'home')]))
- for joints_chain in self.urdf_writer.listofchains:
- #group_name = "chain_"+str(i+1)
+ for idx, joints_chain in enumerate(self.urdf_writer.listofchains):
+ #group_name = "chain" + self.urdf_writer.find_chain_tag(joints_chain)
#groups_in_chains_group.append(ET.SubElement(chains_group, 'group', name=group_name))
- group_name = "arm" + self.urdf_writer.branch_switcher.get(i + 1)
- hand_name = "hand" + self.urdf_writer.branch_switcher.get(i + 1)
+ group_name = "arm" + self.urdf_writer.find_chain_tag(joints_chain)
+ hand_name = "hand" + self.urdf_writer.find_chain_tag(joints_chain)
groups_in_arms_group.append(ET.SubElement(arms_group, 'group', name=group_name))
# MoveIt: create controller list
controller_list.append(OrderedDict([('name', 'fake_'+group_name+'_controller'), ('joints', [])]))
kinematics.update([(group_name, copy.deepcopy(tmp_kinematics['group_name']))])
ompl.update([(group_name, copy.deepcopy(tmp_ompl['group_name']))])
for joint_module in joints_chain:
- if joint_module.type in {'joint', 'dagana', 'wheel'} :
+ if joint_module.type in ModuleClass.joint_modules() | {ModuleType.DAGANA}:
# Homing state
if builder_joint_map is not None:
- homing_value = float(builder_joint_map[joint_module.name]['angle'])
+ homing_value = float(builder_joint_map[joint_module.name])
else:
homing_value = 0.1
#self.urdf_writer.print(homing_value)
@@ -426,24 +427,23 @@ def write_srdf(self, builder_joint_map=None):
# Disable collision
# disable_collision = ET.SubElement(root, 'disable_collisions', link1=joint_module.stator_name, link2=joint_module.distal_link_name, reason='Adjacent')
# MoveIt: add joints to controller
- controller_list[i]['joints'].append(joint_module.name)
+ controller_list[idx]['joints'].append(joint_module.name)
hardware_interface_joints.append(joint_module.name)
- elif joint_module.type == 'tool_exchanger':
+ elif joint_module.type is ModuleType.TOOL_EXCHANGER:
tool_exchanger_group = ET.SubElement(root, 'group', name="ToolExchanger")
end_effectors.append(ET.SubElement(tool_exchanger_group, 'joint',
name=joint_module.name + '_fixed_joint'))
- elif joint_module.type == 'gripper':
+ elif joint_module.type is ModuleType.GRIPPER:
self.add_hand_group_to_srdf(root, joint_module.name, hand_name)
# groups_in_hands_group.append(ET.SubElement(hands_group, 'group', name=hand_name))
end_effectors += filter(lambda item: item is not None, [self.add_gripper_to_srdf(root, joint_module.name, hand_name, group_name)])
controller_list.append(OrderedDict([('name', 'fake_' + hand_name + '_controller'), ('joints', [])]))
- controller_list[i+1]['joints'].append(joint_module.name+'_finger_joint1')
- controller_list[i+1]['joints'].append(joint_module.name + '_finger_joint2')
+ controller_list[idx+1]['joints'].append(joint_module.name+'_finger_joint1')
+ controller_list[idx+1]['joints'].append(joint_module.name + '_finger_joint2')
hardware_interface_joints.append(joint_module.name + '_finger_joint1')
initial_poses.append(OrderedDict([('group', hand_name), ('pose', 'open')]))
ompl.update([(hand_name, copy.deepcopy(tmp_ompl['group_name']))])
ompl.update([('arm_'+hand_name, copy.deepcopy(tmp_ompl['group_name']))])
- i += 1
# MoveIt: add virtual joint
# ET.SubElement(root, "virtual_joint", name="virtual_joint", type="floating", parent_frame="world", child_link="base_link")
@@ -563,7 +563,6 @@ def write_lowlevel_config(self, use_robot_id=False):
with open(basic_config_filename, 'r') as stream:
try:
lowlevel_config = ordered_load(stream, yaml.SafeLoader)
- # cartesio_stack['EE']['base_link'] = self.urdf_writer.listofchains[0]
self.urdf_writer.print(list(lowlevel_config.items())[0])
except yaml.YAMLError as exc:
self.urdf_writer.print(exc)
@@ -577,9 +576,9 @@ def write_lowlevel_config(self, use_robot_id=False):
# HACK
p += 1
for joint_module in joints_chain:
- if joint_module.type not in {'joint', 'dagana', 'wheel', 'tool_exchanger', 'gripper'}:
+ if joint_module.type in ModuleClass.nonactuated_modules():
continue
- if joint_module.type in { 'joint', 'wheel' }:
+ if joint_module.type in ModuleClass.joint_modules():
i += 1
lowlevel_config['GazeboXBotPlugin']['gains'][joint_module.name] = OrderedDict(
[('p', 300), ('d', 20)])
@@ -595,7 +594,7 @@ def write_lowlevel_config(self, use_robot_id=False):
# TODO: fix this
if p > 1:
value.pid.impedance = [500.0, 20.0, 1.0, 0.003, 0.99]
- elif joint_module.type == 'tool_exchanger':
+ elif joint_module.type is ModuleType.TOOL_EXCHANGER:
if use_robot_id:
key = 'AinMsp432ESC_' + str(joint_module.robot_id)
xbot_ecat_interface = [[int(joint_module.robot_id)], "libXBotEcat_ToolExchanger"]
@@ -605,7 +604,7 @@ def write_lowlevel_config(self, use_robot_id=False):
value = joint_module.AinMsp432ESC
self.urdf_writer.print(yaml.dump(joint_module.AinMsp432ESC))
lowlevel_config['HALInterface']['IEndEffectors'].append(xbot_ecat_interface)
- elif joint_module.type == 'gripper':
+ elif joint_module.type is ModuleType.GRIPPER:
if use_robot_id:
key = 'LpESC_' + str(joint_module.robot_id)
xbot_ecat_interface = [[int(joint_module.robot_id)], "libXBotEcat_Gripper"]
@@ -663,7 +662,7 @@ def remove_joint(self, joint_name):
if pid.attrib['name'] == joint_name:
self.pid_node.remove(pid)
- # SRDF
+ # SRDF
def add_gripper_to_srdf(self, root, gripper_name, hand_name, parent_group_name):
return None
@@ -699,14 +698,12 @@ def write_joint_map(self, use_robot_id=False):
joint_map['joint_map'][i] = "HUB_" + str(i)
for joints_chain in self.urdf_writer.listofchains:
for joint_module in joints_chain:
- if joint_module.type not in {'joint', 'dagana', 'wheel', 'tool_exchanger', 'gripper', 'drill'}:
+ if joint_module.type in ModuleClass.nonactuated_modules():
continue
i += 1
- if joint_module.type == 'tool_exchanger':
+ if joint_module.type is ModuleType.TOOL_EXCHANGER:
name = joint_module.name + '_fixed_joint'
- elif joint_module.type == 'dagana':
- name = joint_module.dagana_joint_name
- elif joint_module.type == 'gripper':
+ elif joint_module.type is ModuleType.GRIPPER:
name = joint_module.name
fingers = [name + '_rightfinger', name + '_leftfinger']
if use_robot_id:
@@ -714,7 +711,7 @@ def write_joint_map(self, use_robot_id=False):
else:
joint_map['albero_gripper_map'][i] = {'name': name, 'fingers': fingers}
else:
- name = joint_module.name
+ name = self.urdf_writer.get_joint_name(joint_module)
if use_robot_id:
joint_map['joint_map'][int(joint_module.robot_id)] = name
@@ -758,10 +755,10 @@ def write_lowlevel_config(self, use_robot_id=False):
i = 0
for joints_chain in self.urdf_writer.listofchains:
for joint_module in joints_chain:
- if joint_module.type not in {'joint', 'dagana', 'wheel', 'tool_exchanger', 'gripper', 'drill'}:
+ if joint_module.type in ModuleClass.nonactuated_modules():
continue
i += 1
- if joint_module.type in ('tool_exchanger', 'gripper'):
+ if joint_module.type in {ModuleType.TOOL_EXCHANGER, ModuleType.GRIPPER}:
if use_robot_id:
mod_id = str(joint_module.robot_id)
else:
@@ -774,7 +771,7 @@ def write_lowlevel_config(self, use_robot_id=False):
i = 0
for joints_chain in self.urdf_writer.listofchains:
for joint_module in joints_chain:
- if joint_module.type =='dagana':
+ if joint_module.type is ModuleType.DAGANA:
attrs = [a for a in dir(joint_module.joint_gripper_adapter) if not a.startswith('__') and not callable(getattr(joint_module.joint_gripper_adapter, a))]
attrs_with_prefix = [joint_module.name+"/" + x for x in attrs]
@@ -852,21 +849,18 @@ def write_lowlevel_config(self, use_robot_id=False):
# HACK
p += 1
for joint_module in joints_chain:
- if joint_module.type not in {'joint', 'dagana', 'wheel', 'tool_exchanger', 'gripper', 'drill'}:
+ if joint_module.type in ModuleClass.nonactuated_modules():
continue
- if joint_module.type in ['joint', 'dagana']:
- if joint_module.type == 'dagana':
- key = joint_module.dagana_joint_name
- else:
- key = joint_module.name
+ if joint_module.type in {ModuleType.JOINT, ModuleType.DAGANA}:
+ key = self.urdf_writer.get_joint_name(joint_module)
value = joint_module.CentAcESC
# Remove parameters that are now not used by XBot2 (they are handled by the EtherCat master on a different config file)
if hasattr(value, 'sign'):
- del value.sign
+ del value.sign
if hasattr(value, 'pos_offset'):
- del value.pos_offset
+ del value.pos_offset
if hasattr(value, 'max_current_A'):
- del value.max_current_A
+ del value.max_current_A
impd4_joint_config[key] = copy.deepcopy(value)
impd4_joint_config[key].control_mode = 'D4_impedance_ctrl'
@@ -899,16 +893,16 @@ def write_lowlevel_config(self, use_robot_id=False):
# if p > 1:
# value.pid.impedance = [500.0, 20.0, 1.0, 0.003, 0.99]
- elif joint_module.type == 'wheel':
- key = joint_module.name
+ elif joint_module.type is ModuleType.WHEEL:
+ key = self.urdf_writer.get_joint_name(joint_module)
value = joint_module.CentAcESC
# Remove parameters that are now not used by XBot2 (they are handled by the EtherCat master on a different config file)
if hasattr(value, 'sign'):
- del value.sign
+ del value.sign
if hasattr(value, 'pos_offset'):
- del value.pos_offset
+ del value.pos_offset
if hasattr(value, 'max_current_A'):
- del value.max_current_A
+ del value.max_current_A
impd4_joint_config[key] = copy.deepcopy(value)
impd4_joint_config[key].control_mode = '71_motor_vel_ctrl'
@@ -922,31 +916,20 @@ def write_lowlevel_config(self, use_robot_id=False):
if hasattr(idle_joint_config[key].pid, 'velocity'):
del idle_joint_config[key].pid.velocity
- elif joint_module.type == 'dagana':
- key = joint_module.name
- value = joint_module.CentAcESC
- # Remove parameters that are now not used by XBot2 (they are handled by the EtherCat master on a different config file)
- if hasattr(value, 'sign'):
- del value.sign
- if hasattr(value, 'pos_offset'):
- del value.pos_offset
- if hasattr(value, 'max_current_A'):
- del value.max_current_A
-
- elif joint_module.type == 'tool_exchanger':
+ elif joint_module.type is ModuleType.TOOL_EXCHANGER:
key = joint_module.name
value = joint_module.AinMsp432ESC
- elif joint_module.type == 'gripper':
+ elif joint_module.type is ModuleType.GRIPPER:
key = joint_module.name + '_motor'
value = joint_module.LpESC
# Remove parameters that are now not used by XBot2 (they are handled by the EtherCat master on a different config file)
if hasattr(value, 'sign'):
- del value.sign
+ del value.sign
if hasattr(value, 'pos_offset'):
- del value.pos_offset
+ del value.pos_offset
if hasattr(value, 'max_current_A'):
- del value.max_current_A
+ del value.max_current_A
impd4_joint_config[key] = copy.deepcopy(value)
impd4_joint_config[key].control_mode = '3B_motor_pos_ctrl'
@@ -957,9 +940,9 @@ def write_lowlevel_config(self, use_robot_id=False):
# idle_joint_config[key] = copy.deepcopy(value)
# idle_joint_config[key].control_mode = 'idle'
# Remove parameters that are now not used by XBot2 (they are handled by the EtherCat master on a different config file)
- # del idle_joint_config[key].sign
- # del idle_joint_config[key].pos_offset
- # del idle_joint_config[key].max_current_A
+ # del idle_joint_config[key].sign
+ # del idle_joint_config[key].pos_offset
+ # del idle_joint_config[key].max_current_A
with open(xbot2_config_template, 'r') as stream:
try:
@@ -1022,15 +1005,37 @@ def write_lowlevel_config(self, use_robot_id=False):
# noinspection PyUnresolvedReferences
class UrdfWriter:
- def __init__(self,
- config_file='config_file.yaml',
- control_plugin='xbot2',
- elementree=None,
- speedup=False,
- parent=None,
+ def __init__(self,
+ config_file='config_file.yaml',
+ control_plugin='xbot2',
+ elementree=None,
+ speedup=False,
+ parent=None,
floating_base=False,
verbose=False,
- logger=None):
+ logger=None,
+ slave_desc_mode='use_pos'):
+ self.config_file = config_file
+ self.resource_finder = ResourceFinder(self.config_file)
+ self.modular_resources_manager = ModularResourcesManager(self.resource_finder)
+ self.reset(control_plugin,
+ elementree,
+ speedup,
+ parent,
+ floating_base,
+ verbose,
+ logger,
+ slave_desc_mode)
+
+ def reset(self,
+ control_plugin='xbot2',
+ elementree=None,
+ speedup=False,
+ parent=None,
+ floating_base=False,
+ verbose=False,
+ logger=None,
+ slave_desc_mode='use_pos'):
# Setting this variable to True, speed up the robot building.
# To be used when the urdf does not need to be shown at every iteration
@@ -1050,21 +1055,16 @@ def __init__(self,
self.set_floating_base(floating_base)
if logger is None:
- self.logger = logging.getLogger('URDF_writer')
+ self.logger = logging.getLogger('URDF_writer')
else:
self.logger = logger
-
+
self.verbose = verbose
if self.verbose and self.logger is not None:
- self.logger.setLevel(logging.DEBUG)
+ self.logger.setLevel(logging.DEBUG)
else:
pass
- self.config_file = config_file
-
- self.resource_finder = ResourceFinder(self.config_file)
- self.resources_paths = [['resources_path'], ['external_resources', 'concert_resources_path']]
-
self.collision_elements = []
# Plugin class attribute. Can be XBot2Plugin, XBotCorePlugin or RosControlPlugin
@@ -1090,7 +1090,7 @@ def __init__(self,
#self.root = ET.fromstring(string)
self.urdf_tree = ET.ElementTree(self.root)
-
+
# change path to xacro library
library_filename = self.resource_finder.get_filename('urdf/ModularBot.library.urdf.xacro', ['data_path'])
control_filename = self.resource_finder.get_filename('urdf/ModularBot.control.urdf.xacro', ['data_path'])
@@ -1106,8 +1106,9 @@ def __init__(self,
self.root = elementree
self.urdf_tree = ET.ElementTree(self.root)
- self.tag_num = 1
+ self.tag_num = 0
self.branch_switcher = {
+ 0: '',
1: '_A',
2: '_B',
3: '_C',
@@ -1128,41 +1129,48 @@ def __init__(self,
self.inverse_branch_switcher = {y: x for x, y in iteritems(self.branch_switcher)}
- self.n_cubes = 0
- self.cube_switcher = {
- 0: 'a',
- 1: 'b',
- 2: 'c',
- 3: 'd',
- 4: 'e',
- 5: 'f',
- 6: 'g',
- 7: 'h'
- }
-
- self.listofchains = []
- self.listofhubs = []
-
self.origin, self.xaxis, self.yaxis, self.zaxis = (0, 0, 0.4), (1, 0, 0), (0, 1, 0), (0, 0, 1)
- # add attribute corresponding to the connector transform
- self.T_con = tf.transformations.translation_matrix((0, 0, 0.0)) # self.slavecube.geometry.connector_length))
-
data = {'type': "base_link", 'name': "base_link", 'kinematics_convention': "urdf"}
self.base_link = ModuleNode.ModuleNode(data, "base_link")
setattr(self.base_link, 'name', "base_link")
- setattr(self.base_link, 'tag', "_A")
+ setattr(self.base_link, 'tag', self.branch_switcher.get(self.tag_num))
setattr(self.base_link, 'flange_size', '3')
setattr(self.base_link, 'i', 0)
setattr(self.base_link, 'p', 0)
setattr(self.base_link, 'Homogeneous_tf', tf.transformations.identity_matrix())
setattr(self.base_link, 'robot_id', 0)
+ setattr(self.base_link, 'current_port', 1)
+ #HACK: base_link does not have ports.
+ setattr(self.base_link, 'active_ports', "0011")
+ setattr(self.base_link, 'occupied_ports', "0001")
+ setattr(self.base_link, 'connectors', ['connector_0'])
+ setattr(self.base_link, 'connector_idx', 1)
+ setattr(self.base_link, 'is_structural', False)
+ setattr(self.base_link, 'mesh_names', [])
+
+ self.listofchains = [[self.base_link]]
+ self.listofhubs = []
self.parent_module = self.base_link
# update generator expression
- self.update_generator()
+ self.update_generators()
+
+ # map between name of the mesh and the module
+ self.mesh_to_module_map = {}
+
+ self.urdf_string = self.process_urdf()
+
+ self.model_stats = ModelStats(self)
+
+ # set the slave description mode
+ try:
+ self.slave_desc_mode = SlaveDescMode(slave_desc_mode)
+ except ValueError:
+ self.slave_desc_mode = SlaveDescMode.USE_POSITIONS
+ self.info_print('Slave description mode not recognized! Defaulting to USE_POSITIONS')
def set_floating_base(self, floating_base):
"""Set the floating base flag"""
@@ -1189,6 +1197,12 @@ def info_print(self, *args):
else:
print(args)
+ def error_print(self, *args):
+ if isinstance(self.logger, logging.Logger):
+ self.logger.error(' '.join(str(a) for a in args))
+ else:
+ print(args)
+
@staticmethod
def find_module_from_id(module_id, modules):
"""Given the module id find the corresponding dictionary entry and return it"""
@@ -1222,7 +1236,7 @@ def find_next_module_in_chain(module_id, modules):
else:
continue
return found_module, found_module_id
-
+
def sort_modules(self, modules_dict):
ordered_chain = [None] * len(modules_dict)
@@ -1233,11 +1247,11 @@ def sort_modules(self, modules_dict):
try:
ordered_chain[module_position - 1] = item
-
+
except IndexError:
self.print('unexpected module position {}, modules number: {}'.format(module_position, len(modules_dict)))
return list()
-
+
return ordered_chain
@@ -1261,28 +1275,19 @@ def sort_modules_by_pos(self, modules_dict):
# This method will be used when branches in the robot will be supported.
def read_from_json(self, json_data):
+ # HACK: we keep track of how many sockets we have to add to insert a default offset
+ socket_counter = 0
# If a tree representing the topology was already instantiated, re-initialize and start from scratch
if self.root != 0:
self.print("Re-initialization")
- self.__init__(config_file=self.config_file,
- control_plugin=self.control_plugin,
- speedup=self.speedup,
+ self.__init__(config_file=self.config_file,
+ control_plugin=self.control_plugin,
+ speedup=self.speedup,
verbose=self.verbose,
- logger=self.logger)
-
- # # Open the base xacro file
- # filename = path_name + '/urdf/ModularBot_new.urdf.xacro'
- # with codecs.open(filename, 'r') as f:
- # string = f.read()
- # # Instantiate an Element Tree
- # self.root = ET.fromstring(string)
- # self.urdf_tree = ET.ElementTree(self.root)
- # self.print(ET.tostring(self.urdf_tree.getroot()))
-
- # Load the robot_id dictionary from yaml file
- # opts = repl_option()
- # robot_id_dict = yaml.safe_load(open(opts["robot_id_yaml"], 'r'))
+ logger=self.logger,
+ slave_desc_mode=self.slave_desc_mode)
+
robot_id_yaml = self.resource_finder.get_filename('robot_id.yaml')
robot_id_dict = yaml.safe_load(open(robot_id_yaml, 'r'))
@@ -1291,13 +1296,22 @@ def read_from_json(self, json_data):
# Process the modules described in the json to create the tree
modules_dict = yaml.safe_load(json_data)
- modules_list = self.sort_modules_by_pos(modules_dict)
+
+ if self.slave_desc_mode is SlaveDescMode.USE_POSITIONS:
+ # Sort the modules by position
+ modules_list = self.sort_modules_by_pos(modules_dict)
+ elif self.slave_desc_mode is SlaveDescMode.USE_IDS:
+ # Sort the modules by id
+ modules_list = self.sort_modules(modules_dict)
+ else:
+ raise ValueError('Slave description mode not recognized!')
for module in modules_list:
module_position = int(module['position'])
module['robot_id'] = int(module['robot_id']) if module['robot_id'] != -1 else module_position*(-1)
robot_id = module['robot_id']
+ active_ports = int(module['active_ports'])
mod_type = int(module['mod_type'])
mod_id = int(module['mod_id'])
@@ -1311,7 +1325,6 @@ def read_from_json(self, json_data):
self.info_print("Id not recognized! Skipping add_module() for id", robot_id_dict.get(robot_id))
continue
-
self.info_print('Discovered module with ID:', robot_id)
parent_position = None
@@ -1345,98 +1358,45 @@ def read_from_json(self, json_data):
if parent_position :
parent = modules_list[parent_position -1]
self.print('parent:', parent)
- # # HACK: skip hub for discovery!
- # if parent['robot_id'] == -1:
- # parent = modules_list[parent['position'] -2]
parent_id = int(parent['robot_id'])
self.print('parent_id:', parent_id)
-
+
parent_active_ports = int(parent['active_ports'])
self.print('parent_active_ports:', parent_active_ports)
parent_topology = int(parent['topology'])
self.print('parent_topology:', parent_topology)
- if self.verbose:
- # Render tree
- self.print(RenderTree(self.base_link))
- for pre, _, node in RenderTree(self.base_link):
- self.print(pre, node, node.name, node.robot_id)
- # treestr = u"%s%s" % (pre, node.name)
- # self.print(treestr.ljust(8), node.name, node.robot_id)
-
- # parent_module = anytree.search.findall_by_attr(self.base_link, parent_id, name='robot_id')[0]
- # self.print('parent_module:', parent_module, '\nparent name:', parent_module.name)
- # self.select_module_from_name(parent_module.name)
- # self.print(self.parent_module.name)
- #TODO:replace with select_module_from_id
+ # select the correct parent module from its id and sets the correct current port
self.select_module_from_id(parent_id)
- # set the selected_port as occupied
- mask = 1 << self.parent_module.selected_port - 1
+ # set the current_port as occupied
+ mask = 1 << self.eth_to_physical_port_idx(self.parent_module.current_port)
self.print(mask)
self.print(self.parent_module.occupied_ports)
self.parent_module.occupied_ports = "{0:04b}".format(int(self.parent_module.occupied_ports, 2) | mask)
self.print(self.parent_module.occupied_ports)
- #parent_module.occupied_ports[-selected_port] = 1
- #If the parent is a cube to support non-structural box we add a socket
- if self.parent_module.type == 'cube':
- if self.parent_module.is_structural == False:
- self.add_socket()
+ #HACK: If the parent is a cube to support non-structural box we add a socket
+ if self.parent_module.type is ModuleType.CUBE:
+ if not self.parent_module.is_structural:
+ self.add_module('socket.yaml', {'x': float(socket_counter)}, reverse=False)
+ socket_counter += 1
- # # HACK: for CONCERT mobile base select directly the connector for the manipulator. Discovery of the legs is skipped for now!
- # if parent_module.type == 'mobile_base':
- # parent_module.selected_port = 5
-
- # get which ports in the ESC slave are active
- active_ports = int(module['active_ports'])
- self.print('active_ports:', active_ports)
+ # HACK: manually set name of mobile platform to be 'mobile_base', instead of auto-generated name
+ module_name = None
+ if module_filename=='concert/mobile_platform_concert.json':
+ module_name = 'mobile_base'
#add the module
- if module_filename=='master_cube.yaml':
- data = self.add_slave_cube(0, is_structural=False, robot_id=robot_id, active_ports=active_ports)
- elif module_filename=='concert/mobile_platform_concert.json':
- is_structural = True
- if self.parent_module.type == 'mobile_base':
- is_structural = False
- data = self.add_mobile_platform(is_structural=is_structural, robot_id=robot_id, active_ports=active_ports)
- # # leg + wheel 1
- # data = self.select_module_from_name('mobile_base_con1')
- # wheel_data, steering_data = self.add_wheel_module(wheel_filename='concert/module_wheel_concert.json',
- # steering_filename='concert/module_steering_concert_fl_rr.json',
- # angle_offset=0.0, robot_id=(21,22))
- # # leg + wheel 2
- # data = self.select_module_from_name('mobile_base_con2')
- # wheel_data, steering_data = self.add_wheel_module(wheel_filename='concert/module_wheel_concert.json',
- # steering_filename='concert/module_steering_concert_fr_rl.json',
- # angle_offset=0.0, robot_id=(11,12))
- # # leg + wheel 3
- # data = self.select_module_from_name('mobile_base_con3')
- # wheel_data, steering_data = self.add_wheel_module(wheel_filename='concert/module_wheel_concert.json',
- # steering_filename='concert/module_steering_concert_fr_rl.json',
- # angle_offset=0.0, robot_id=(31,32))
- # # leg + wheel 4
- # data = self.select_module_from_name('mobile_base_con4')
- # wheel_data, steering_data = self.add_wheel_module(wheel_filename='concert/module_wheel_concert.json',
- # steering_filename='concert/module_steering_concert_fl_rr.json',
- # angle_offset=0.0, robot_id=(41,42))
- else:
- data = self.add_module(module_filename, 0, robot_id=robot_id, active_ports=active_ports)
+ data = self.add_module(module_filename, {}, reverse=False, robot_id=robot_id, active_ports=active_ports, module_name=module_name)
- if self.verbose:
- for pre, _, node in RenderTree(self.base_link):
- self.print(pre, node, node.name, node.robot_id)
-
## HACK: Manually add passive end effector for now!
# self.add_simple_ee(0.0, 0.0, 0.135, mass=0.23)
- # data = self.add_module('concert/passive_end_effector_panel.json', 0, False)
- # data = self.add_module('experimental/passive_end_effector_pen.json', 0, False)
+ # data = self.add_module('concert/passive_end_effector_panel.json', {}, False)
+ # data = self.add_module('experimental/passive_end_effector_pen.json', {}, False)
- # doc = xacro.parse(string)
- # xacro.process_doc(doc, in_order=True)
- # string = doc.toprettyxml(indent=' ')
self.urdf_string = self.process_urdf()
self.info_print("Discovery completed")
@@ -1450,33 +1410,6 @@ def render_tree(self):
return 0
-
- def process_connections(self, connections_list, modules_list, name, m_type):
- """Process connections of the module as described in the JSON as a list"""
- self.print('enter!')
- for child_id in connections_list[1:]:
- self.print('child: ', child_id)
- self.select_module_from_name(name)
- self.print(self.parent_module.name)
- if child_id != -1:
- # Find child module to process searching by id
- child = self.find_module_from_id(child_id, modules_list)
- # If the processed module is a mastercube we need first to select the connector to which attach to
- if m_type == 'mastercube':
- _connector_index = connections_list.index(child_id) + 1
- con_name = name + '_con' + str(_connector_index)
- self.select_module_from_name(con_name)
- # Add the module
- if child['type'] == 'master_cube':
- data = self.add_slave_cube(0)
- else:
- data = self.add_module(child['type'] + '.yaml', 0)
- # Update variables and process its connections
- module_name = data['lastModule_name']
- module_type = data['lastModule_type']
- self.process_connections(child['connections'], modules_list, module_name, module_type)
-
-
def read_file(self, file_str):
"""Open the URDF chosen from the front-end and import it as a ElemenTree tree"""
# global root, urdf_tree
@@ -1498,10 +1431,10 @@ def read_file(self, file_str):
def process_urdf(self, xacro_mappings={}):
"""Process the urdf to convert from xacro and perform macro substitutions. Returns urdf string"""
-
+
# write the urdf tree to a string
xmlstr = xml.dom.minidom.parseString(ET.tostring(self.urdf_tree.getroot())).toprettyxml(indent=" ")
- self.print(xmlstr)
+ # self.print(xmlstr)
# parse the string to convert from xacro
doc = xacro.parse(xmlstr)
@@ -1528,16 +1461,17 @@ def add_to_chain(self, new_joint):
# get tag_index, an integer representing on which branch of the robot the joint has been added
tag_index = self.inverse_branch_switcher.get(new_joint.tag)
+ parent_tag_index = self.inverse_branch_switcher.get(new_joint.parent.tag)
chain = [new_joint]
self.print("tag_index: ", tag_index, "list of chains: ", len(self.listofchains))
- # if tag_index is bigger than the length of the list of chains, it means this chain hasn't been added yet.
+ # if tag_index (offseted by one, since now we start from 0) is bigger than the length of the list of chains, it means this chain hasn't been added yet.
# then we need to append a new list representing the new chain formed by the new joint only
- if tag_index > len(self.listofchains):
+ if tag_index > parent_tag_index:
self.listofchains.append(chain)
# if instead tag_index is not bigger it means the chain the new joint is part of has already beeen added.
# then the new joint is appended to the list representing the chain it's part of.
else:
- self.listofchains[tag_index - 1].append(new_joint)
+ self.listofchains[tag_index].append(new_joint)
def remove_from_chain(self, joint):
"""Remove joint from the list of the robot kinematic chains
@@ -1552,446 +1486,20 @@ def remove_from_chain(self, joint):
chain.remove(joint)
self.listofchains = list(filter(None, self.listofchains))
-
- # noinspection PyPep8Naming
- def add_slave_cube(self, angle_offset, is_structural=True, robot_id=0, active_ports=1, connection_port=2):
- """Method adding slave/master cube to the tree.
-
- Parameters
- ----------
- angle_offset: float
- Value of the angle between the parent module output frame and the cube input frame
-
- is_structural: float
- Bool variable indicating if the box is a structural part of the robot or it's just used as computation unit away from the robot.
- In the second case the different chains are placed in default locations in a xy plane
- (the user will then be queried to specify their actual location once the robot model is recontructed)
-
- robot_id: int
- Value of the robot_id set in the firmware of the module.
- This is obtained in Discovery Mode when reading the JSON from the EtherCAT master. This is not used when in Bulding Mode.
-
- active_ports: int
- The number of active ports of the cube (how many ports have established a connection to a module).
- The value is the conversion to int of the 4-bit binary string where each bit represent one port (1 if port is active, 0 if port is unactive)
-
- Returns
- -------
- data: dict
- Dictionary with as entries all the relevant info on the newly added module.
- In particular the updated and newly processed urdf string.
-
- """
- # global T_con, L_0a, n_cubes, parent_module
-
- # TODO: This part below the "if" is deprecated. It still uses "connectors" separate module.
- # It was made to handle creating robots with multiple "boxes", which will be probably never done.
- # If important should be reviewed and modify it as the part below the "else".
-
- if self.parent_module != self.base_link :
- # add slave cube
- self.print('add_slave_cube')
- # Generate name according to the # of cubes already in the tree
- name = 'L_0' + self.cube_switcher.get(self.n_cubes)
- self.n_cubes += 1
-
- slavecube = None
- for resource_path in self.resources_paths:
- filename = self.resource_finder.get_filename('yaml/master_cube.yaml', resource_path)
- template_name = self.resource_finder.get_filename('yaml/template.yaml', ['resources_path'])
-
- # call the method that reads the yaml file describing the cube and instantiate a new module object
- try:
- slavecube = ModuleNode.module_from_yaml(filename, self.parent_module, template_name)
- break
- except FileNotFoundError:
- continue
- if slavecube is None:
- raise FileNotFoundError(filename+' was not found in the available resources')
-
- setattr(slavecube, 'name', name)
-
- # Set attributes of the newly added module object
- setattr(slavecube, 'i', self.parent_module.i)
- setattr(slavecube, 'p', self.parent_module.p)
- # flange_size is already set from the YAML file
- # setattr(slavecube, 'flange_size', self.parent_module.flange_size)
-
- setattr(slavecube, 'angle_offset', angle_offset)
- setattr(slavecube, 'robot_id', robot_id)
-
- # add the master cube to the xml tree
- ET.SubElement(self.root, "xacro:add_slave_cube", type='cube', name=name, filename=filename)
- self.add_connectors(slavecube)
-
- self.add_gazebo_element(slavecube.gazebo.body_1, slavecube.name)
-
- # # Get inverse of the transform of the connector
- # T_con_inv = tf.transformations.inverse_matrix(self.T_con)
-
- # # Generate name and dict for the 1st connector module
- # name_con1 = name + '_con1'
- # data1 = {'Homogeneous_tf': T_con_inv, 'type': "con", 'name': name_con1, 'i': 0, 'p': 0, 'flange_size': 3}
- # self.print('T_con_inv:', T_con_inv)
-
- # Generate name and dict for the 1st connector module
- name_con1 = name + '_con1'
- data1 = {'Homogeneous_tf': T_con_inv, 'type': "con", 'name': name_con1, 'i': 0, 'p': 0, 'flange_size': 3}
- self.print('T_con_inv:', T_con_inv)
-
- if self.parent_module.type in { 'joint', 'wheel' }:
- parent_distal_tf = self.parent_module.Distal_tf
- elif self.parent_module.type == 'cube' or self.parent_module.type == 'mobile_base':
- if self.parent_module.selected_port == 1:
- parent_distal_tf = self.parent_module.Con_1_tf
- elif self.parent_module.selected_port == 2:
- parent_distal_tf = self.parent_module.Con_2_tf
- elif self.parent_module.selected_port == 3:
- parent_distal_tf = self.parent_module.Con_3_tf
- elif self.parent_module.selected_port == 4:
- parent_distal_tf = self.parent_module.Con_4_tf
- elif self.parent_module.selected_port == 5:
- parent_distal_tf = self.parent_module.Con_5_tf
- else:
- parent_distal_tf = self.parent_module.Homogeneous_tf
-
- if connection_port == 1:
- cube_proximal_tf = slavecube.Con_1_tf
- elif connection_port == 2:
- cube_proximal_tf = slavecube.Con_2_tf
- elif connection_port == 3:
- cube_proximal_tf = slavecube.Con_3_tf
- elif connection_port == 4:
- cube_proximal_tf = slavecube.Con_4_tf
- elif connection_port == 5:
- cube_proximal_tf = slavecube.Con_5_tf
-
- # Get transform representing the output frame of the parent module after a rotation of angle_offset
- parent_transform = ModuleNode.get_rototranslation(parent_distal_tf,
- tf.transformations.rotation_matrix(angle_offset,
- self.zaxis))
- cube_transform = ModuleNode.get_rototranslation(parent_transform, cube_proximal_tf)
-
- x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(cube_transform)
-
- # Generate the name of the fixed joint used to connect the cube
- if self.parent_module.type == "cube" or self.parent_module.type == "mobile_base":
- fixed_joint_name = 'FJ_' + self.parent_module.parent.name + '_' + name
- else:
- fixed_joint_name = 'FJ_' + self.parent_module.name + '_' + name
-
- # Select the name of the parent to use to generate the urdf. If the parent is a joint use the name of the
- # dummy link attached to it
- if self.parent_module.type == "joint":
- parent_name = self.parent_module.distal_link_name
- else:
- parent_name = self.parent_module.name
-
- # Add the fixed joint to the xml tree
- ET.SubElement(
- self.root,
- "xacro:add_fixed_joint",
- type="fixed_joint",
- name=fixed_joint_name,
- father=parent_name,
- child=name,
- x=x,
- y=y,
- z=z,
- roll=roll,
- pitch=pitch,
- yaw=yaw
- )
-
- if self.verbose:
- # Render tree
- for pre, _, node in anytree.render.RenderTree(self.base_link):
- self.print("%s%s" % (pre, node.name))
-
- if self.speedup:
- self.urdf_string = ""
- else:
- # Process the urdf string by calling the process_urdf method.
- # Parse, convert from xacro and write to string.
- self.urdf_string = self.process_urdf()
-
- # Update the EtherCAT port connected to the electro-mechanical interface where the new module/slave will be added
- # 1 2 3 4
- # o o o o
- # | | | |
- # com-exp upper port front port nothing
- setattr(mastercube, 'selected_port', 3)
- self.print('mastercube.selected_port :', mastercube.selected_port)
-
- # save the active ports as a binary string
- setattr(mastercube, 'active_ports', "{0:04b}".format(active_ports))
- self.print('active_ports: ', mastercube.active_ports)
-
- # save the occupied ports as a binary string
- setattr(mastercube, 'occupied_ports', "{0:04b}".format(active_ports))
- self.print('occupied_ports: ', mastercube.occupied_ports)
-
-
- # Update the parent_module attribute of the URDF_writer class
- self.parent_module = slavecube
-
- self.listofhubs.append(slavecube)
-
- # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
- data = {'result': self.urdf_string,
- 'lastModule_type': 'mastercube',
- 'lastModule_name': name,
- 'flange_size': 3,
- 'count': self.n_cubes}
-
- return data
-
- else:
- # add master cube
- self.print('add_master_cube')
- # Generate name according to the # of cubes already in the tree
- name = 'L_0' + self.cube_switcher.get(self.n_cubes)
- self.n_cubes += 1
-
- # self.T_con = tf.transformations.translation_matrix((0, 0, 0.1))
- # self.T_con = self.mastercube.geometry.connector_length))
-
- mastercube = None
- for resource_path in self.resources_paths:
- filename = self.resource_finder.get_filename('yaml/master_cube.yaml', resource_path)
- template_name = self.resource_finder.get_filename('yaml/template.yaml', ['resources_path'])
-
- # call the method that reads the yaml file describing the cube and instantiate a new module object
- try:
- mastercube = ModuleNode.module_from_yaml(filename, self.parent_module, template_name)
- break
- except FileNotFoundError:
- continue
- if mastercube is None:
- raise FileNotFoundError(filename+' was not found in the available resources')
-
- # set attributes of the newly added module object
- setattr(mastercube, 'name', name)
- setattr(mastercube, 'i', 0)
- setattr(mastercube, 'p', 0)
-
- setattr(mastercube, 'robot_id', robot_id)
-
- setattr(mastercube, 'is_structural', is_structural)
- if is_structural:
- # add the master cube to the xml tree
- ET.SubElement(self.root, "xacro:add_master_cube", type='cube', name=name, filename=filename)
- self.add_connectors(mastercube)
- else:
- # add the master cube to the xml tree
- #ET.SubElement(self.root, "xacro:add_master_cube", type='cube', name=name, filename=filename)
- #ET.SubElement(self.root, "xacro:add_connectors", type='connectors', name=name, filename=filename)
- pass
-
- self.add_gazebo_element(mastercube.gazebo.body_1, mastercube.name)
-
- # # instantate a ModuleNode for branch 1 connector
- # name_con1 = name + '_con1'
- # data1 = {'Homogeneous_tf': mastercube.Con_1_tf, 'type': "con", 'name': name_con1, 'i': 0, 'p': 0, 'flange_size': 3}
- # slavecube_con1 = ModuleNode.ModuleNode(data1, name_con1, parent=mastercube)
-
- # # instantate a ModuleNode for branch 2 connector
- # name_con2 = name + '_con2'
- # data2 = {'Homogeneous_tf': mastercube.Con_2_tf, 'type': "con", 'name': name_con2, 'i': 0, 'p': 0, 'flange_size': 3}
- # slavecube_con2 = ModuleNode.ModuleNode(data2, name_con2, parent=mastercube)
-
- # # instantate a ModuleNode for branch 3 connector
- # name_con3 = name + '_con3'
- # data3 = {'Homogeneous_tf': mastercube.Con_3_tf, 'type': "con", 'name': name_con3, 'i': 0, 'p': 0, 'flange_size': 3}
- # slavecube_con3 = ModuleNode.ModuleNode(data3, name_con3, parent=mastercube)
-
- # # instantate a ModuleNode for branch 4 connector
- # name_con4 = name + '_con4'
- # data4 = {'Homogeneous_tf': mastercube.Con_4_tf, 'type': "con", 'name': name_con4, 'i': 0, 'p': 0, 'flange_size': 3}
- # slavecube_con4 = ModuleNode.ModuleNode(data4, name_con4, parent=mastercube)
-
- # Render tree
- #for pre, _, node in anytree.render.RenderTree(self.base_link):
- #self.print("%s%s" % (pre, node.name))
-
- # new_Link = slavecube_con1
- # past_Link = parent_module
- # new_Link.get_rototranslation(past_Link.Homogeneous_tf, tf.transformations.identity_matrix())
- # self.print(new_Link.z)
-
- # ET.SubElement(root, "xacro:add_master_cube", name=name)
-
- # fixed_joint_name = 'cube_joint'
- # ET.SubElement(root,
- # "xacro:add_fixed_joint",
- # name=fixed_joint_name,
- # type="fixed_joint",
- # father=past_Link.name,
- # child=new_Link.name,
- # x=new_Link.x,
- # y=new_Link.y,
- # z=new_Link.z,
- # roll=new_Link.roll,
- # pitch=new_Link.pitch,
- # yaw=new_Link.yaw)
-
- # update the urdf file, adding the new module
- # string = write_urdf(path_name + '/urdf/ModularBot_test.urdf', urdf_tree)
-
- if self.speedup:
- self.urdf_string = ""
- else:
- # Process the urdf string by calling the process_urdf method. Parse, convert from xacro and write to string.
- self.urdf_string = self.process_urdf()
-
- # Update the EtherCAT port connected to the electro-mechanical interface where the new module/slave will be added
- # 1 2 3 4
- # o o o o
- # | | | |
- # com-exp upper port front port nothing
- setattr(mastercube, 'selected_port', 2)
- self.print('mastercube.selected_port :', mastercube.selected_port)
-
- # save the active ports as a binary string
- setattr(mastercube, 'active_ports', "{0:04b}".format(active_ports))
- self.print('active_ports: ', mastercube.active_ports)
-
- # save the occupied ports as a binary string
- setattr(mastercube, 'occupied_ports', "0001")
- self.print('occupied_ports: ', mastercube.occupied_ports)
-
- # # If parent topology is greater than 2 the parent is a switch/hub so we need to find the right port where the module is connected
- # if active_ports >= 3:
- # for port_idx in range(2, len(mastercube.active_ports) - 1)
- # if mastercube.active_ports[-port_idx] == 1:
- # mastercube.selected_port = port_idx
- # break
-
- # if parent_active_ports == 3:
- # self.parent_module.selected_port = 3
- # elif parent_active_ports == 5:
- # self.parent_module.selected_port = 4
- # self.print('self.parent_module.selected_port: ', self.parent_module.selected_port)
-
- # Update the parent_module attribute of the URDF_writer class. A default connection is chosen.
- #self.parent_module = slavecube_con3
- self.parent_module = mastercube
-
- self.listofhubs.append(mastercube)
-
- # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
- data = {'result': self.urdf_string,
- 'lastModule_type': 'mastercube',
- 'lastModule_name': name,
- 'flange_size': 3,
- 'count': self.n_cubes}
-
- return data
-
-
- # noinspection PyPep8Naming
- def add_mobile_platform(self, angle_offset=0.0, is_structural=True, robot_id=0, active_ports=1, connection_port=2):
- """Method adding slave/master cube to the tree.
-
- Parameters
- ----------
- angle_offset: float
- Value of the angle between the parent module output frame and the cube input frame
-
- robot_id: int
- Value of the robot_id set in the firmware of the module.
- This is obtained in Discovery Mode when reading the JSON from the EtherCAT master. This is not used when in Bulding Mode.
-
- active_ports: int
- The number of active ports of the cube (how many ports have established a connection to a module).
- The value is the conversion to int of the 4-bit binary string where each bit represent one port (1 if port is active, 0 if port is unactive)
-
- Returns
- -------
- data: dict
- Dictionary with as entries all the relevant info on the newly added module.
- In particular the updated and newly processed urdf string.
-
- """
- self.set_floating_base(True) # TODO: better way to do this?
-
- # if self.parent_module != self.base_link :
- # self.print('mobile base can be have only base_link as parent!')
- # self.parent_module = self.base_link
-
- self.print('add_mobile_platform')
- # Generate name according to the # of cubes already in the tree
- name = 'mobile_base' # _' + str(len(self.listofhubs))
-
- mobilebase = None
- for resource_path in self.resources_paths:
- filename = self.resource_finder.get_filename('json/concert/mobile_platform_concert.json', resource_path)
- template_name = self.resource_finder.get_filename('yaml/template.yaml', ['resources_path'])
-
- # call the method that reads the yaml file describing the cube and instantiate a new module object
- try:
- mobilebase = ModuleNode.module_from_json(filename, self.parent_module, template_name)
- break
- except FileNotFoundError:
+ def get_actuated_modules_chains(self):
+ active_modules_chains = []
+ for modules_chain in self.listofchains:
+ # check number of joints and active modules in the chain.
+ joint_num = 0
+ for joint_module in modules_chain:
+ if joint_module.type in ModuleClass.actuated_modules():
+ joint_num += 1
+ # If 0, skip it. The chain doesn't need to be added to the srdf in this case.
+ if joint_num == 0:
continue
- if mobilebase is None:
- raise FileNotFoundError(filename+' was not found in the available resources')
-
- # set attributes of the newly added module object
- setattr(mobilebase, 'name', name)
- setattr(mobilebase, 'i', 0)
- setattr(mobilebase, 'p', 0)
-
- setattr(mobilebase, 'robot_id', robot_id)
-
- setattr(mobilebase, 'n_child_hubs', 0)
- setattr(mobilebase, 'is_structural', is_structural)
- if is_structural:
- # add the master cube to the xml tree
- ET.SubElement(self.root, "xacro:add_mobile_base", type='mobile_base', name=mobilebase.name, filename=mobilebase.filename)
- self.add_connectors(mobilebase)
- else:
- # the added module is a hub (not structural) extension to the mobile base
- if self.parent_module.type == 'mobile_base':
- # if the parent is a mobile base, the n_child_hubs attribute is incremented, in order to keep track of the number of hubs connected to the mobile base and therefore the number of ports occupied. This is needed to select the right connector where to connect the new module
- self.parent_module.n_child_hubs += 1
-
- self.add_gazebo_element(mobilebase.gazebo.body_1, mobilebase.name)
-
- if self.speedup:
- self.urdf_string = ""
- else:
- # Process the urdf string by calling the process_urdf method. Parse, convert from xacro and write to string.
- self.urdf_string = self.process_urdf()
-
- # Update the EtherCAT port connected to the electro-mechanical interface where the new module/slave will be added
- # 1 2 3 4
- # o o o o
- # | | | |
- # com-exp upper port front port nothing
- setattr(mobilebase, 'selected_port', 2)
- self.print('mobilebase.selected_port :', mobilebase.selected_port)
-
- # save the active ports as a binary string
- setattr(mobilebase, 'active_ports', "{0:04b}".format(active_ports))
- self.print('active_ports: ', mobilebase.active_ports)
-
- # save the occupied ports as a binary string
- setattr(mobilebase, 'occupied_ports', "0001")
- self.print('occupied_ports: ', mobilebase.occupied_ports)
-
- self.parent_module = mobilebase
-
- self.listofhubs.append(mobilebase)
-
- # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
- data = {'result': self.urdf_string,
- 'lastModule_type': 'mobile_base',
- 'lastModule_name': name,
- 'flange_size': 3,
- 'count': 1}
-
- return data
+ else:
+ active_modules_chains.append(modules_chain)
+ return active_modules_chains
def get_ET(self):
return self.urdf_tree
@@ -2001,44 +1509,47 @@ def get_parent_module(self):
@staticmethod
def find_chain_tip_link(chain):
- if chain[-1].children:
- if "con_" in chain[-1].children[0].name:
- tip_link = chain[-1].children[0].children[0].name
- else:
- tip_link = chain[-1].children[0].name
- else:
- if chain[-1].type in { 'joint', 'wheel' }:
- tip_link = chain[-1].distal_link_name
- if chain[-1].type == 'tool_exchanger':
- tip_link = chain[-1].pen_name
- if chain[-1].type == 'gripper':
- tip_link = chain[-1].TCP_name
- elif chain[-1].type in { 'simple_ee', 'link', 'size_adapter'}:
- tip_link = chain[-1].name
- elif chain[-1].type in { 'end_effector', 'drill'}:
- tip_link = chain[-1].tcp_name
- elif chain[-1].type == 'dagana':
- tip_link = chain[-1].dagana_link_name
+ if chain[-1].type in ModuleClass.joint_modules():
+ tip_link = chain[-1].distal_link_name
+ elif chain[-1].type in ModuleClass.link_modules() | ModuleClass.hub_modules():
+ tip_link = chain[-1].name
+ elif chain[-1].type in ModuleClass.end_effector_modules() - {ModuleType.DAGANA}:
+ tip_link = chain[-1].tcp_name
+ elif chain[-1].type is ModuleType.DAGANA:
+ tip_link = chain[-1].dagana_link_name
return tip_link
@staticmethod
def find_chain_base_link(chain):
+ if not chain[0].parent:
+ base_link = chain[0].name
if "con_" in chain[0].parent.name:
base_link = chain[0].parent.parent.name
else:
- base_link = chain[0].parent.name
+ if not chain[0].parent.is_structural and chain[0].parent.type in ModuleClass.hub_modules():
+ base_link = chain[0].parent.parent.name
+ else:
+ base_link = chain[0].parent.name
return base_link
-
- def update_generator(self):
+ @staticmethod
+ def find_chain_tag(chain):
+ return chain[-1].tag
+
+ def update_generators(self):
# Generator expression for list of urdf elements without the gazebo tag.
# This is needed because of the change in the xacro file, as gazebo simulation tags
# are now added from the start and this creates problems with the search
nodes = set(self.root.findall("*"))
gazebo_nodes = set(self.root.findall("./gazebo"))
xacro_include_nodes = set(self.root.findall('./xacro:include', ns))
- filtered_nodes = nodes.difference(gazebo_nodes).difference(xacro_include_nodes)
- self.gen = (node for node in filtered_nodes)
+ xacro_if_nodes = set(self.root.findall('./xacro:if', ns))
+ # xacro_macro_nodes = set(self.root.findall('./xacro:macro', ns))
+ xacro_property_nodes = set(self.root.findall('./xacro:property', ns))
+ xacro_arg_nodes = set(self.root.findall('./xacro:arg', ns))
+ filtered_nodes = nodes.difference(gazebo_nodes).difference(xacro_include_nodes).difference(xacro_if_nodes).difference(xacro_property_nodes).difference(xacro_arg_nodes)
+ self.urdf_nodes_generator = (node for node in filtered_nodes)
+ self.gazebo_nodes_generator = (node for node in gazebo_nodes)
# Adds a table for simulation purposes
def add_table(self):
@@ -2063,163 +1574,59 @@ def add_table(self):
self.parent_module = table
+ # Select the current connector of the new module
+ selected_connector = self.select_connector(table)
+ # Select the meshes to highlight in the GUI
+ selected_meshes = self.select_meshes(selected_connector, table)
+
if self.speedup:
self.urdf_string = ""
else:
# Process the urdf string by calling the process_urdf method. Parse, convert from xacro and write to string
self.urdf_string = self.process_urdf()
- # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
- data = {'result': self.urdf_string,
- 'lastModule_type': table.type,
- 'lastModule_name': table.name,
+ # Create the dictionary with the relevant info on the selected module, so that the GUI can dispaly it.
+ data = {'name': table.name,
+ 'type': table.type,
'flange_size': table.flange_size,
- 'count': table.i}
+ 'selected_connector': selected_connector,
+ 'selected_meshes': selected_meshes,
+ 'urdf_string': self.urdf_string}
return data
+
+ def add_drillbit(self, length=0.27, radius=0.012, mass=0.1):
+ drillbit_name = 'drillbit'+ self.parent_module.tag
+ ET.SubElement(self.root,
+ "xacro:add_cylinder",
+ type="drillbit",
+ name=drillbit_name,
+ size_z=str(length),
+ mass=str(mass),
+ radius=str(radius))
+ self.parent_module.mesh_names.append(drillbit_name)
- def move_socket(self, socket_name, x_offset=0.0, y_offset=0.0, z_offset=0.0, angle_offset=0.0):
- socket = self.access_module_by_name(socket_name)
- fixed_joint_name = 'L_' + str(socket.i) + socket.tag + '_fixed_joint_' + str(socket.p)
-
- # Update generator expression
- self.update_generator()
-
- # From the list of xml elements find the ones with name corresponding to the relative joint, stator link
- # and fixed joint before the stator link and remove them from the xml tree
- for node in self.gen:
- try:
- if node.attrib['name'] == fixed_joint_name:
- node.set('x', str(x_offset))
- node.set('y', str(y_offset))
- node.set('z', str(z_offset))
- node.set('yaw', str(angle_offset))
- except KeyError:
- pass
-
- if self.speedup:
- self.urdf_string = ""
- else:
- # Process the urdf string by calling the process_urdf method. Parse, convert from xacro and write to string
- self.urdf_string = self.process_urdf()
+ trasl = tf.transformations.translation_matrix((0.0, 0.0, length))
+ rot = tf.transformations.euler_matrix(0.0, 0.0, 0.0, 'sxyz')
+ transform = ModuleNode.get_rototranslation(trasl, rot)
+ x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(transform)
- if self.verbose:
- # Render tree
- for pre, _, node in anytree.render.RenderTree(self.base_link):
- self.print("%s%s" % (pre, node.name))
-
- # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
- data = {'result': self.urdf_string,
- 'lastModule_type': socket.type,
- 'lastModule_name': socket.name,
- 'flange_size': socket.flange_size,
- 'count': socket.i}
-
- # Update the parent_module attribute of the URDF_writer class
- self.parent_module = socket
-
- return data
-
- def add_socket(self, x_offset=0.0, y_offset=0.0, z_offset=0.0, angle_offset=0.0):
- filename = 'socket.yaml'
- # Set base_link as parent
- self.parent_module = self.base_link
-
- new_socket = None
- # Generate the path to the required YAML file
- for resource_path in self.resources_paths:
- module_name = self.resource_finder.get_filename('yaml/'+filename, resource_path)
- template_name = self.resource_finder.get_filename('yaml/template.yaml', ['resources_path'])
-
- # create a ModuleNode instance for the socket
- try:
- new_socket = ModuleNode.module_from_yaml(module_name, self.parent_module, template_name, reverse=0)
- break
- except FileNotFoundError:
- continue
- if new_socket is None:
- raise FileNotFoundError(filename+' was not found in the available resources')
-
- # assign a new tag to the chain
- tag_letter = self.branch_switcher.get(self.tag_num)
- setattr(new_socket, 'tag', tag_letter)
- self.tag_num += 1
-
- # Set attributes of the newly added module object
- setattr(new_socket, 'i', self.parent_module.i)
- setattr(new_socket, 'p', self.parent_module.p)
- # flange_size is already set from the YAML file
- # setattr(new_socket, 'flange_size', self.parent_module.flange_size)
-
- setattr(new_socket, 'angle_offset', angle_offset)
- setattr(new_socket, 'robot_id', 0)
-
- # Update the EtherCAT port connected to the electro-mechanical interface where the new module/slave will be added
- setattr(new_socket, 'selected_port', 2)
- #self.print('selected_port :', new_socket.selected_port)
-
- # save the active ports as a binary string
- setattr(new_socket, 'active_ports', "{0:04b}".format(3)) # TODO:change this
- #self.print('active_ports: ', new_socket.active_ports)
-
- # save the occupied ports as a binary string
- setattr(new_socket, 'occupied_ports', "0001")
- #self.print('occupied_ports: ', new_socket.occupied_ports)
-
- setattr(new_socket, 'name', 'L_' + str(new_socket.i) + new_socket.tag)
- ET.SubElement(self.root,
- "xacro:add_socket",
- type="link",
- name=new_socket.name,
- filename=new_socket.filename,
- flange_size=str(new_socket.flange_size))
-
- self.add_gazebo_element(new_socket.gazebo.body_1 , new_socket.name)
-
- if self.parent_module.type == 'cube' or self.parent_module.type == "mobile_base":
- if self.parent_module.is_structural:
- parent_name = self.parent_module.name
- if self.parent_module.selected_port == 1:
- interface_transform = self.parent_module.Con_1_tf
- elif self.parent_module.selected_port == 2:
- interface_transform = self.parent_module.Con_2_tf
- elif self.parent_module.selected_port == 3:
- interface_transform = self.parent_module.Con_3_tf
- elif self.parent_module.selected_port == 4:
- interface_transform = self.parent_module.Con_4_tf
- elif self.parent_module.selected_port == 5:
- interface_transform = self.parent_module.Con_5_tf
- else:
- parent_name = self.parent_module.parent.name
- interface_transform = tf.transformations.identity_matrix()
- else:
- parent_name = self.parent_module.name
- interface_transform = self.parent_module.Homogeneous_tf
-
- transform = ModuleNode.get_rototranslation(interface_transform,
- tf.transformations.rotation_matrix(angle_offset,
- self.zaxis))
- x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(transform)
- x = str(x_offset)
- y = str(y_offset)
- z = str(z_offset)
-
- fixed_joint_name = 'L_' + str(new_socket.i) + new_socket.tag + '_fixed_joint_' + str(new_socket.p)
+ father_name = self.parent_module.tcp_name
ET.SubElement(self.root,
"xacro:add_fixed_joint",
- name=fixed_joint_name,
type="fixed_joint",
- father=parent_name,
- child=new_socket.name,
+ name="fixed_" + drillbit_name,
+ father=father_name,
+ child=drillbit_name,
x=x,
y=y,
z=z,
roll=roll,
pitch=pitch,
yaw=yaw)
-
- self.collision_elements.append((self.parent_module.name, new_socket.name))
+
+ self.collision_elements.append((father_name, drillbit_name))
if self.speedup:
self.urdf_string = ""
@@ -2227,44 +1634,24 @@ def add_socket(self, x_offset=0.0, y_offset=0.0, z_offset=0.0, angle_offset=0.0)
# Process the urdf string by calling the process_urdf method. Parse, convert from xacro and write to string
self.urdf_string = self.process_urdf()
- # update the urdf file, adding the new module
- # string = write_urdf(path_name + '/urdf/ModularBot_test.urdf', urdf_tree)
-
- if self.verbose:
- # Render tree
- for pre, _, node in anytree.render.RenderTree(self.base_link):
- self.print("%s%s" % (pre, node.name))
-
- # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
- data = {'result': self.urdf_string,
- 'lastModule_type': new_socket.type,
- 'lastModule_name': new_socket.name,
- 'flange_size': new_socket.flange_size,
- 'count': new_socket.i}
-
- # if new_module.name.endswith('_stator'):
- # new_module.name = selected_module[:-7]
- # last_module = anytree.search.findall_by_attr(L_0a, selected_module)[0]
+ return [drillbit_name, "fixed_" + drillbit_name]
- # Update the parent_module attribute of the URDF_writer class
- self.parent_module = new_socket
-
- # self.print(self.parent_module)
-
- return data
-
- def add_drillbit(self, length=0.27, radius=0.012, mass=0.1):
- drillbit_name = 'drillbit'+ self.parent_module.tag
+ def add_handle(self, x_offset=0.0, y_offset=0.25, z_offset=-0.18, mass=0.330, radius=0.025):
+ handle_name = 'handle'+ self.parent_module.tag
ET.SubElement(self.root,
"xacro:add_cylinder",
type="drillbit",
- name=drillbit_name,
- size_z=str(length),
+ name=handle_name,
+ size_z=str(abs(y_offset)),
mass=str(mass),
radius=str(radius))
+ self.parent_module.mesh_names.append(handle_name)
- trasl = tf.transformations.translation_matrix((0.0, 0.0, length))
- rot = tf.transformations.euler_matrix(0.0, 0.0, 0.0, 'sxyz')
+ trasl = tf.transformations.translation_matrix((x_offset, y_offset, z_offset))
+ if y_offset >= 0.0:
+ rot = tf.transformations.euler_matrix(-1.57, 0.0, 0.0, 'sxyz')
+ else:
+ rot = tf.transformations.euler_matrix(1.57, 0.0, 0.0, 'sxyz')
transform = ModuleNode.get_rototranslation(trasl, rot)
x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(transform)
@@ -2273,9 +1660,9 @@ def add_drillbit(self, length=0.27, radius=0.012, mass=0.1):
ET.SubElement(self.root,
"xacro:add_fixed_joint",
type="fixed_joint",
- name="fixed_" + drillbit_name,
+ name="fixed_" + handle_name,
father=father_name,
- child=drillbit_name,
+ child=handle_name,
x=x,
y=y,
z=z,
@@ -2283,7 +1670,31 @@ def add_drillbit(self, length=0.27, radius=0.012, mass=0.1):
pitch=pitch,
yaw=yaw)
- self.collision_elements.append((father_name, drillbit_name))
+ self.collision_elements.append((father_name, handle_name))
+
+ # Add also a frame on the handle gripping point
+ trasl = tf.transformations.translation_matrix((0.0, y_offset/2, z_offset))
+ rot = tf.transformations.euler_matrix(0.0, 0.0, 0.0, 'sxyz')
+ transform = ModuleNode.get_rototranslation(trasl, rot)
+ x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(transform)
+
+ handle_gripping_point_name = 'handle_gripping_point'+ self.parent_module.tag
+ ET.SubElement(self.root,
+ "xacro:add_fixed_joint",
+ type="fixed_joint",
+ name="fixed_" + handle_gripping_point_name,
+ father=father_name,
+ child=handle_gripping_point_name,
+ x=x,
+ y=y,
+ z=z,
+ roll=roll,
+ pitch=pitch,
+ yaw=yaw)
+
+ ET.SubElement(self.root,
+ "link",
+ name=handle_gripping_point_name)
if self.speedup:
self.urdf_string = ""
@@ -2291,14 +1702,7 @@ def add_drillbit(self, length=0.27, radius=0.012, mass=0.1):
# Process the urdf string by calling the process_urdf method. Parse, convert from xacro and write to string
self.urdf_string = self.process_urdf()
- # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
- data = {'result': self.urdf_string,
- 'lastModule_type': self.parent_module.type,
- 'lastModule_name': self.parent_module.name,
- 'flange_size': self.parent_module.flange_size,
- 'count': self.parent_module.i}
-
- return data
+ return [handle_name, "fixed_" + handle_name, handle_gripping_point_name, "fixed_" + handle_gripping_point_name]
# Add a cylinder as a fake end-effector
def add_simple_ee(self, x_offset=0.0, y_offset=0.0, z_offset=0.0, angle_offset=0.0, mass=1.0, radius=0.02):
@@ -2322,7 +1726,7 @@ def add_simple_ee(self, x_offset=0.0, y_offset=0.0, z_offset=0.0, angle_offset=0
radius=str(radius))
try:
- self.add_gazebo_element(simple_ee.gazebo.body_1, simple_ee.name)
+ self.add_gazebo_element(simple_ee, simple_ee.gazebo.body_1, simple_ee.name)
except AttributeError:
pass
@@ -2331,15 +1735,15 @@ def add_simple_ee(self, x_offset=0.0, y_offset=0.0, z_offset=0.0, angle_offset=0
rototrasl = ModuleNode.get_rototranslation(trasl, rot)
setattr(simple_ee, 'Homogeneous_tf', rototrasl)
- if self.parent_module.type=='joint':
+ if self.parent_module.type is ModuleType.JOINT:
transform = ModuleNode.get_rototranslation(self.parent_module.Distal_tf, rototrasl)
else:
transform = ModuleNode.get_rototranslation(self.parent_module.Homogeneous_tf, rototrasl)
x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(transform)
fixed_joint_name = 'L_' + str(simple_ee.i) + '_fixed_joint_' + str(simple_ee.p) + simple_ee.tag
-
- if self.parent_module.type == 'joint':
+
+ if self.parent_module.type is ModuleType.JOINT:
father_name = 'L_' + str(self.parent_module.i) + self.parent_module.tag
else:
father_name = self.parent_module.name
@@ -2359,8 +1763,14 @@ def add_simple_ee(self, x_offset=0.0, y_offset=0.0, z_offset=0.0, angle_offset=0
self.collision_elements.append((father_name, simple_ee.name))
- self.parent_module = simple_ee
self.add_to_chain(simple_ee)
+
+ self.parent_module = simple_ee
+
+ # Select the current connector of the new module
+ selected_connector = self.select_connector(simple_ee)
+ # Select the meshes to highlight in the GUI
+ selected_meshes = self.select_meshes(selected_connector, simple_ee)
if self.speedup:
self.urdf_string = ""
@@ -2368,35 +1778,62 @@ def add_simple_ee(self, x_offset=0.0, y_offset=0.0, z_offset=0.0, angle_offset=0
# Process the urdf string by calling the process_urdf method. Parse, convert from xacro and write to string
self.urdf_string = self.process_urdf()
- # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
- data = {'result': self.urdf_string,
- 'lastModule_type': simple_ee.type,
- 'lastModule_name': simple_ee.name,
+ # Create the dictionary with the relevant info on the selected module, so that the GUI can dispaly it.
+ data = {'name': simple_ee.name,
+ 'type': simple_ee.type,
'flange_size': simple_ee.flange_size,
- 'count': simple_ee.i}
+ 'selected_connector': selected_connector,
+ 'selected_meshes': selected_meshes,
+ 'urdf_string': self.urdf_string}
return data
- def add_wheel_module(self, wheel_filename, steering_filename, angle_offset, reverse=False, robot_id=(0,0)):
- steering_data = self.add_module(steering_filename, angle_offset, reverse, robot_id[0])
- wheel_data = self.add_module(wheel_filename, angle_offset, reverse, robot_id[1])
+ def add_wheel_module(self, wheel_filename, steering_filename, offsets={}, reverse=False, robot_id=(0,0)):
+ steering_data = self.add_module(steering_filename, offsets, reverse, robot_id=robot_id[0])
+ wheel_data = self.add_module(wheel_filename, offsets, reverse, robot_id=robot_id[1])
return wheel_data, steering_data
- def add_module(self, filename, angle_offset, reverse=False, robot_id=0, active_ports=3):
+ def add_addon(self, addon_filename):
+ new_addon = None
+ try:
+ addons_dict = self.modular_resources_manager.get_available_addons_dict()
+ new_addon = addons_dict[addon_filename]
+ if new_addon['header']['type'] == 'drillbit':
+ self.parent_module.addon_elements += self.add_drillbit(length=new_addon['parameters']['length'], radius=new_addon['parameters']['radius'], mass=new_addon['parameters']['mass'])
+ elif new_addon['header']['type'] == 'handle':
+ self.parent_module.addon_elements += self.add_handle(x_offset=new_addon['parameters']['x_offset'], y_offset=new_addon['parameters']['y_offset'], z_offset=new_addon['parameters']['z_offset'], mass=new_addon['parameters']['mass'], radius=new_addon['parameters']['radius'])
+ else:
+ self.logger.info('Addon type not supported')
+
+ except FileNotFoundError:
+ raise FileNotFoundError(addon_filename+' was not found in the available resources')
+
+
+ def add_module(self, filename, offsets={}, reverse=False, addons =[], robot_id=0, active_ports=3, is_structural=True, module_name=None):
"""Add a module specified by filename as child of the currently selected module.
Parameters
----------
filename: str
String with the name of the YAML file to load, describing the module parameters
- angle_offset: float
- Value of the angle between the parent module output frame and the module input frame
+ offsets: dict
+ Dictionary containing the various offsets ('x','y','z','roll','pitch','yaw') between the parent module output frame and the module input frame. Es. offsets = {'x': 1.0, 'y': 2.0, 'yaw': 1.57}
reverse: bool
Bool value expressing if the module is mounted in reverse direction (true) or in standard one (false).
By default it is false.
+ Not used for hub types (cube, mobile base, etc.).
+ robot_id: int
+ Value of the robot_id set in the firmware of the module.
+ This is obtained in Discovery Mode when reading the JSON from the EtherCAT master. This is not used when in Bulding Mode.
+ active_ports: int
+ The number of active ports of the module (how many ports have established a connection to a module).
+ This is the integer conversion of the 4-bit binary string where each bit represent one port (1 if port is active, 0 if port is unactive)
+ is_structural: bool
+ Bool value expressing if the module is structural (true) or not (false).
+ Used only for hub types (cube, mobile base, etc.).
Returns
-------
@@ -2409,37 +1846,35 @@ def add_module(self, filename, angle_offset, reverse=False, robot_id=0, active_p
self.print(path_name)
self.print(filename)
- new_module = None
- # Generate the path and access the required YAML file
- for resource_path in self.resources_paths:
- template_name = self.resource_finder.get_filename('yaml/template.yaml', ['resources_path'])
- try:
- if filename.lower().endswith(('.yaml', '.yml')):
- # Generate the path to the required YAML file
- module_name = self.resource_finder.get_filename('yaml/'+filename, resource_path)
- # Load the module from YAML and create a ModuleNode instance
- new_module = ModuleNode.module_from_yaml(module_name, self.parent_module, template_name, reverse)
- self.print("Module loaded from YAML: " + new_module.name)
- elif filename.lower().endswith(('.json')):
- # Generate the path to the required YAML file
- module_name = self.resource_finder.get_filename('json/'+filename, resource_path)
- # Load the module from YAML and create a ModuleNode instance
- new_module = ModuleNode.module_from_json(module_name, self.parent_module, template_name, reverse)
- self.print("Module loaded from JSON: " + new_module.name)
- break
- except FileNotFoundError:
- continue
- if new_module is None:
- raise FileNotFoundError(filename+' was not found in the available resources')
-
- # If the parent is a connector module, it means we are starting a new branch from a cube.
+ try:
+ module_dict = self.modular_resources_manager.get_available_modules_dict()[filename]
+ template_dict = self.modular_resources_manager.get_available_modules_dict()['template.yaml']
+ if filename.lower().endswith(('.yaml', '.yml')):
+ # Load the module from YAML and create a ModuleNode instance
+ new_module = ModuleNode.module_from_yaml_dict(module_dict, self.parent_module, template_dict, reverse)
+ self.print("Module loaded from YAML: " + new_module.name)
+ elif filename.lower().endswith(('.json')):
+ # Load the module from YAML and create a ModuleNode instance
+ new_module = ModuleNode.module_from_json_dict(module_dict, self.parent_module, template_dict, reverse)
+ self.print("Module loaded from JSON: " + new_module.name)
+ except KeyError:
+ raise KeyError(filename+' was not found in the available resources')
+
+ # Socket module is a custom type. It behaves differently from other link modules because it has no electronics onboard. Its parent should always be the base_link. On the hardware it will actually be connected to a non-structural hub, which therefore will not be part of the URDF, so we consider the base_link to be the parent in any case. This means the ports of the hub will not actually be occupied, so potentially there is no limit to how many sockets could be connected (>3).
+ if new_module.type is ModuleType.SOCKET:
+ self.parent_module = new_module.parent = self.base_link
+
+ # If the parent is a hub module, it means we are starting a new branch.
# Then assign the correct tag (A, B, C, ...) to the new module (and therefore start a new branch)
# by looking at the current tag_num (1, 2, 3, ...) and so at how many branches are already present in the robot.
# If the parent is any other kind of module, assign as tag the same of his parent.
- if self.parent_module.type == 'cube' or self.parent_module.type == 'mobile_base' :
+ if (
+ self.parent_module.type in ModuleClass.hub_modules() | {ModuleType.BASE_LINK}
+ and new_module.type not in ModuleClass.hub_modules()
+ ):
+ self.tag_num += 1
tag_letter = self.branch_switcher.get(self.tag_num)
setattr(new_module, 'tag', tag_letter)
- self.tag_num += 1
else:
setattr(new_module, 'tag', self.parent_module.tag)
@@ -2451,65 +1886,129 @@ def add_module(self, filename, angle_offset, reverse=False, robot_id=0, active_p
# flange_size is already set from the YAML file
# setattr(new_module, 'flange_size', self.parent_module.flange_size)
- setattr(new_module, 'angle_offset', angle_offset)
+ setattr(new_module, 'offsets', offsets)
setattr(new_module, 'reverse', reverse)
setattr(new_module, 'robot_id', robot_id)
+ # Attribute specifying if the module is structural or not. Useful for those types of modules that are not structural (e.g. hubs), in particular if they are present in the network and discovered by EtherCAT, but they are not part of the robot structure.
+ if hasattr(new_module.header, 'is_structural'):
+ setattr(new_module, 'is_structural', new_module.header.is_structural)
+ else:
+ # if the attribute is not present, set it, otherwise leave it as it is (it has been set from the YAML/JSON file)
+ setattr(new_module, 'is_structural', is_structural)
+
self.print("parent module:", self.parent_module.name, ", type :", self.parent_module.type)
# Update the EtherCAT port connected to the electro-mechanical interface where the new module/slave will be added
+ #################################################
+ # non-hub modules:
# 1 2 3 4
# o o o o
# | | | |
# input port output port nothing nothing
- setattr(new_module, 'selected_port', 2)
- self.print('mastercube.selected_port :', new_module.selected_port)
+ #################################################
+ # cube modules:
+ # 1 2 3 4
+ # o o o o
+ # | | | |
+ # com-exp upper port front port nothing
+ #################################################
+ setattr(new_module, 'current_port', 1)
+ self.print('new_module.current_port :', new_module.current_port)
# save the active ports as a binary string
- setattr(new_module, 'active_ports', "{0:04b}".format(active_ports))
+ setattr(new_module, 'active_ports', "{0:04b}".format(active_ports))
self.print('active_ports: ', new_module.active_ports)
# save the occupied ports as a binary string
setattr(new_module, 'occupied_ports', "0001")
self.print('occupied_ports: ', new_module.occupied_ports)
+ # add list of addons as attribute
+ setattr(new_module, 'addon_elements', [])
+
+ # add list of urdf elements as attribute
+ setattr(new_module, 'xml_tree_elements', [])
+
+ # add list of xml elements with an associated visual mesh as attribute
+ setattr(new_module, 'mesh_names', [])
+
+ # add list of connectors names as attribute. The 0 connector is added by default. The others will be added by the add_connectors() method
+ setattr(new_module, 'connectors', ['connector_0'])
+
+ # For certain types of modules, the model is considered as floating base, i.e. the base_link is not fixed to the world frame, but is connected through a floating joint.
+ # WARNING: this changes the behavior of the whole URDF not only for this module
+ if new_module.type in {'mobile_base'}:
+ self.set_floating_base(True)
+
# Depending on the type of the parent module and the new module, call the right method to add the new module.
# Add the module to the correct chain via the 'add_to_chain' method.
-
- #if self.parent_module.type == "base_link":
-
if self.parent_module.type == 'joint':
if new_module.type in { 'joint', 'wheel' }:
# joint + joint
self.print("joint + joint")
- self.joint_after_joint(new_module, self.parent_module, angle_offset, reverse=reverse)
+ self.joint_after_joint(new_module, self.parent_module, offsets=offsets, reverse=reverse)
+ elif new_module.type in { 'cube', 'mobile_base' }:
+ # joint + hub
+ self.print("joint + hub")
+ self.hub_after_joint(new_module, self.parent_module, offsets=offsets, reverse=reverse, module_name=module_name)
else:
# joint + link
self.print("joint + link")
- self.link_after_joint(new_module, self.parent_module, angle_offset, reverse=reverse)
+ self.link_after_joint(new_module, self.parent_module, offsets=offsets, reverse=reverse)
elif self.parent_module.type == 'wheel':
# TODO: prevent adding modules after wheels in a better way (raise exception?)
return {'result': 'ERROR: module cannot be added after wheel module. Select another chain or remove the wheel module.'}
- elif self.parent_module.type == 'cube' or self.parent_module.type == "mobile_base":
+ elif self.parent_module.type in {'cube', "mobile_base"}:
if new_module.type in { 'joint', 'wheel' }:
- # cube + joint
- self.joint_after_cube(new_module, self.parent_module, angle_offset, reverse=reverse)
+ # hub + joint
+ self.print("hub + joint")
+ self.joint_after_hub(new_module, self.parent_module, offsets=offsets, reverse=reverse)
+ elif new_module.type in { 'cube', 'mobile_base' }:
+ # hub + hub
+ self.print("hub + hub")
+ self.hub_after_hub(new_module, self.parent_module, offsets=offsets, reverse=reverse, module_name=module_name)
else:
- # cube + link
- self.link_after_cube(new_module, self.parent_module, angle_offset, reverse=reverse)
+ # hub + link
+ self.print("hub + link")
+ self.link_after_hub(new_module, self.parent_module, offsets=offsets, reverse=reverse)
else:
if new_module.type in { 'joint', 'wheel' }:
# link + joint
self.print("link + joint")
- self.joint_after_link(new_module, self.parent_module, angle_offset, reverse=reverse)
+ self.joint_after_link(new_module, self.parent_module, offsets=offsets, reverse=reverse)
+ elif new_module.type in { 'cube', 'mobile_base' }:
+ # link + hub
+ self.print("link + hub")
+ self.hub_after_link(new_module, self.parent_module, offsets=offsets, reverse=reverse, module_name=module_name)
else:
# link + link
self.print("link + link")
- self.link_after_link(new_module, self.parent_module, angle_offset, reverse=reverse)
+ self.link_after_link(new_module, self.parent_module, offsets=offsets, reverse=reverse)
- # Add the module to the list of chains
+ # # TODO: check if this is correct
+ # # Add the module to the list of chains if there is at least a joint before it
+ # if new_module.i > 0:
+ # self.add_to_chain(new_module)
self.add_to_chain(new_module)
+ # Update the parent_module attribute of the URDF_writer class
+ self.parent_module = new_module
+
+ # Select the current connector of the new module
+ selected_connector = self.select_connector(new_module, port_idx=new_module.current_port)
+ # Select the meshes to highlight in the GUI
+ selected_meshes = self.select_meshes(selected_connector, new_module)
+
+ for addon in addons:
+ try:
+ self.add_addon(addon_filename=addon)
+ except FileNotFoundError:
+ self.logger.error(f'Addon {addon} not found, skipping it')
+
+ # add meshes to the map
+ self.mesh_to_module_map.update({k: new_module.name for k in new_module.mesh_names})
+
if self.speedup:
self.urdf_string = ""
else:
@@ -2522,55 +2021,119 @@ def add_module(self, filename, angle_offset, reverse=False, robot_id=0, active_p
if self.verbose:
# Render tree
for pre, _, node in anytree.render.RenderTree(self.base_link):
- self.print("%s%s" % (pre, node.name))
+ self.print("%s%s: %d" % (pre, node.name, node.robot_id))
# Create a dictionary containing the urdf string just processed and other parameters needed by the web app
- data = {'result': self.urdf_string,
- 'lastModule_type': new_module.type,
- 'lastModule_name': new_module.name,
+ data = {'name': new_module.name,
+ 'type': new_module.type,
'flange_size': new_module.flange_size,
- 'count': new_module.i}
-
- # if new_module.name.endswith('_stator'):
- # new_module.name = selected_module[:-7]
- # last_module = anytree.search.findall_by_attr(L_0a, selected_module)[0]
-
- # Update the parent_module attribute of the URDF_writer class
- self.parent_module = new_module
-
- # self.print(self.parent_module)
+ 'selected_connector': selected_connector,
+ 'selected_meshes': selected_meshes,
+ 'urdf_string': self.urdf_string}
self.info_print("Module added to URDF: " + new_module.name + " (" + new_module.type + ")")
return data
- def add_gazebo_element(self, new_module_gazebo, new_module_name):
+ def add_gazebo_element(self, new_module_obj, gazebo_obj, new_module_name):
"""
Add a gazebo element to the new module
"""
# Add the gazebo element to the new module
- if new_module_gazebo is not None:
- gazebo_if_el = ET.SubElement(self.root,
- 'xacro:if',
- value="${GAZEBO_URDF}")
- gazebo_el = ET.SubElement(gazebo_if_el,
+ if gazebo_obj is not None:
+ gazebo_el_name = 'gazebo_' + new_module_name
+ gazebo_if_el = ET.SubElement(self.root,
+ 'xacro:xacro_if_guard',
+ value="${GAZEBO_URDF}",
+ name = gazebo_el_name)
+ new_module_obj.xml_tree_elements.append(gazebo_el_name)
+
+ gazebo_el = ET.SubElement(gazebo_if_el,
'gazebo',
reference=new_module_name)
- self.add_gazebo_element_children(new_module_gazebo, gazebo_el)
-
- def add_gazebo_element_children(self, new_module_gazebo, gazebo_element):
+ self.add_gazebo_element_children(gazebo_obj, gazebo_el)
+
+
+ def add_gazebo_element_children(self, gazebo_child_obj, gazebo_element):
"""
Add the gazebo element children to the new module
"""
- for key, value in vars(new_module_gazebo).items():
+ for key, value in vars(gazebo_child_obj).items():
gazebo_child_el = ET.SubElement(gazebo_element, key)
if isinstance(value, ModuleNode.Module.Attribute):
- self.print(vars(value))
self.add_gazebo_element_children(value, gazebo_child_el)
else:
- self.print(value)
gazebo_child_el.text = str(value)
+
+ def update_module(self, selected_module=0, offsets={}, reverse=False, addons=[]):
+ if selected_module == 0:
+ selected_module = (self.parent_module)
+ # If the selected module is a connector module, select his parent (the hub) instead
+ if '_con' in selected_module.name:
+ selected_module = selected_module.parent
+
+ self.info_print('Updating module: ' + str(selected_module.name))
+
+ # Update generator expression
+ self.update_generators()
+
+ # Update offsets. MEMO: to be fixed! must apply offsets not overwrite
+ for node in self.urdf_nodes_generator:
+ try:
+ if node.attrib['name'] == selected_module.fixed_joint_name:
+ for key in offsets.keys():
+ node.set(key, str(offsets[key]))
+ except (KeyError, AttributeError):
+ pass
+
+ # update generator expression
+ self.update_generators()
+
+ # remove addons
+ if(getattr(selected_module, 'addon_elements')):
+ for node in self.urdf_nodes_generator:
+ try:
+ if node.attrib['name'] in selected_module.addon_elements:
+ # remove mesh from list of meshes and from the map
+ if node.attrib['name'] in selected_module.mesh_names:
+ selected_module.mesh_names.remove(node.attrib['name'])
+ self.mesh_to_module_map.pop(node.attrib['name'])
+ # remove node from tree
+ self.root.remove(node)
+ except KeyError:
+ pass
+
+ for addon in addons:
+ try:
+ self.add_addon(addon_filename=addon)
+ except FileNotFoundError:
+ self.logger.error(f'Addon {addon} not found, skipping it')
+
+ self.mesh_to_module_map.update({k: selected_module.name for k in selected_module.mesh_names})
+
+ # Select the current connector of the new module
+ selected_connector = self.select_connector(selected_module, port_idx=selected_module.current_port)
+ # Select the meshes to highlight in the GUI
+ selected_meshes = self.select_meshes(selected_connector, selected_module)
+
+ if self.speedup:
+ self.urdf_string = ""
+ else:
+ # Process the urdf string by calling the process_urdf method. Parse, convert from xacro and write to string
+ # Update the urdf file, removing the module
+ self.urdf_string = self.process_urdf()
+
+ # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
+ data = {'name': selected_module.name,
+ 'type': selected_module.type,
+ 'flange_size': selected_module.flange_size,
+ 'selected_connector': selected_connector,
+ 'selected_meshes': selected_meshes,
+ 'urdf_string': self.urdf_string}
+
+ return data
+
def remove_module(self, selected_module=0):
"""Remove the selected module (and all its childs and descendants) and return info on its parent
@@ -2578,8 +2141,7 @@ def remove_module(self, selected_module=0):
Parameters
----------
selected_module: ModuleNode.ModuleNode
- NodeModule object of the module to remove. Default value is 0, in which case the current parent_module is
- selected as the module to be removed.
+ NodeModule object of the module to remove. Default value is 0, in which case the current parent_module is selected as the module to be removed.
Returns
-------
@@ -2588,199 +2150,68 @@ def remove_module(self, selected_module=0):
In particular the updated and newly processed urdf string, so without the removed modules.
"""
- # global tag, n_cubes, parent_module
-
# If no selected_module argument was passed to the method,
# select the current parent module to be the one to remove
if selected_module == 0:
selected_module = (self.parent_module)
- # If the selected module is a connector module, select his parent (the cube) instead
- if '_con' in selected_module.name:
- selected_module = selected_module.parent
-
self.info_print('Removing module: ' + str(selected_module.name) + ' (and all its descendants)')
- # If the selected module is NOT a cube start by first removing its child and descendants.
- # There is a recursive call to this function inside the loop to remove each module.
- if selected_module.type != 'cube':
- self.print('eliminate child')
- for child in selected_module.children:
- self.remove_module(child)
-
- self.print(selected_module.children)
- self.print(selected_module.parent.name)
+ # Remove the module childs and its descendants recursively
+ for child in selected_module.children:
+ self.print('eliminate child: ' + child.name + ' of type: ' + child.type + ' of parent: ' + selected_module.name)
+ self.remove_module(child)
# update generator expression
- self.update_generator()
- #self.gen = (node for node in self.root.findall("*") if node.tag != 'gazebo')
+ self.update_generators()
+
+ xml_elements_to_remove = []
+ # remove addons
+ if(getattr(selected_module, 'addon_elements')):
+ xml_elements_to_remove += selected_module.addon_elements
+ # remove module xml elements
+ if(getattr(selected_module, 'xml_tree_elements')):
+ xml_elements_to_remove += selected_module.xml_tree_elements
+
+ # remove all required xml elements from the tree
+ for node in self.urdf_nodes_generator:
+ try:
+ if node.attrib['name'] in xml_elements_to_remove:
+ # remove mesh from list of meshes and from the map
+ if node.attrib['name'] in selected_module.mesh_names:
+ selected_module.mesh_names.remove(node.attrib['name'])
+ self.mesh_to_module_map.pop(node.attrib['name'])
+ # remove node from tree
+ self.root.remove(node)
+ except KeyError:
+ pass
- # switch depending on module type
- if selected_module.type in { 'joint', 'wheel' }:
- #remove the joints from the list of chains
- self.remove_from_chain(selected_module)
+ # save parent of the module to remove. This will be the last element of the chain after removal,
+ # and its data will be returned by the function
+ father = selected_module.parent
- # save parent of the module to remove. This will be the last element of the chain after removal,
- # and it'll be returned by the function
- father = selected_module.parent
-
- # From the list of xml elements find the ones with name corresponding to the relative joint, stator link
- # and fixed joint before the stator link and remove them from the xml tree
- for node in self.gen:
- try:
- if node.attrib['name'] == selected_module.name:
- self.root.remove(node)
- elif node.attrib['name'] == selected_module.stator_name:
- self.root.remove(node)
- elif node.attrib['name'] == selected_module.fixed_joint_stator_name:
- self.root.remove(node)
- elif node.attrib['name'] == selected_module.distal_link_name:
- self.root.remove(node)
- elif node.attrib['name'] == selected_module.distal_link_name + '_rotor_fast':
- self.root.remove(node)
- elif node.attrib['name'] == 'fixed_' + selected_module.distal_link_name + '_rotor_fast':
- self.root.remove(node)
- except KeyError:
- pass
+ # remove the module from the list of chains
+ self.remove_from_chain(selected_module)
+ # switch depending on module type
+ if selected_module.type in ModuleClass.joint_modules():
self.control_plugin.remove_joint(selected_module.name)
- # TODO: This is not working in the urdf. The ModuleNode obj is removed but the elment from the tree is not
- elif selected_module.type == 'cube':
- self.listofhubs.remove(selected_module)
- # save parent of the module to remove. This will be the last element of the chain after removal,
- # and its data will be returned by the function
- father = selected_module.parent.parent
- self.print(selected_module.parent.name)
-
- # update attribute representing number of cubes present in the model
- self.n_cubes -= 1
-
- # Remove childs of the cube (so connectors!)
- for child in selected_module.children:
- for node in self.gen:
- try:
- if node.attrib['name'] == child.name:
- self.root.remove(node)
- except KeyError:
- pass
-
- # Remove the cube module from the xml tree
- for node in self.gen:
- try:
- if node.attrib['name'] == selected_module.name:
- self.root.remove(node)
- except KeyError:
- pass
-
- # selected_module.parent = None
-
- # select the father module of the cube
- father_module = self.access_module_by_name(selected_module.parent.name)
-
- # Generate the name of the fixed joint between parent and cube
- joint_name = 'FJ_' + father_module.parent.parent.name + '_' + father_module.name
- self.print(joint_name)
-
- # Remove the fixed joint
- for node in self.gen:
- try:
- if node.attrib['name'] == joint_name:
- #self.print(joint_name)
- self.root.remove(node)
- except KeyError:
- pass
-
- # before deleting father_module set his parent property to None. Otherwise this will mess up the obj tree
- father_module.parent = None
-
- # delete object father_module
- del father_module
- elif selected_module.type == 'gripper':
- #remove the gripper from their chain
- self.remove_from_chain(selected_module)
-
- # save parent of the module to remove. This will be the last element of the chain after removal,
- # and its data will be returned by the function
- father = selected_module.parent
-
- # Generate te name of the fixed joint connecting the module with its parent
- fixed_joint_name = str(selected_module.name) + '_fixed_joint'
-
- for node in self.gen:
- try:
- if node.attrib['name'] == fixed_joint_name:
- self.root.remove(node)
- elif node.attrib['name'] == selected_module.name:
- self.root.remove(node)
- except KeyError:
- pass
-
+ elif selected_module.type is ModuleType.GRIPPER:
# TO BE FIXED: ok for ros_control. How will it be for xbot2?
self.control_plugin.remove_joint(selected_module.name+'_finger_joint1')
self.control_plugin.remove_joint(selected_module.name+'_finger_joint2')
- elif selected_module.type == 'tool_exchanger':
- #remove the tool exchanger from the chain
- self.remove_from_chain(selected_module)
-
- # save parent of the module to remove. This will be the last element of the chain after removal,
- # and its data will be returned by the function
- father = selected_module.parent
-
- # Generate te name of the fixed joint connecting the module with its parent
- fixed_joint_name = str(selected_module.name) + '_fixed_joint'
-
- for node in self.gen:
- try:
- if node.attrib['name'] == fixed_joint_name:
- self.root.remove(node)
- elif node.attrib['name'] == selected_module.name:
- self.root.remove(node)
- elif node.attrib['name'] == selected_module.pen_name:
- self.root.remove(node)
- elif node.attrib['name'] == 'fixed_'+selected_module.pen_name:
- self.root.remove(node)
-
- except KeyError:
- pass
-
- else:
- # save parent of the module to remove. This will be the last element of the chain after removal,
- # and its data will be returned by the function
- father = selected_module.parent
-
- # Generate te name of the fixed joint connecting the module with its parent
- fixed_joint_name = 'L_' + str(selected_module.i) + '_fixed_joint_' + str(
- selected_module.p) + selected_module.tag
-
- for node in self.gen:
- try:
- if node.attrib['name'] == fixed_joint_name:
- self.root.remove(node)
- elif node.attrib['name'] == selected_module.name:
- self.root.remove(node)
- except KeyError:
- pass
+ elif selected_module.type in ModuleClass.hub_modules():
+ # if the module is a hub, remove it from the list of hubs
+ self.listofhubs.remove(selected_module)
- # if selected_module.type == 'link':
- # #root.remove(root.findall("*[@name=selected_module.name]", ns)[-1])
- # for node in self.gen:
- # if node.attrib['name'] == selected_module.name:
- # self.root.remove(node)
- # self.gen = (node for node in self.root.findall("*") if node.tag != 'gazebo')
- # elif selected_module.type == 'elbow':
- # #root.remove(root.findall("*[@name=selected_module.name]", ns)[-1])
- # for node in self.gen:
- # if node.attrib['name'] == selected_module.name:
- # self.root.remove(node)
- # self.gen = (node for node in self.root.findall("*") if node.tag != 'gazebo')
- # elif selected_module.type == 'size_adapter':
- # #root.remove(root.findall("*[@name=selected_module.name]", ns)[-1])
- # for node in self.gen:
- # if node.attrib['name'] == selected_module.name:
- # self.root.remove(node)
- # self.gen = (node for node in self.root.findall("*") if node.tag != 'gazebo')
+ # if the parent module is a hub, decrease the tag number. A chain has been removed, tag should be reset accordingly
+ if (
+ father.type in ModuleClass.hub_modules() | {ModuleType.BASE_LINK}
+ and selected_module.type not in ModuleClass.hub_modules()
+ ):
+ self.tag_num -= 1
if self.speedup:
self.urdf_string = ""
@@ -2789,31 +2220,25 @@ def remove_module(self, selected_module=0):
# Update the urdf file, removing the module
self.urdf_string = self.process_urdf()
- # Update parent module attribute. TODO: understand why and if it's needed
- if not self.parent_module.children:
- self.parent_module = father
+ # Update the parent_module attribute of the URDF_writer class
+ self.parent_module = father
- # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
- if father.type == 'cube':
- data = {'result': self.urdf_string,
- 'lastModule_type': father.type,
- 'lastModule_name': father.name,
- 'flange_size': father.flange_size,
- 'count': self.n_cubes}
- else:
- data = {'result': self.urdf_string,
- 'lastModule_type': father.type,
- 'lastModule_name': father.name,
- 'flange_size': father.flange_size,
- 'count': father.i}
- # data = jsonify(data)
-
- if '_con' in father.name:
- self.tag_num -= 1
+ # Select the current connector of the new module
+ selected_connector = self.select_connector(father, port_idx=self.connector_to_port_idx(father.connector_idx, father))
+ # Select the meshes to highlight in the GUI
+ selected_meshes = self.select_meshes(selected_connector, father)
+
+
+ # Create a dictionary containing the urdf string just processed and other parameters needed by the web app
+ data = {'name': father.name,
+ 'type': father.type,
+ 'flange_size': father.flange_size,
+ 'selected_connector': selected_connector,
+ 'selected_meshes': selected_meshes,
+ 'urdf_string': self.urdf_string}
# before deleting selected_module set his parent property to None. Otherwise this will mess up the obj tree
selected_module.parent = None
- # selected_module.parent.children = None
# delete object selected_module
del selected_module
@@ -2873,226 +2298,392 @@ def access_module_by_name(self, queried_module_name):
queried_module = anytree.search.findall_by_attr(self.base_link, queried_module_name)[0]
self.print('queried_module.type: ', queried_module.type)
-
+
# Update parent_module attribute
self.parent_module = queried_module
- return queried_module
+ return queried_module
+
+ def select_module_from_id(self, id, current_port=None):
+ """Allows to select a module from the tree. An inner call to access_module_by_id sets the selected module as the
+ current parent module. Returns info on the selected module, so that the GUI can display it.
+
+ Parameters
+ ----------
+ id: int
+ The id of the module to select. It will be used to call the access_module_by_id method.
+ The corresponding object module data is then put in a dictionary and returned.
+
+ current_port: int
+ Represent the current port. If the module is a hub/box it is used to select tjhe connector to be used.
+
+ Returns
+ -------
+ data: dict
+ The dictionary containing all necessary data about the selected module.
+
+ """
+ # global parent_module
+ self.print('id: ', id)
+
+ # Call the access_module_by_id method to find the selected module
+ selected_module = self.access_module_by_id(id)
+
+ # Select the current connector of the selected module
+ selected_connector = self.select_connector(selected_module, port_idx=current_port)
+ # Select the meshes to highlight in the GUI
+ selected_meshes = self.select_meshes(selected_connector, selected_module)
+
+ # Create the dictionary with the relevant info on the selected module, so that the GUI can dispaly it.
+ data = {'name': selected_module.name,
+ 'type': selected_module.type,
+ 'flange_size': selected_module.flange_size,
+ 'selected_connector': selected_connector,
+ 'selected_meshes': selected_meshes,
+ 'urdf_string': self.urdf_string}
+
+ return data
+
+ def select_module_from_name(self, name, current_port=None):
+ """Allows to select a module from the tree. An inner call to access_module_by_name sets the selected module as the
+ current parent module. Returns info on the selected module, so that the GUI can display it.
+
+ Parameters
+ ----------
+ name: str
+ String with the name of the module to select or the name of the mesh clicked on the GUI. It will be used to call the access_module_by_name method.
+ The corresponding object module data is then put in a dictionary and returned.
+
+ current_port: int
+ Represent the current port. If the module is a hub/box it is used to select tjhe connector to be used.
+
+ Returns
+ -------
+ data: dict
+ The dictionary containing all necessary data about the selected module.
+
+ """
+
+ self.print(name)
+
+ # If the name of the mesh clicked on the GUI is not the name of the module, but the name of the mesh, we need to
+ # find the module object from the mesh name. The mesh_to_module_map dictionary is used for this. Default value
+ # is the name itself, so if the name is not in the dictionary, it is the name of the module itself.
+ selected_module_name = self.mesh_to_module_map.get(name, name)
+
+ # Call access_module_by_name to get the object with the requested name and sets it as parent.
+ # The method doing the real work is actually access_module_by_name
+ selected_module = self.access_module_by_name(selected_module_name)
+
+ # Select the current connector of the selected module
+ selected_connector = self.select_connector(selected_module, connector_name=name, port_idx=current_port)
+ # Select the meshes to highlight in the GUI
+ selected_meshes = self.select_meshes(selected_connector, selected_module)
+
+ # Create the dictionary with the relevant info on the selected module, so that the GUI can dispaly it.
+ data = {'name': selected_module.name,
+ 'type': selected_module.type,
+ 'flange_size': selected_module.flange_size,
+ 'selected_connector': selected_connector,
+ 'selected_meshes': selected_meshes,
+ 'urdf_string': self.urdf_string}
+
+ return data
+
+
+ def port_to_connector_idx(self, port_idx, module):
+ """Convert the port index to the connector index, for the given module.
+
+ Parameters
+ ----------
+ port_idx: int
+ The index of the port to convert.
+
+ module: ModuleNode.ModuleNode
+ The module to compute the connector index for.
+
+ Returns
+ -------
+ connector_idx: int
+ The index of the connector corresponding to the port index.
+
+ """
+ # MYNOTE: this part is used only in Discovery mode for now.
+ # TODO: this works only for hub trees of maximum depth 2. For deeper trees, this should be revised.
+ idx_offset = 0
+ # If the hub is not structural, we need to take into account the other children the parent hub might have.
+ # If the hub is not structural, by default its parent must be a hub as well. Non-structural hubs can only be
+ # connected to structural hubs (or other non-structural hubs) and be a "children hub". Their only purpose is to
+ # "increase" the number of ports of its parent hub (and therefore its available connectors).
+ # The connectors are shared between the parent and children hubs, so their index must be computed accordingly.
+ if module.type in ModuleClass.hub_modules() and module.parent.type in ModuleClass.hub_modules() and not module.is_structural:
+ # # The current port used by the parent hub to connect to the hub we are computing the transforms of.
+ # parent_current_port = 1 << self.eth_to_physical_port_idx(module.parent.current_port)
+ # # The ports of the parent hub already occupied before adding the current hub.
+ # parent_already_occupied_ports = int(module.parent.occupied_ports, 2) & ~parent_current_port
+ # # The ports 1, 2 and 3
+ # non_zero_ports = int("1110", 2)
+ # # The ports of the parent hub already occupied before adding the current hub, excluding the port 0.
+ # parent_ports_occupied_before_hub = (parent_already_occupied_ports & non_zero_ports)
+ # # The number of children the parent hub has before adding the current hub.
+ # n_children_before_hub = 0
+ # for i in range(4):
+ # if parent_ports_occupied_before_hub & (1 << i):
+ # n_children_before_hub += 1
+
+ # The number of hubs children the parent hub has after adding the current hub.
+ parent_elder_hubs_children = module.parent.n_children_hubs - 1
+ # The index offset is computed by looking at the number of children hubs and non-hubs the parent hub has before adding the current hub.
+ if parent_elder_hubs_children > 0:
+ # Count the number of non-structural hubs children the parent hub has (sieblings of the current hub)
+ # Remove the current hub from the count, should not be taken into account when counting the index.
+ nonstructural_hub_children = self.count_children_non_structural_hubs(module.parent, count=-1)
+ # We take into account the other hubs connected to get the right index. We have 4 connectors per hub, but since port 0 is occupied by the hub-hub connection, each child hub increase the index by 3
+ idx_offset += (4-1)*nonstructural_hub_children
+ # We take into account that one port on the current hub (parent) is used to establish a connection with a second hub, and that should not be taken into account when counting the index
+ idx_offset -= 1*nonstructural_hub_children
+ # # Each hub sibling increases the index offset by 1!
+ # idx_offset += (1)*parent_elder_hubs_children
+
+ # The number of non-hubs children the parent hub has before adding the current hub.
+ #parent_elder_nonhubs_children = n_children_before_hub - parent_elder_hubs_children
+ # # the number of non-hubs children increases the index offset by 1 (since each non-hub has 2 connectors, but one is used to connect to the parent hub).
+ # idx_offset +=(parent_elder_nonhubs_children)*1
+ #MYNOTE: this is kind of magic
+ idx_offset += module.parent.current_port - 1
+
+ # indexes for connector and selected port are the same, unless the hub is connected to another non-structural hub
+ connector_idx = port_idx + idx_offset
+
+ # We need to add an offset to the connector index introduced by the other non-structural hubs already connected to the current hub
+ if module.type in ModuleClass.hub_modules():
+ # Count the number of non-structural hubs children the current hub has
+ nonstructural_hub_children = self.count_children_non_structural_hubs(module)
+ # We take into account the other hubs connected to get the right index. We have 4 connectors per hub, but since port 0 is occupied by the hub-hub connection, each child hub increase the index by 3
+ connector_idx += (4-1)*nonstructural_hub_children
+ # We take into account that one port on the current hub (parent) is used to establish a connection with a second hub, and that should not be taken into account when counting the index
+ connector_idx -= 1*nonstructural_hub_children
+
+ return connector_idx
+
+
+ def count_children_non_structural_hubs(self, module, count=0):
+ """Count all non-strucural hubs children and grandchildren of the given module recursively.
+
+ Parameters
+ ----------
+ module: ModuleNode.ModuleNode
+ The module to compute the offset for.
+
+ count: int
+ The current offset count. Default value is 0.
+
+ Returns
+ -------
+ count: int
+ The offset of the connector index for the given module.
+
+ """
+ for child in module.children:
+ count = self.count_children_non_structural_hubs(child, count)
+ if child.type in ModuleClass.hub_modules() and not child.is_structural:
+ count += 1
+ return count
+
+
+ def connector_to_port_idx(self, connector_idx, module):
+ """Convert the connector index to the port index.
+
+ Parameters
+ ----------
+ connector_idx: int
+ The index of the connector to convert.
+
+ Returns
+ -------
+ port_idx: int
+ The index of the port corresponding to the connector index.
+
+ """
+ # MYNOTE: this part is used only in Building mode for now. When the differences between the two modes will be removed, the implemantation of this function will be the reverse of the port_to_connector_idx function.
+
+ # connector index is the same as the port index for the first 4 ports
+ port_idx = connector_idx
+
+ return port_idx
+
+
+ def eth_to_physical_port_idx(self, eth_port_idx):
+ """Convert the EtherCAT port index to the physical port index. This is necessary because the EtherCAT master
+ scans the ports in a different order than the physical one.
+
+ Parameters
+ ----------
+
+ eth_port_idx: int
+ The index of the EtherCAT port to convert.
+
+ Returns
+ -------
+ physical_port_idx: int
+ The index of the physical port corresponding to the EtherCAT port index.
+
+ """
+ eth_to_physical_port_map = {
+ 0: 0,
+ 1: 3,
+ 2: 1,
+ 3: 2
+ }
+ return eth_to_physical_port_map[eth_port_idx]
- def select_module_from_id(self, id, selected_port=None):
- """Allows to select a module from the tree. An inner call to access_module_by_id sets the selected module as the
- current parent module. Returns info on the selected module, so that the GUI can display it.
+
+ def set_current_port(self, module, port_idx=None):
+ """Set the current port of the module, i.e. the one where the new module will be added to.
+ The current port is the first free one, i.e. the first one seen from the EtherCAT master scan.
+ If the port_idx argument is passed, the current port is set to the one specified by it.
Parameters
----------
- id: int
- The id of the module to select. It will be used to call the access_module_by_id method.
- The corresponding object module data is then put in a dictionary and returned.
+ module: ModuleNode.ModuleNode
+ The object of the module to set the current port to.
- selected_port: int
- Represent the port selected if the module is a hub/box
+ port_idx: int
+ The index of the port to select as the current one.
Returns
-------
- data: dict
- The dictionary containing all necessary data about the selected module.
+ module.current_port: int
+ The port selected as the current one.
"""
- # global parent_module
- self.print('id: ', id)
+ # If the port index is not None, it means that the user has selected it from the GUI. Value is overwritten
+ if port_idx is not None:
+ module.current_port = port_idx
+ else:
+ #MYNOTE: this part is used only in Discovery mode for now. occupied ports gets updated only in Discovery mode for now
+ # binary XOR: the free ports are the ones that are active but not occupied
+ free_ports = int(module.active_ports, 2) ^ int(module.occupied_ports, 2)
+ self.print(module.name + " active_ports: " + module.active_ports + " - " + "occupied_ports: " + module.occupied_ports + " =")
+ self.print("{0:04b}".format(free_ports))
- # Call the access_module_by_id method to find the selected module
- selected_module = self.access_module_by_id(id)
+ # remap the ports from the physical order to the EtherCAT order: 3, 2, 1, 0 -> 2, 1, 3, 0.
+ # See EtherCAT slave documentation for more info
+ free_ports_remapped = ((free_ports & int("0110", 2)) << 1) + ((free_ports & int("1000", 2)) >> 2)
+ self.print("{0:04b}".format(free_ports_remapped))
- # TODO: Replace this with select_ports
- # binary XOR
- free_ports = int(selected_module.active_ports, 2) ^ int(selected_module.occupied_ports, 2)
- self.print("{0:04b}".format(free_ports))
+ # By default the selected port is the first free one (the firt one seen from the EtherCAT master scan)
+ selected_eth_port = self.ffs(free_ports_remapped)
+ self.print('selected EtherCAT port :', selected_eth_port)
- selected_module.selected_port = self.ffs(free_ports)
- self.print('selected_module.selected_port :', selected_module.selected_port)
-
- # # If parent topology is greater than 2 the parent is a switch/hub so we need to find the right port where the module is connected
- # if active_ports >= 3:
- # for port_idx in range(2, len(mastercube.active_ports) - 1)
- # if mastercube.active_ports[-port_idx] == 1:
- # mastercube.selected_port = port_idx
- # break
-
- # if parent_active_ports == 3:
- # self.parent_module.selected_port = 3
- # elif parent_active_ports == 5:
- # self.parent_module.selected_port = 4
- # self.print('self.parent_module.selected_port: ', self.parent_module.selected_port)
+ # MYNOTE: this part is not needed. We are not interested in the physical port index, but in the EtherCAT port index, so that it matches the order of the ports in the EtherCAT master scan.
+ # # remap the ports from the EtherCAT order to the physical order: 2, 1, 3, 0 -> 3, 2, 1, 0.
+ # selected_physical_port = self.eth_to_physical_port_idx(selected_eth_port)
+ # self.print('selected physical port :', selected_physical_port)
- # Create the dictionary with the relevant info on the selected module, so that the GUI can dispaly it.
- if selected_module.type == 'cube':
- data = {'lastModule_type': selected_module.type,
- 'lastModule_name': selected_module.name,
- 'flange_size': selected_module.flange_size,
- 'count': self.n_cubes}
- else:
- data = {'lastModule_type': selected_module.type,
- 'lastModule_name': selected_module.name,
- 'flange_size': selected_module.flange_size,
- 'count': selected_module.i}
+ # Set the current_port attribute of the module
+ module.current_port = selected_eth_port
- return data
+ self.print('module.current_port :', module.current_port)
- def select_module_from_name(self, name, selected_port=None):
- """Allows to select a module from the tree. An inner call to access_module_by_name sets the selected module as the
- current parent module. Returns info on the selected module, so that the GUI can display it.
+ return module.current_port
+
+
+ def select_connector(self, module, connector_name=None, port_idx=None):
+ """Select the connector of the module to which the new module will be added to.
+ If no `connector_name` is passed, the connector is the first free one, i.e. the first one seen from the EtherCAT master scan. (Discovery mode)
+ Otherwise the connector name is selected as the one passed as argument. (Building mode)
Parameters
----------
- name: str
- String with the name of the module to select or the name of the mesh clicked on the GUI. It will be used to call the access_module_by_name method.
- The corresponding object module data is then put in a dictionary and returned.
+ module: ModuleNode.ModuleNode
+ The object of the module to set the current port to.
- selected_port: int
- Represent the port selected if the module is a hub/box
+ connector_name: str
+ String with the name of the connector. Could come from the name of the mesh clicked on the GUI and associated to the connector.
+
+ port_idx: int
+ The index of the port to select as the current one.
Returns
-------
- data: dict
- The dictionary containing all necessary data about the selected module.
-
+ selected_connector: str
+ The name of the connector currently selected.
"""
- self.print(name)
-
- # If the selected module is the stator of a joint modify the string so to select the joint itself.
- # This is needed because from the GUI when you select a joint by clicking, the mesh corresponding to the stator
- # is selected, while the module we want to access is the joint (the stator is not part of the tree, only urdf).
- if name.endswith('_stator'):
- # Take the joint when the mesh of the joint stator is selected
- selected_module_name = name[:-7]
- elif '_con' in name:
- # Take the box as parent when a connector is selected
- selected_module_name = name[:-5]
- # Save the selected port. We take the connector index from the name and increment it b 1 to get the port
- selected_port = int(name[-1]) + 1
- self.print(selected_port)
+ # If the selected mesh is the one of a connector, we need to set the right port
+ if connector_name in module.connectors:
+ # The connector index is retrieved from the list of connectors of the module
+ connector_idx = module.connectors.index(connector_name)
+ # Convert the connector index to the port index
+ current_port = self.connector_to_port_idx(connector_idx, module)
+ # TODO: the current port is not at the moment. This is currently done only in Discovery mode. In Building mode the current port is not used.
+ # Set the name of the selected connector
+ selected_connector = connector_name
else:
- selected_module_name = name
+ # Set the current port of the module
+ self.set_current_port(module, port_idx=port_idx)
+ # Convert the port index to the connector index
+ connector_idx = self.port_to_connector_idx(module.current_port, module)
+ # Set the name of the selected connector. If the index is out of range, it means that the module has only one connector, so we use as name the module name itself.
+ # TODO: add connectors also for modules with only one connector, so to avoid this and have a uniform behavior
+ if 0 <= connector_idx < len(module.connectors):
+ selected_connector = module.connectors[connector_idx]
+ else:
+ selected_connector = module.name
- self.print(selected_module_name)
+ setattr(module, 'connector_idx', connector_idx)
- # Call access_module_by_name to get the object with the requested name and sets it as parent.
- # The method doing the real work is actually access_module_by_name
- selected_module = self.access_module_by_name(selected_module_name)
- self.print(selected_module.type)
- self.print(selected_module.name)
- self.print(selected_module.robot_id)
- self.print(selected_module.active_ports)
- self.print(selected_module.occupied_ports)
-
- # TODO: Replace this with select_ports
- # binary XOR
- free_ports = int(selected_module.active_ports, 2) ^ int(selected_module.occupied_ports, 2)
- self.print("{0:04b}".format(free_ports))
+ self.print('selected_connector :', selected_connector)
- selected_module.selected_port = self.ffs(free_ports)
- self.print('selected_module.selected_port :', selected_module.selected_port)
-
- # # If parent topology is greater than 2 the parent is a switch/hub so we need to find the right port where the module is connected
- # if active_ports >= 3:
- # for port_idx in range(2, len(mastercube.active_ports) - 1)
- # if mastercube.active_ports[-port_idx] == 1:
- # mastercube.selected_port = port_idx
- # break
-
- # if parent_active_ports == 3:
- # self.parent_module.selected_port = 3
- # elif parent_active_ports == 5:
- # self.parent_module.selected_port = 4
- # self.print('self.parent_module.selected_port: ', self.parent_module.selected_port)
-
- # Select the correct port where to add the module to
- if '_con' in name:
- selected_module.selected_port = selected_port
-
- # # Update active and occupied port of the ESC and select the right port
- # self.select_ports(selected_module, name)
+ return selected_connector
+
- # Create the dictionary with the relevant info on the selected module, so that the GUI can dispaly it.
- if selected_module.type == 'cube':
- data = {'lastModule_type': selected_module.type,
- 'lastModule_name': selected_module.name,
- 'flange_size': selected_module.flange_size,
- 'count': self.n_cubes}
+ def select_meshes(self, selected_connector, module):
+ """Select the mesh of the module to be highlighted on the GUI.
+
+ Parameters
+ ----------
+ selected_connector: str
+ String with the name of the connector.
+
+ module: ModuleNode.ModuleNode
+ The object of the module to select the mesh from.
+
+ Returns
+ -------
+ selected_mesh: list
+ The names of the meshes currently selected.
+ """
+
+ if selected_connector in module.connectors:
+ # If the selected mesh is the one of a connector, we select as mesh only the one associated to the connector
+ selected_meshes = [selected_connector]
else:
- data = {'lastModule_type': selected_module.type,
- 'lastModule_name': selected_module.name,
- 'flange_size': selected_module.flange_size,
- 'count': selected_module.i}
+ # Otherwise we select all the meshes of the module
+ selected_meshes = module.mesh_names
- return data
+ self.print('selected_mesh :', selected_meshes)
- def select_ports(self, module, name):
- # In building mode the port is not set by reading the EtherCAT infos, but from the user which selects the
- # connector mesh with a mouse click
- if '_con' in name:
- # "Deactivate" ports which are not occupied. This is necessary if from the GUI the user selects a port
- # but doesn't attach anything to it.
- module.active_ports = module.occupied_ports # int(module.active_ports, 2) & int(module.occupied_ports, 2)
- # Save the selected port
- selected_port = int(name[-1])
- #self.print(selected_port)
- # Set the selected_port as active
- mask = 1 << selected_port - 1
- #self.print(mask)
- #self.print(module.active_ports)
- # binary OR
- module.active_ports = "{0:04b}".format(int(module.active_ports, 2) | mask)
- #self.print(module.active_ports)
- #self.print(module.type)
- #self.print(module.name)
- #self.print(module.robot_id)
- #self.print(module.active_ports)
- #self.print(module.occupied_ports)
- # binary XOR
- free_ports = int(module.active_ports, 2) ^ int(module.occupied_ports, 2)
- #self.print("{0:04b}".format(free_ports))
-
- module.selected_port = self.ffs(free_ports)
- #self.print('module.selected_port :', module.selected_port)
-
- # # If parent topology is greater than 2 the parent is a switch/hub so we need to find the right port where
- # the module is connected if active_ports >= 3: for port_idx in range(2, len(mastercube.active_ports) - 1) if
- # mastercube.active_ports[-port_idx] == 1: mastercube.selected_port = port_idx break
-
- # if parent_active_ports == 3:
- # self.parent_module.selected_port = 3
- # elif parent_active_ports == 5:
- # self.parent_module.selected_port = 4
- # #self.print('self.parent_module.selected_port: ', self.parent_module.selected_port)
-
- # Select the correct port where to add the module to
- # if '_con' in name:
- # module.selected_port = selected_port
+ return selected_meshes
- return 0
@staticmethod
def ffs(x):
"""Returns the index, counting from 0, of the
least significant set bit in `x`.
"""
- return (x & -x).bit_length()
-
+ return (x & -x).bit_length() - 1
+ # TODO: handle reverse also for links
def add_link(self, new_Link, parent_name, transform, reverse):
x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(transform)
- if new_Link.type == 'link':
+ if new_Link.type in ModuleClass.link_modules() - {ModuleType.SIZE_ADAPTER}:
setattr(new_Link, 'name', 'L_' + str(new_Link.i) + '_link_' + str(new_Link.p) + new_Link.tag)
- ET.SubElement(self.root,
- "xacro:add_link",
- type="link",
- name=new_Link.name,
- filename=new_Link.filename)
- elif new_Link.type == 'dagana':
+ self.add_link_element(new_Link.name, new_Link, 'body_1') # , type='link')
+
+ elif new_Link.type is ModuleType.DAGANA:
setattr(new_Link, 'name', 'dagana' + new_Link.tag)
ET.SubElement(self.root,
"xacro:add_dagana",
@@ -3105,6 +2696,10 @@ def add_link(self, new_Link, parent_name, transform, reverse):
roll=roll,
pitch=pitch,
yaw=yaw)
+ # add the xacro:add_dagana element to the list of urdf elements
+ new_Link.xml_tree_elements.append(new_Link.name)
+ new_Link.mesh_names += [new_Link.name + '_top_link', new_Link.name + '_bottom_link']
+
setattr(new_Link, 'dagana_joint_name', new_Link.name + '_claw_joint')
setattr(new_Link, 'dagana_link_name', new_Link.name + '_bottom_link')
setattr(new_Link, 'dagana_tcp_name', new_Link.name + '_tcp')
@@ -3114,13 +2709,14 @@ def add_link(self, new_Link, parent_name, transform, reverse):
type="pen",
name=new_Link.tcp_name,
father=new_Link.dagana_tcp_name,
- filename=new_Link.filename,
x="0.0",
y="0.0",
z="0.0",
roll="0.0",
pitch="0.0",
yaw="0.0")
+ # add the xacro:add_tcp element to the list of urdf elements
+ new_Link.xml_tree_elements.append(new_Link.tcp_name)
# the dagana gets added to the chain. it's needed in the joint map and in the config!
# self.add_to_chain(new_Link)
@@ -3128,13 +2724,26 @@ def add_link(self, new_Link, parent_name, transform, reverse):
return
- elif new_Link.type == 'drill':
+ elif new_Link.type is ModuleType.DRILL:
setattr(new_Link, 'name', 'drill' + new_Link.tag)
+ self.add_link_element(new_Link.name, new_Link, 'body_1') # , type='link')
+
+ setattr(new_Link, 'camera_name', 'drill_camera' + new_Link.tag)
ET.SubElement(self.root,
- "xacro:add_drill",
+ "xacro:add_realsense_d_camera",
type="link",
- name=new_Link.name,
- filename=new_Link.filename)
+ name=new_Link.camera_name,
+ parent_name=new_Link.name)
+ # add the xacro:add_realsense_d_camera to the list of urdf elements
+ new_Link.xml_tree_elements.append(new_Link.camera_name)
+ new_Link.mesh_names.append(new_Link.camera_name)
+
+ #
+ # #
+ #
+ #
+ #
+
x_ee, y_ee, z_ee, roll_ee, pitch_ee, yaw_ee = ModuleNode.get_xyzrpy(tf.transformations.numpy.array(new_Link.kinematics.link.pose))
setattr(new_Link, 'tcp_name', 'ee' + new_Link.tag)
ET.SubElement(self.root,
@@ -3142,22 +2751,22 @@ def add_link(self, new_Link, parent_name, transform, reverse):
type="pen",
name=new_Link.tcp_name,
father=new_Link.name,
- filename=new_Link.filename,
x=x_ee,
y=y_ee,
z=z_ee,
roll=roll_ee,
pitch=pitch_ee,
yaw=yaw_ee)
+ # add the xacro:add_tcp element to the list of urdf elements
+ new_Link.xml_tree_elements.append(new_Link.tcp_name)
+
# the drill gets added to the chain although it's not a joint. it's needed in the joint map and in the config!
# self.add_to_chain(new_Link)
- elif new_Link.type == 'end_effector':
+
+ elif new_Link.type is ModuleType.END_EFFECTOR:
setattr(new_Link, 'name', 'end_effector' + new_Link.tag)
- ET.SubElement(self.root,
- "xacro:add_link",
- type="link",
- name=new_Link.name,
- filename=new_Link.filename)
+ self.add_link_element(new_Link.name, new_Link, 'body_1') # , type='link')
+
x_ee, y_ee, z_ee, roll_ee, pitch_ee, yaw_ee = ModuleNode.get_xyzrpy(tf.transformations.numpy.array(new_Link.kinematics.link.pose))
setattr(new_Link, 'tcp_name', 'ee' + new_Link.tag)
ET.SubElement(self.root,
@@ -3165,54 +2774,66 @@ def add_link(self, new_Link, parent_name, transform, reverse):
type="pen",
name=new_Link.tcp_name,
father=new_Link.name,
- filename=new_Link.filename,
x=x_ee,
y=y_ee,
z=z_ee,
roll=roll_ee,
pitch=pitch_ee,
yaw=yaw_ee)
- elif new_Link.type == 'tool_exchanger':
+ # add the xacro:add_tcp element to the list of urdf elements
+ new_Link.xml_tree_elements.append(new_Link.tcp_name)
+
+ elif new_Link.type is ModuleType.TOOL_EXCHANGER:
setattr(new_Link, 'name', 'tool_exchanger' + new_Link.tag)
- ET.SubElement(self.root,
- "xacro:add_tool_exchanger",
- type="tool_exchanger",
- name=new_Link.name,
- filename=new_Link.filename)
+ self.add_link_element(new_Link.name, new_Link, 'body_1') # , type='tool_exchanger')
+
# the end-effector gets added to the chain although it's not a joint. it's needed in the joint map and in the config!
# self.add_to_chain(new_Link)
# HACK: add pen after tool_exchanger
- setattr(new_Link, 'pen_name', 'pen' + new_Link.tag)
+ setattr(new_Link, 'tcp_name', 'pen' + new_Link.tag)
ET.SubElement(self.root,
- "xacro:add_pen",
+ "xacro:add_tcp",
type="pen",
- name=new_Link.pen_name,
- father=new_Link.name)
- elif new_Link.type == 'gripper':
+ name=new_Link.tcp_name,
+ father=new_Link.name,
+ x="0.0",
+ y="0.0",
+ z="0.222",
+ roll="0.0",
+ pitch="0.0",
+ yaw="0.0")
+ # add the xacro:add_tcp element to the list of urdf elements
+ new_Link.xml_tree_elements.append(new_Link.tcp_name)
+
+ elif new_Link.type is ModuleType.GRIPPER:
setattr(new_Link, 'name', 'gripper' + new_Link.tag)
- ET.SubElement(self.root,
- "xacro:add_gripper_body",
- type="gripper_body",
- name=new_Link.name,
- filename=new_Link.filename)
+ self.add_link_element(new_Link.name, new_Link, 'body_1') # , type='gripper_body')
+
# the end-effector gets added to the chain although it's not a joint. it's needed in the joint map and in the config!
# self.add_to_chain(new_Link)
# add fingers and tcp after gripper
- setattr(new_Link, 'TCP_name', 'TCP_' + new_Link.name)
+ setattr(new_Link, 'tcp_name', 'TCP_' + new_Link.name)
setattr(new_Link, 'joint_name_finger1', new_Link.name + '_finger_joint1')
setattr(new_Link, 'joint_name_finger2', new_Link.name + '_finger_joint2')
+
+ # TODO: add_gripper_fingers still use the xacro to load the yaml file and get the parameters. It should be changed to use the python function for uniformity
ET.SubElement(self.root,
"xacro:add_gripper_fingers",
type="gripper_fingers",
name=new_Link.name,
joint_name_finger1=new_Link.joint_name_finger1,
joint_name_finger2=new_Link.joint_name_finger2,
- TCP_name=new_Link.TCP_name,
+ TCP_name=new_Link.tcp_name,
filename=new_Link.filename)
+ # add the xacro:add_gripper_fingers element to the list of urdf elements
+ new_Link.xml_tree_elements.append(new_Link.name)
+ new_Link.mesh_names += [new_Link.name + '_finger1', new_Link.name + '_finger2']
+
# TO BE FIXED: ok for ros_control. How will it be for xbot2?
self.control_plugin.add_joint(new_Link.joint_name_finger1)
self.control_plugin.add_joint(new_Link.joint_name_finger2)
- elif new_Link.type == 'size_adapter':
+
+ elif new_Link.type is ModuleType.SIZE_ADAPTER:
setattr(new_Link, 'name', 'L_' + str(new_Link.i) + '_size_adapter_' + str(new_Link.p) + new_Link.tag)
ET.SubElement(self.root,
"xacro:add_size_adapter",
@@ -3223,11 +2844,14 @@ def add_link(self, new_Link, parent_name, transform, reverse):
# size_in=new_Link.size_in,
# size_out=new_Link.size_out
)
+ # add the xacro:add_size_adapter element to the list of urdf elements
+ new_Link.xml_tree_elements.append(new_Link.name)
+ new_Link.mesh_names.append(new_Link.name)
setattr(new_Link, 'flange_size', new_Link.size_out)
- self.add_gazebo_element(new_Link.gazebo.body_1, new_Link.name)
-
- if new_Link.type == 'tool_exchanger' or new_Link.type == 'gripper' or new_Link.type == 'end_effector' or new_Link.type == 'drill':
+ self.add_gazebo_element(new_Link, new_Link.gazebo.body_1, new_Link.name)
+
+ if new_Link.type in ModuleClass.end_effector_modules():
fixed_joint_name = new_Link.name + '_fixed_joint'
else:
fixed_joint_name = 'L_' + str(new_Link.i) + '_fixed_joint_' + str(new_Link.p) + new_Link.tag
@@ -3244,61 +2868,25 @@ def add_link(self, new_Link, parent_name, transform, reverse):
roll=roll,
pitch=pitch,
yaw=yaw)
+ # add the xacro:add_gripper_fingers element to the list of urdf elements
+ new_Link.xml_tree_elements.append(fixed_joint_name)
+ setattr(new_Link, 'fixed_joint_name', fixed_joint_name)
return
- # noinspection PyPep8Naming
- def link_after_cube(self, new_Link, past_Cube, offset, reverse):
- """Adds to the URDF tree a link module as a child of a cube module
-
- Parameters
- ----------
- new_Link: ModuleNode.ModuleNode
- ModuleNode object of the link module to add
-
- past_Cube: ModuleNode.ModuleNode
- ModuleNode object of the cube module to which attach the link
-
- offset: float
- Value of the angle between the parent module output frame and the module input frame
- """
- setattr(new_Link, 'p', past_Cube.p + 1)
-
- self.print('past_Cube: ', past_Cube)
- self.print('past_Cube.selected_port: ', past_Cube.selected_port)
-
- if past_Cube.is_structural:
- parent_name = past_Cube.name
- else:
- parent_name = past_Cube.parent.name
-
- interface_transform = self.get_cube_output_transform(past_Cube)
-
- transform = self.get_proximal_transform(interface_transform, offset, reverse)
+ def get_hub_output_transform(self, hub):
- # HACK: to handle 90° offset between PINO and CONCERT flanges
- transform = self.apply_adapter_transform_rotation(transform, past_Cube.flange_size, new_Link.flange_size)
-
- self.add_link(new_Link, parent_name, transform, reverse)
-
- self.collision_elements.append((past_Cube.name, new_Link.name))
-
-
- def get_cube_output_transform(self, past_Cube):
- # index for connector and selecte port are shifted by 1
- connector_idx = (past_Cube.selected_port -1)
- # We take into account the other hubs connected to get the right index. We have 4 connectors per hub, but since ports and index are shifted by 1, each child hub increase the index by 3
- connector_idx += (past_Cube.n_child_hubs) * (4-1)
- # We take into account that one port is used to establish a connection with a second hub, and that should not be taken into account when counting the index
- connector_idx -= past_Cube.n_child_hubs
-
- connector_name = 'Con_' + str(connector_idx) + '_tf'
- interface_transform = getattr(past_Cube, connector_name)
- # if not past_Cube.is_structural:
+ connector_name = 'Con_' + str(hub.connector_idx) + '_tf'
+ try:
+ interface_transform = getattr(hub, connector_name)
+ except AttributeError:
+ self.error_print('AttributeError: ' + connector_name + ' not found in hub ' + hub.name + '. Either something went wrong during the discovery or the resources should be updated.')
+ raise AttributeError
+ # if not hub.is_structural:
# interface_transform = tf.transformations.identity_matrix()
- self.print('past_Cube.selected_port:', past_Cube.selected_port)
+ self.print('hub.current_port:', hub.current_port)
self.print('interface_transform: ', interface_transform)
return interface_transform
@@ -3312,15 +2900,27 @@ def get_link_output_transform(self, past_Link):
return past_Link.Homogeneous_tf
- def get_proximal_transform(self, interface_transform, offset, reverse):
+ def get_joint_name(self, module):
+ if module.type in ModuleClass.joint_modules() | {ModuleType.DRILL}:
+ return module.name
+ elif module.type is ModuleType.DAGANA:
+ return module.dagana_joint_name
+ else:
+ return None
+
+ def get_proximal_transform(self, interface_transform, offsets, reverse):
+ # compute offset
+ T = tf.transformations.translation_matrix((offsets.get('x', 0.0), offsets.get('y', 0.0), offsets.get('z', 0.0)))
+ R = tf.transformations.euler_matrix(offsets.get('roll', 0.0), offsets.get('pitch', 0.0), offsets.get('yaw', 0.0), 'sxyz')
+ offset_transform = tf.transformations.concatenate_matrices(T, R)
+
transform = ModuleNode.get_rototranslation(interface_transform,
- tf.transformations.rotation_matrix(offset,
- self.zaxis))
+ offset_transform)
# If the module is mounted in the opposite direction rotate the final frame by 180 deg., as per convention
if reverse:
transform = ModuleNode.get_rototranslation(transform,
tf.transformations.rotation_matrix(3.14, self.yaxis))
-
+
return transform
# HACK: to handle 90° offset between PINO and CONCERT flanges
@@ -3335,22 +2935,120 @@ def apply_adapter_transform_rotation(self, interface_transform, size1, size2):
return transform
+ def add_origin(self, parent_el, pose):
+ # x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(pose) # TODO: migrate to JSON format and use this
+
+ ET.SubElement(parent_el, "origin",
+ xyz=str(pose.x) + " " + str(pose.y) + " " + str(pose.z),
+ rpy=str(pose.roll) + " " + str(pose.pitch) + " " + str(pose.yaw))
+
+
+ def add_geometry(self, parent_el, geometry):
+ geometry_el = ET.SubElement(parent_el, "geometry")
+ if geometry.type == "mesh":
+ ET.SubElement(geometry_el, "mesh",
+ filename=geometry.parameters.file,
+ scale=' '.join(str(x) for x in geometry.parameters.scale))
+ elif geometry.type == "box":
+ ET.SubElement(geometry_el, "box",
+ size=' '.join(str(x) for x in geometry.parameters.size))
+ elif geometry.type == "cylinder":
+ ET.SubElement(geometry_el, "cylinder",
+ radius=str(geometry.parameters.radius),
+ length=str(geometry.parameters.length))
+ elif geometry.type == "sphere":
+ ET.SubElement(geometry_el, "sphere",
+ radius=str(geometry.parameters.radius))
+
+
+ def add_material(self, parent_el, color):
+ material_el = ET.SubElement(parent_el, "material",
+ name = color.material_name)
+ if hasattr(color, 'rgba'):
+ ET.SubElement(material_el, "color",
+ rgba=' '.join(str(x) for x in color.rgba))
+ if hasattr(color, 'texture'):
+ ET.SubElement(material_el, "texture",
+ filename=color.texture.filename)
+
+
+ def add_inertial(self, parent_el, dynamics, gear_ratio=1.0):
+ inertial_el = ET.SubElement(parent_el, "inertial")
+ # We interpret the mass as a flag to enable/disable the inertial properties
+ if dynamics.mass:
+ ET.SubElement(inertial_el, "origin",
+ xyz=str(dynamics.CoM.x) + " " + str(dynamics.CoM.y) + " " + str(dynamics.CoM.z),
+ rpy=str(0) + " " + str(0) + " " + str(0))
+ ET.SubElement(inertial_el, "mass",
+ value=str(dynamics.mass))
+ ET.SubElement(inertial_el, "inertia",
+ ixx=str(dynamics.inertia_tensor.I_xx),
+ ixy=str(dynamics.inertia_tensor.I_xy),
+ ixz=str(dynamics.inertia_tensor.I_xz),
+ iyy=str(dynamics.inertia_tensor.I_yy),
+ iyz=str(dynamics.inertia_tensor.I_yz),
+ izz=str(gear_ratio*gear_ratio*dynamics.inertia_tensor.I_zz))
+ # If the mass is 0.0 we set the inertial properties to a default value to avoid issues with the dynamics libraries using the URDF
+ else:
+ ET.SubElement(inertial_el, "mass",
+ value=str(1e-04))
+ ET.SubElement(inertial_el, "inertia",
+ ixx=str(1e-09),
+ ixy=str(0),
+ ixz=str(0),
+ iyy=str(1e-09),
+ iyz=str(0),
+ izz=str(1e-09))
+
+
+ def add_link_element(self, link_name, module_obj, body_name, is_geared=False):
+ link_el = ET.SubElement(self.root,
+ 'link',
+ name=link_name)
+ # Add the link to the list of urdf elements of the module
+ module_obj.xml_tree_elements.append(link_name)
+ module_obj.mesh_names.append(link_name)
+
+ visual_bodies = getattr(module_obj.visual, body_name, None)
+ collision_bodies = getattr(module_obj.collision, body_name, None)
+ dynamics_body = getattr(module_obj.dynamics, body_name, None)
+
+ for body in visual_bodies or []:
+ visual_el = ET.SubElement(link_el,
+ 'visual')
+ self.add_origin(visual_el, body.pose)
+ self.add_geometry(visual_el, body)
+ if hasattr(body.parameters, 'color'):
+ self.add_material(visual_el, body.parameters.color)
+
+ for body in collision_bodies or []:
+ collision_el = ET.SubElement(link_el,
+ 'collision')
+ self.add_origin(collision_el, body.pose)
+ self.add_geometry(collision_el, body)
+
+ if dynamics_body:
+ if is_geared:
+ self.add_inertial(link_el, dynamics_body, module_obj.actuator_data.gear_ratio)
+ else:
+ self.add_inertial(link_el, dynamics_body)
+
def add_joint(self, new_Joint, parent_name, transform, reverse):
x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(transform)
- if new_Joint.type == 'joint':
+ if new_Joint.type is ModuleType.JOINT:
setattr(new_Joint, 'name', 'J' + str(new_Joint.i) + new_Joint.tag)
setattr(new_Joint, 'distal_link_name', 'L_' + str(new_Joint.i) + new_Joint.tag)
- elif new_Joint.type == 'wheel':
+ elif new_Joint.type is ModuleType.WHEEL:
setattr(new_Joint, 'name', 'J_wheel' + new_Joint.tag)
setattr(new_Joint, 'distal_link_name', 'wheel' + new_Joint.tag)
setattr(new_Joint, 'stator_name', new_Joint.name + '_stator')
- setattr(new_Joint, 'fixed_joint_stator_name', "fixed_" + new_Joint.name)
+ setattr(new_Joint, 'fixed_joint_name', "fixed_" + new_Joint.name)
ET.SubElement(self.root, "xacro:add_fixed_joint",
type="fixed_joint_stator",
- name=new_Joint.fixed_joint_stator_name,
- father=parent_name, # TODO: check!
+ name=new_Joint.fixed_joint_name,
+ father=parent_name,
child=new_Joint.stator_name,
x=x,
y=y,
@@ -3358,6 +3056,8 @@ def add_joint(self, new_Joint, parent_name, transform, reverse):
roll=roll,
pitch=pitch,
yaw=yaw)
+ # add the xacro:add_fixed_joint element to the list of urdf elements
+ new_Joint.xml_tree_elements.append(new_Joint.fixed_joint_name)
self.collision_elements.append((parent_name, new_Joint.stator_name))
@@ -3377,13 +3077,9 @@ def add_joint(self, new_Joint, parent_name, transform, reverse):
prox_mesh_transform = mesh_transform
x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(prox_mesh_transform)
- ET.SubElement(self.root,
- "xacro:add_proximal",
- type="joint_stator",
- name=new_Joint.stator_name,
- filename=new_Joint.filename)
-
- self.add_gazebo_element(new_Joint.gazebo.body_1, new_Joint.stator_name)
+ # Add proximal link
+ self.add_link_element(new_Joint.stator_name, new_Joint, 'body_1')
+ self.add_gazebo_element(new_Joint, new_Joint.gazebo.body_1, new_Joint.stator_name)
joint_transform = ModuleNode.get_rototranslation(tf.transformations.identity_matrix(),
new_Joint.Proximal_tf)
@@ -3411,10 +3107,12 @@ def add_joint(self, new_Joint, parent_name, transform, reverse):
lower_lim=lower_lim,
effort=effort,
velocity=velocity)
+ # add the xacro:add_joint element to the list of urdf elements
+ new_Joint.xml_tree_elements.append(new_Joint.name)
####
#ET.SubElement(self.xbot2_pid, "xacro:add_xbot2_pid", name=new_Joint.name, profile="small_mot")
- self.control_plugin.add_joint(new_Joint.name,
+ self.control_plugin.add_joint(new_Joint.name,
control_params=new_Joint.xbot_gz if hasattr(new_Joint, 'xbot_gz') else None)
####
@@ -3425,27 +3123,26 @@ def add_joint(self, new_Joint, parent_name, transform, reverse):
x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(dist_mesh_transform)
- ET.SubElement(self.root,
- "xacro:add_distal",
- type="add_distal",
- name=new_Joint.distal_link_name,
- filename=new_Joint.filename)
-
+ # Add distal link
+ self.add_link_element(new_Joint.distal_link_name, new_Joint, 'body_2')
+ self.add_gazebo_element(new_Joint, new_Joint.gazebo.body_2, new_Joint.distal_link_name)
+
+ # Add proximal/distal links pair to the list of collision elements to ignore
self.collision_elements.append((new_Joint.stator_name, new_Joint.distal_link_name))
- self.add_gazebo_element(new_Joint.gazebo.body_2, new_Joint.distal_link_name)
-
if reverse:
new_Joint.Distal_tf = ModuleNode.get_rototranslation(new_Joint.Distal_tf,
tf.transformations.rotation_matrix(3.14, self.yaxis))
# add the fast rotor part to the inertia of the link/rotor part as a new link. NOTE: right now this is
# attached at the rotating part not to the fixed one (change it so to follow Pholus robot approach)
+ # TODO: create a switch between the different methods to consider the fast rotor part
if hasattr(new_Joint.dynamics, 'body_2_fast'):
+ setattr(new_Joint, 'fixed_joint_rotor_fast_name', "fixed_" + new_Joint.distal_link_name + '_rotor_fast')
ET.SubElement(self.root,
"xacro:add_fixed_joint",
type="fixed_joint",
- name="fixed_" + new_Joint.distal_link_name + '_rotor_fast',
+ name=new_Joint.fixed_joint_rotor_fast_name,
father=new_Joint.distal_link_name, # stator_name, #
child=new_Joint.distal_link_name + '_rotor_fast',
x=x,
@@ -3454,53 +3151,243 @@ def add_joint(self, new_Joint, parent_name, transform, reverse):
roll=roll,
pitch=pitch,
yaw=yaw)
- ET.SubElement(self.root,
- "xacro:add_rotor_fast",
- type="add_rotor_fast",
- name=new_Joint.distal_link_name + '_rotor_fast',
- filename=new_Joint.filename,
+ # add the xacro:add_fixed_joint element to the list of urdf elements
+ new_Joint.xml_tree_elements.append(new_Joint.fixed_joint_rotor_fast_name)
+
+ self.add_link_element(new_Joint.distal_link_name + '_rotor_fast', new_Joint, 'body_2_fast', is_geared=True)
+
+
+ def add_hub(self, new_Hub, parent_name, transform, hub_name=None):
+ x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(transform)
+
+ if hub_name:
+ setattr(new_Hub, 'name', hub_name)
+ else:
+ setattr(new_Hub, 'name', 'L_' + str(new_Hub.i) + '_link_' + str(new_Hub.p) + new_Hub.tag)
+
+ self.add_link_element(new_Hub.name, new_Hub, 'body_1')
+ self.add_gazebo_element(new_Hub, new_Hub.gazebo.body_1, new_Hub.name)
+
+ self.add_connectors(new_Hub)
+
+ fixed_joint_name = 'fixed_' + new_Hub.name
+
+ ET.SubElement(self.root,
+ "xacro:add_fixed_joint",
+ name=fixed_joint_name,
+ type="fixed_joint",
+ father=parent_name,
+ child=new_Hub.name,
x=x,
y=y,
z=z,
roll=roll,
pitch=pitch,
yaw=yaw)
+ # add the xacro:add_fixed_joint element to the list of urdf elements
+ new_Hub.xml_tree_elements.append(fixed_joint_name)
+ setattr(new_Hub, 'fixed_joint_name', fixed_joint_name)
+
+ if new_Hub.type is ModuleType.MOBILE_BASE:
+ ET.SubElement(self.root,
+ "xacro:add_mobile_base_sensors",
+ name=new_Hub.name + '_sensors',
+ parent_name=new_Hub.name)
+ # add the xacro:add_mobile_base_sensors element to the list of urdf elements
+ new_Hub.xml_tree_elements.append(new_Hub.name + '_sensors')
+
+ # Add hub and parent links pair to the list of collision elements to ignore
+ self.collision_elements.append((parent_name, new_Hub.name))
+
+
+ # noinspection PyPep8Naming
+ def link_after_hub(self, new_Link, past_Hub, offsets, reverse):
+ """Adds to the URDF tree a link module as a child of a hub module
+
+ Parameters
+ ----------
+ new_Link: ModuleNode.ModuleNode
+ ModuleNode object of the link module to add
+
+ past_Hub: ModuleNode.ModuleNode
+ ModuleNode object of the hub module to which attach the link
+
+ offsets: dict
+ Dictionary containing the various offsets ('x','y','z','roll','pitch','yaw') between the parent module output frame and the module input frame. Es. offsets = {'x': 1.0, 'y': 2.0, 'yaw': 1.57}
+ """
+ setattr(new_Link, 'p', 0) # past_Hub.p + 1)
+ setattr(new_Link, 'i', 0) # past_Hub.i)
+
+ if past_Hub.is_structural:
+ parent_name = past_Hub.name
+ else:
+ parent_name = past_Hub.parent.name
+
+ interface_transform = self.get_hub_output_transform(past_Hub)
+
+ transform = self.get_proximal_transform(interface_transform, offsets, reverse)
+
+ # HACK: to handle 90° offset between PINO and CONCERT flanges
+ transform = self.apply_adapter_transform_rotation(transform, past_Hub.flange_size, new_Link.flange_size)
+
+ self.add_link(new_Link, parent_name, transform, reverse)
+
+ self.collision_elements.append((past_Hub.name, new_Link.name))
# noinspection PyPep8Naming
- def joint_after_cube(self, new_Joint, past_Cube, offset, reverse):
- """Adds to the URDF tree a joint module as a child of a cube module
+ def joint_after_hub(self, new_Joint, past_Hub, offsets, reverse):
+ """Adds to the URDF tree a joint module as a child of a hub module
Parameters
----------
new_Joint: ModuleNode.ModuleNode
ModuleNode object of the joint module to add
- past_Cube: ModuleNode.ModuleNode
- ModuleNode object of the cube module to which the joint will be attached
+ past_Hub: ModuleNode.ModuleNode
+ ModuleNode object of the hub module to which the joint will be attached
- offset: float
- Value of the angle between the parent module output frame and the module input frame
+ offsets: dict
+ Dictionary containing the various offsets ('x','y','z','roll','pitch','yaw') between the parent module output frame and the module input frame. Es. offsets = {'x': 1.0, 'y': 2.0, 'yaw': 1.57}
"""
- if past_Cube.is_structural:
- parent_name = past_Cube.name
+ if past_Hub.is_structural:
+ parent_name = past_Hub.name
else:
- parent_name = past_Cube.parent.name
+ parent_name = past_Hub.parent.name
- interface_transform = self.get_cube_output_transform(past_Cube)
+ interface_transform = self.get_hub_output_transform(past_Hub)
- transform = self.get_proximal_transform(interface_transform, offset, reverse)
+ transform = self.get_proximal_transform(interface_transform, offsets, reverse)
# HACK: to handle 90° offset between PINO and CONCERT flanges
- transform = self.apply_adapter_transform_rotation(transform, past_Cube.flange_size, new_Joint.flange_size)
+ transform = self.apply_adapter_transform_rotation(transform, past_Hub.flange_size, new_Joint.flange_size)
setattr(new_Joint, 'i', 1)
setattr(new_Joint, 'p', 0)
self.add_joint(new_Joint, parent_name, transform, reverse)
+
+ def hub_after_hub(self, new_Hub, past_Hub, offsets, reverse, module_name=None):
+ """Adds to the URDF tree a hub module as a child of a hub module
+
+ Parameters
+ ----------
+ new_Hub: ModuleNode.ModuleNode
+ ModuleNode object of the hub module to add
+
+ past_Hub: ModuleNode.ModuleNode
+ ModuleNode object of the hub module to which the hub will be attached
+
+ offsets: dict
+ Dictionary containing the various offsets ('x','y','z','roll','pitch','yaw') between the parent module output frame and the module input frame. Es. offsets = {'x': 1.0, 'y': 2.0, 'yaw': 1.57}
+ """
+ if past_Hub.is_structural:
+ parent_name = past_Hub.name
+ else:
+ parent_name = past_Hub.parent.name
+
+ setattr(new_Hub, 'i', 0)
+ setattr(new_Hub, 'p', past_Hub.p + 1)
+
+ interface_transform = self.get_hub_output_transform(past_Hub)
+
+ transform = self.get_proximal_transform(interface_transform, offsets, reverse)
+
+ # HACK: to handle 90° offset between PINO and CONCERT flanges
+ transform = self.apply_adapter_transform_rotation(transform, past_Hub.flange_size, new_Hub.flange_size)
+
+ # Set the number of child hubs to 0 (it will be incremented when a child hub is added)
+ setattr(new_Hub, 'n_children_hubs', 0)
+
+ if new_Hub.is_structural:
+ self.add_hub(new_Hub, parent_name, transform, hub_name=module_name)
+ else:
+ # HACK: we set the name of the non-structural hub to be the same as the parent. This is needed to correctly write the SRDF chains!
+ setattr(new_Hub, 'name', parent_name)
+ # HACK: we set the connectors of the non-structural hub to be the same as the parent.
+ new_Hub.connectors = past_Hub.connectors
+ # if the parent is a hub, the n_children_hubs attribute is incremented, in order to keep track of the number of hubs connected to the parent hub and therefore the number of ports occupied. This is needed to select the right connector where to connect the new module
+ self.parent_module.n_children_hubs += 1
+
+ # Add the hub to the list of hubs
+ self.listofhubs.append(new_Hub)
+
+
+ def hub_after_link(self, new_Hub, past_Link, offsets, reverse, module_name=None):
+ """Adds to the URDF tree a hub module as a child of a link module
+
+ Parameters
+ ----------
+ new_Hub: ModuleNode.ModuleNode
+ ModuleNode object of the hub module to add
+
+ past_Link: ModuleNode.ModuleNode
+ ModuleNode object of the link module to which the hub will be attached
+
+ offsets: dict
+ Dictionary containing the various offsets ('x','y','z','roll','pitch','yaw') between the parent module output frame and the module input frame. Es. offsets = {'x': 1.0, 'y': 2.0, 'yaw': 1.57}
+ """
+ setattr(new_Hub, 'i', past_Link.i)
+ setattr(new_Hub, 'p', past_Link.p + 1)
+
+ interface_transform = self.get_link_output_transform(past_Link)
+
+ transform = self.get_proximal_transform(interface_transform, offsets, reverse=reverse) # TODO check reverse
+
+ # HACK: to handle 90° offset between PINO and CONCERT flanges
+ transform = self.apply_adapter_transform_rotation(transform, past_Link.flange_size, new_Hub.flange_size)
+
+ parent_name = past_Link.name
+
+ # Set the number of child hubs to 0 (it will be incremented when a child hub is added)
+ setattr(new_Hub, 'n_children_hubs', 0)
+
+ if new_Hub.is_structural:
+ self.add_hub(new_Hub, parent_name, transform, hub_name=module_name)
+
+ # Add the hub to the list of hubs
+ self.listofhubs.append(new_Hub)
+
+
+ def hub_after_joint(self, new_Hub, past_Joint, offsets, reverse, module_name=None):
+ """Adds to the URDF tree a hub module as a child of a joint module
+
+ Parameters
+ ----------
+ new_Hub: ModuleNode.ModuleNode
+ ModuleNode object of the hub module to add
+
+ past_Joint: ModuleNode.ModuleNode
+ ModuleNode object of the joint module to which the hub will be attached
+
+ offsets: dict
+ Dictionary containing the various offsets ('x','y','z','roll','pitch','yaw') between the parent module output frame and the module input frame. Es. offsets = {'x': 1.0, 'y': 2.0, 'yaw': 1.57}
+ """
+ setattr(new_Hub, 'i', past_Joint.i)
+ setattr(new_Hub, 'p', past_Joint.p + 1)
+
+ interface_transform = self.get_joint_output_transform(past_Joint)
+
+ transform = self.get_proximal_transform(interface_transform, offsets, reverse=reverse) # TODO check reverse
+
+ # HACK: to handle 90° offset between PINO and CONCERT flanges
+ transform = self.apply_adapter_transform_rotation(transform, past_Joint.flange_size, new_Hub.flange_size)
+
+ parent_name = past_Joint.distal_link_name
+
+ # Set the number of child hubs to 0 (it will be incremented when a child hub is added)
+ setattr(new_Hub, 'n_children_hubs', 0)
+
+ if new_Hub.is_structural:
+ self.add_hub(new_Hub, parent_name, transform, hub_name=module_name)
+
+ # Add the hub to the list of hubs
+ self.listofhubs.append(new_Hub)
+
+
# noinspection PyPep8Naming
- def link_after_joint(self, new_Link, past_Joint, offset, reverse):
+ def link_after_joint(self, new_Link, past_Joint, offsets, reverse):
"""Adds to the URDF tree a link module as a child of a joint module
Parameters
@@ -3511,15 +3398,15 @@ def link_after_joint(self, new_Link, past_Joint, offset, reverse):
past_Joint: ModuleNode.ModuleNode
ModuleNode object of the joint module to which attach the link
- offset: float
- Value of the angle between the parent module output frame and the module input frame
+ offsets: dict
+ Dictionary containing the various offsets ('x','y','z','roll','pitch','yaw') between the parent module output frame and the module input frame. Es. offsets = {'x': 1.0, 'y': 2.0, 'yaw': 1.57}
"""
-
+ setattr(new_Link, 'i', past_Joint.i)
setattr(new_Link, 'p', past_Joint.p + 1)
interface_transform = self.get_joint_output_transform(past_Joint)
-
- transform = self.get_proximal_transform(interface_transform, offset, reverse)
+
+ transform = self.get_proximal_transform(interface_transform, offsets, reverse)
# HACK: to handle 90° offset between PINO and CONCERT flanges
transform = self.apply_adapter_transform_rotation(transform, past_Joint.flange_size, new_Link.flange_size)
@@ -3531,7 +3418,7 @@ def link_after_joint(self, new_Link, past_Joint, offset, reverse):
self.collision_elements.append((past_Joint.distal_link_name, new_Link.name))
# noinspection PyPep8Naming
- def joint_after_joint(self, new_Joint, past_Joint, offset, reverse):
+ def joint_after_joint(self, new_Joint, past_Joint, offsets, reverse):
"""Adds to the URDF tree a joint module as a child of a joint module
Parameters
@@ -3542,12 +3429,12 @@ def joint_after_joint(self, new_Joint, past_Joint, offset, reverse):
past_Joint: ModuleNode.ModuleNode
ModuleNode object of the joint module to which the joint will be attached
- offset: float
- Value of the angle between the parent module output frame and the module input frame
+ offsets: dict
+ Dictionary containing the various offsets ('x','y','z','roll','pitch','yaw') between the parent module output frame and the module input frame. Es. offsets = {'x': 1.0, 'y': 2.0, 'yaw': 1.57}
"""
interface_transform = self.get_joint_output_transform(past_Joint)
-
- transform = self.get_proximal_transform(interface_transform, offset, reverse)
+
+ transform = self.get_proximal_transform(interface_transform, offsets, reverse)
# HACK: to handle 90° offset between PINO and CONCERT flanges
transform = self.apply_adapter_transform_rotation(transform, past_Joint.flange_size, new_Joint.flange_size)
@@ -3560,7 +3447,7 @@ def joint_after_joint(self, new_Joint, past_Joint, offset, reverse):
self.add_joint(new_Joint, parent_name, transform, reverse)
# noinspection PyPep8Naming
- def joint_after_link(self, new_Joint, past_Link, offset, reverse):
+ def joint_after_link(self, new_Joint, past_Link, offsets, reverse):
"""Adds to the URDF tree a joint module as a child of a link module
Parameters
@@ -3571,12 +3458,12 @@ def joint_after_link(self, new_Joint, past_Link, offset, reverse):
past_Link: ModuleNode.ModuleNode
ModuleNode object of the link module to which the joint will be attached
- offset: float
- Value of the angle between the parent module output frame and the module input frame
+ offsets: dict
+ Dictionary containing the various offsets ('x','y','z','roll','pitch','yaw') between the parent module output frame and the module input frame. Es. offsets = {'x': 1.0, 'y': 2.0, 'yaw': 1.57}
"""
interface_transform = self.get_link_output_transform(past_Link)
- transform = self.get_proximal_transform(interface_transform, offset, reverse)
+ transform = self.get_proximal_transform(interface_transform, offsets, reverse)
# HACK: to handle 90° offset between PINO and CONCERT flanges
transform = self.apply_adapter_transform_rotation(transform, past_Link.flange_size, new_Joint.flange_size)
@@ -3589,7 +3476,7 @@ def joint_after_link(self, new_Joint, past_Link, offset, reverse):
self.add_joint(new_Joint, parent_name, transform, reverse)
# noinspection PyPep8Naming
- def link_after_link(self, new_Link, past_Link, offset, reverse):
+ def link_after_link(self, new_Link, past_Link, offsets, reverse):
"""Adds to the URDF tree a joint module as a child of a link module
Parameters
@@ -3600,15 +3487,16 @@ def link_after_link(self, new_Link, past_Link, offset, reverse):
past_Link: ModuleNode.ModuleNode
ModuleNode object of the link module to which the joint will be attached
- offset: float
- Value of the angle between the parent module output frame and the module input frame
+ offsets: dict
+ Dictionary containing the various offsets ('x','y','z','roll','pitch','yaw') between the parent module output frame and the module input frame. Es. offsets = {'x': 1.0, 'y': 2.0, 'yaw': 1.57}
"""
+ setattr(new_Link, 'i', past_Link.i)
setattr(new_Link, 'p', past_Link.p + 1)
interface_transform = self.get_link_output_transform(past_Link)
- transform = self.get_proximal_transform(interface_transform, offset, reverse)
+ transform = self.get_proximal_transform(interface_transform, offsets, reverse)
# HACK: to handle 90° offset between PINO and CONCERT flanges
transform = self.apply_adapter_transform_rotation(transform, past_Link.flange_size, new_Link.flange_size)
@@ -3619,6 +3507,7 @@ def link_after_link(self, new_Link, past_Link, offset, reverse):
self.collision_elements.append((past_Link.name, new_Link.name))
+
# TODO: remove hard-coded values
def write_problem_description_multi(self):
basic_probdesc_filename = self.resource_finder.get_filename('cartesio/ModularBot_cartesio_IK_config.yaml',
@@ -3642,7 +3531,8 @@ def write_problem_description_multi(self):
i = 0
tasks = []
stack = [tasks]
- for joints_chain in self.listofchains:
+ active_modules_chains = self.get_actuated_modules_chains()
+ for joints_chain in active_modules_chains:
ee_name = "EE_" + str(i + 1)
tasks.append(ee_name)
probdesc['stack'] = stack
@@ -3694,9 +3584,10 @@ def write_problem_description(self):
self.print(list(probdesc.items())[0])
except yaml.YAMLError as exc:
self.print(exc)
-
+
self.print(probdesc.items())
- joints_chain = self.listofchains[0]
+ active_modules_chains = self.get_actuated_modules_chains()
+ joints_chain = active_modules_chains[0]
tip_link = self.find_chain_tip_link(joints_chain)
probdesc['EE']['distal_link'] = tip_link
@@ -3717,13 +3608,13 @@ def write_problem_description(self):
def write_lowlevel_config(self, use_robot_id=False):
"""Creates the low level config file needed by XBotCore """
lowlevel_config = self.control_plugin.write_lowlevel_config(use_robot_id)
-
+
return lowlevel_config
def write_joint_map(self, use_robot_id=False):
"""Creates the joint map needed by XBotCore """
joint_map = self.control_plugin.write_joint_map(use_robot_id)
-
+
return joint_map
def write_srdf(self, builder_joint_map=None, compute_acm=True):
@@ -3828,36 +3719,37 @@ def write_urdf(self):
return string_urdf_xbot
# Save URDF/SRDF etc. in a directory with the specified robot_name
- def deploy_robot(self, robot_name, deploy_dir=None):
+ def deploy_robot(self, robot_name='modularbot', deploy_dir=None):
script = self.resource_finder.get_filename('deploy.sh', ['data_path'])
- if deploy_dir is None:
- deploy_dir = os.path.expanduser(self.resource_finder.cfg['deploy_dir'])
- deploy_dir = os.path.expandvars(deploy_dir)
+ try:
+ if deploy_dir is None:
+ deploy_dir = self.resource_finder.get_expanded_path(['deploy_dir'])
+ if self.verbose:
+ output = subprocess.check_output([script, robot_name, "--destination-folder", deploy_dir, "-v"])
+ else:
+ output = subprocess.check_output([script, robot_name, "--destination-folder", deploy_dir])
+ except (subprocess.CalledProcessError, FileNotFoundError, RuntimeError) as e:
+ self.error_print(f"An error occurred when executing deploy script: {script}. Aborting.")
+ raise e
- if self.verbose:
- output = subprocess.check_output([script, robot_name, "--destination-folder", deploy_dir, "-v"])
- else:
- output = subprocess.check_output([script, robot_name, "--destination-folder", deploy_dir])
-
self.info_print(str(output, 'utf-8', 'ignore'))
- hubs = self.findall_by_type(types=['cube', 'mobile_base'])
+ hubs = self.findall_by_type(types=ModuleClass.hub_modules())
if hubs is not None:
- for hub_module in hubs:
+ for hub_module in (hub for hub in hubs if hub.is_structural):
self.add_connectors(hub_module)
return robot_name
# Remove connectors when deploying the robot
- def remove_connectors(self):
+ def remove_all_connectors(self):
# update generator expression
- self.update_generator()
+ self.update_generators()
- # Remove the fixed joints that join the connectors to the boxes (by checking if 'con' is in the name of the child)
# Catch KeyError when the node has no child element and continue with the loop.
- for node in self.gen:
+ for node in self.urdf_nodes_generator:
try:
node_type = node.attrib['type']
if node_type == 'connectors':
@@ -3867,40 +3759,42 @@ def remove_connectors(self):
#self.print('missing type', node.attrib['name'])
continue
- # Process the urdf string by calling the process_urdf method. Parse, convert from xacro and write to string
- # Update the urdf file, removing the module
- string = self.process_urdf()
-
- if self.verbose:
- # Render tree
- for pre, _, node in anytree.render.RenderTree(self.base_link):
- self.print("%s%s" % (pre, node.name))
-
- return string
def findall_by_type(self, types=[]):
# Serch the tree by name for the selected module
modulenodes = anytree.search.findall(self.base_link, filter_=lambda node: node.type in types)
return modulenodes
-
+
def add_connectors(self, modulenode):
- max_num_con = 10
+ max_num_con = 20
for i in range(1, max_num_con):
if hasattr(modulenode, 'Con_{}_tf'.format(i)):
con_tf = getattr(modulenode, 'Con_{}_tf'.format(i))
x, y, z, roll, pitch, yaw = ModuleNode.get_xyzrpy(con_tf)
con_name = modulenode.name + '_con{}'.format(i)
- ET.SubElement(self.root,
- "xacro:add_connector",
+ ET.SubElement(self.root,
+ "xacro:add_connector",
name=con_name,
- type='connectors',
- parent_name=modulenode.name,
- x=x,
- y=y,
- z=z,
- roll=roll,
- pitch=pitch,
+ type='connectors',
+ parent_name=modulenode.name,
+ x=x,
+ y=y,
+ z=z,
+ roll=roll,
+ pitch=pitch,
yaw=yaw)
+ modulenode.xml_tree_elements.append(con_name)
+ modulenode.mesh_names.append(con_name)
+ modulenode.connectors.append(con_name)
+
+ def compute_payload(self, samples):
+ self.model_stats.update_model()
+ return self.model_stats.compute_payload(n_samples=samples)
+
+
+ def compute_stats(self, samples):
+ self.model_stats.update_model()
+ return self.model_stats.compute_stats(n_samples=samples)
from contextlib import contextmanager
@@ -3915,7 +3809,7 @@ def suppress_stdout():
"""
old_stdout = sys.stdout
sys.stdout = sys.stderr
- try:
+ try:
yield
finally:
sys.stdout = old_stdout
@@ -3924,7 +3818,7 @@ def suppress_stdout():
def write_file_to_stdout(urdf_writer: UrdfWriter, homing_map, robot_name='modularbot'):
import argparse
- parser = argparse.ArgumentParser(prog='Modular URDF/SRDF generator and deployer',
+ parser = argparse.ArgumentParser(prog='Modular URDF/SRDF generator and deployer',
usage='./script_name.py --output urdf writes URDF to stdout \n./script_name.py --deploy deploy_dir generates a ros package at deploy_dir')
parser.add_argument('--output', '-o', required=False, choices=('urdf', 'srdf'), help='write requested file to stdout and exit')
@@ -3944,8 +3838,8 @@ def write_file_to_stdout(urdf_writer: UrdfWriter, homing_map, robot_name='modula
content = None
with suppress_stdout():
-
- urdf_writer.remove_connectors()
+
+ urdf_writer.remove_all_connectors()
if args.output == 'urdf':
content = urdf_writer.process_urdf(xacro_mappings=xacro_mappings)
@@ -3955,8 +3849,8 @@ def write_file_to_stdout(urdf_writer: UrdfWriter, homing_map, robot_name='modula
urdf_writer.urdf_string = urdf_writer.process_urdf(xacro_mappings=xacro_mappings)
content = urdf_writer.write_srdf(homing_map)
open(f'/tmp/{robot_name}.srdf', 'w').write(content)
-
- if content is not None:
+
+ if content is not None:
print(content)
if args.deploy is not None:
@@ -3966,4 +3860,4 @@ def write_file_to_stdout(urdf_writer: UrdfWriter, homing_map, robot_name='modula
urdf_writer.write_srdf(homing_map)
urdf_writer.write_joint_map()
- urdf_writer.deploy_robot(robot_name, args.deploy)
\ No newline at end of file
+ urdf_writer.deploy_robot(robot_name, args.deploy)
diff --git a/src/modular/enums.py b/src/modular/enums.py
new file mode 100644
index 0000000..44e25b9
--- /dev/null
+++ b/src/modular/enums.py
@@ -0,0 +1,64 @@
+from enum import Enum
+
+class ModuleDescriptionFormat(Enum):
+ YAML = 1 # YAML format used internally in HHCM
+ JSON = 2 # JSON format used for the CONCERT project
+
+class KinematicsConvention(str, Enum):
+ """Kinematic convention used to define the rototranslation between two modules"""
+ DH_EXT = 'DH_ext' # extended Denavit-Hartenberg convention. See https://mediatum.ub.tum.de/doc/1280464/file.pdf
+ URDF = 'urdf' # URDF convention
+ AFFINE = 'affine_tf_matrix' # Affine trasformation matrix convention
+
+class ModuleType(str, Enum):
+ """Type of module"""
+ LINK = 'link'
+ JOINT = 'joint'
+ CUBE = 'cube'
+ WHEEL = 'wheel'
+ TOOL_EXCHANGER = 'tool_exchanger'
+ GRIPPER = 'gripper'
+ MOBILE_BASE = 'mobile_base'
+ BASE_LINK = 'base_link'
+ SIZE_ADAPTER = 'size_adapter'
+ SIMPLE_EE = 'simple_ee'
+ END_EFFECTOR = 'end_effector'
+ DRILL = 'drill'
+ DAGANA = 'dagana'
+ SOCKET = 'socket'
+
+class ModuleClass(set, Enum):
+ """Class of module"""
+ LINKS = {ModuleType.LINK, ModuleType.SIZE_ADAPTER, ModuleType.BASE_LINK, ModuleType.SOCKET}
+ JOINTS = {ModuleType.JOINT, ModuleType.WHEEL}
+ HUBS = {ModuleType.CUBE, ModuleType.MOBILE_BASE}
+ END_EFFECTORS = {ModuleType.GRIPPER, ModuleType.TOOL_EXCHANGER, ModuleType.END_EFFECTOR, ModuleType.DRILL, ModuleType.DAGANA, ModuleType.SIMPLE_EE}
+ PASSIVE_MODULES = {ModuleType.SIZE_ADAPTER, ModuleType.BASE_LINK, ModuleType.END_EFFECTOR, ModuleType.SIMPLE_EE, ModuleType.SOCKET}
+ #
+ @classmethod
+ def link_modules(cls):
+ return cls.LINKS
+ @classmethod
+ def joint_modules(cls):
+ return cls.JOINTS
+ @classmethod
+ def hub_modules(cls):
+ return cls.HUBS
+ @classmethod
+ def end_effector_modules(cls):
+ return cls.END_EFFECTORS
+ @classmethod
+ def all_modules(cls):
+ return cls.LINKS | cls.JOINTS | cls.HUBS | cls.END_EFFECTORS
+ @classmethod
+ def passive_modules(cls):
+ return cls.PASSIVE_MODULES
+ @classmethod
+ def active_modules(cls):
+ return cls.all_modules() - cls.passive_modules()
+ @classmethod
+ def nonactuated_modules(cls):
+ return cls.LINKS | cls.HUBS | cls.PASSIVE_MODULES
+ @classmethod
+ def actuated_modules(cls):
+ return cls.all_modules() - cls.nonactuated_modules()
\ No newline at end of file
diff --git a/src/modular/modular_data/cartesio/ModularBot_cartesio_IK_config.yaml b/src/modular/modular_data/cartesio/ModularBot_cartesio_IK_config.yaml
index 625dcc7..15a9b2c 100644
--- a/src/modular/modular_data/cartesio/ModularBot_cartesio_IK_config.yaml
+++ b/src/modular/modular_data/cartesio/ModularBot_cartesio_IK_config.yaml
@@ -24,7 +24,7 @@ constraints:
# indices: [0,1,2,3,4]
EE:
type: Cartesian
- base_link: L_0_A
+ base_link: base_link
distal_link: ee_A
indices: [0,1,2,3,4]
diff --git a/src/modular/modular_data/cartesio/ModularBot_cartesio_config.yaml b/src/modular/modular_data/cartesio/ModularBot_cartesio_config.yaml
new file mode 100644
index 0000000..244e123
--- /dev/null
+++ b/src/modular/modular_data/cartesio/ModularBot_cartesio_config.yaml
@@ -0,0 +1,13 @@
+
+stack:
+- [EE]
+
+
+EE:
+ type: Interaction
+ base_link: J1_A_stator
+ distal_link: tool_exchanger_A
+ stiffness: [1000.0, 1000.0, 1000.0, 200.0, 200.0, 200.0]
+ damping: [0.7, 0.7, 0.7, 0.7, 0.7, 0.7]
+
+
diff --git a/src/modular/modular_data/configs/ModularBot_xbot2.yaml b/src/modular/modular_data/configs/ModularBot_xbot2.yaml
index 80a483e..62bebd6 100644
--- a/src/modular/modular_data/configs/ModularBot_xbot2.yaml
+++ b/src/modular/modular_data/configs/ModularBot_xbot2.yaml
@@ -39,34 +39,9 @@ xbotcore_plugins:
# different names and possibly different parameters
homing:
thread: rt_main
- type: homing_example
+ type: homing
params:
time: { value: 5, type: double }
-
- cartesio_ik:
- thread: rt_main
- type: cartesio_rt
- params:
- problem_description:
- value: $(rospack find ModularBot)/cartesio/ModularBot_cartesio_IK_config.yaml
- type: file
- solver:
- value: OpenSot
- type: string
- enable_feedback:
- value: false
- type: bool
-
- cartesio_imp:
- thread: rt_main
- type: albero_cartesio_rt
- params:
- problem_description:
- value: $(rospack find ModularBot)/cartesio/ModularBot_cartesio_Interaction_config.yaml
- type: file
- solver: {value: AlberoImpedance, type: string}
- enable_feedback: {value: true, type: bool}
- fc_map: {value: {grav: 0.2, dfl: 0.9}, type: map}
# additional parameters that don't relate to any plugin
xbotcore_param:
diff --git a/src/modular/modular_data/configs/low_level/hal/ModularBot_ec_all.yaml b/src/modular/modular_data/configs/low_level/hal/ModularBot_ec_all.yaml
index 28337bf..b3c822a 100644
--- a/src/modular/modular_data/configs/low_level/hal/ModularBot_ec_all.yaml
+++ b/src/modular/modular_data/configs/low_level/hal/ModularBot_ec_all.yaml
@@ -14,17 +14,21 @@ xbotcore_devices:
config_ec_imp:
value: $PWD/../joint_config/ModularBot_impd4.yaml
type: yamlfile
+
+ config_ec_pos:
+ value: $PWD/../joint_config/ModularBot_pos3b.yaml
+ type: yamlfile
joint_id_map: &jim
value: $PWD/../../joint_map/ModularBot_joint_map.yaml
type: yamlfile
- imu_ec:
- names: []
- thread: rt_main
- params:
- robot_name: *rn
- joint_id_map: *jim
+ # imu_ec:
+ # names: []
+ # thread: rt_main
+ # params:
+ # robot_name: *rn
+ # joint_id_map: *jim
pow_ec:
names: []
diff --git a/src/modular/modular_data/deploy.sh b/src/modular/modular_data/deploy.sh
index 489e75e..746f19e 100755
--- a/src/modular/modular_data/deploy.sh
+++ b/src/modular/modular_data/deploy.sh
@@ -28,12 +28,15 @@ else
export DESTINATION_FOLDER="$HOME/albero_xbot2_ws/robots"
fi
+QUIET='-q'
+
# read arguments
while test $# -gt 0
do
case "$1" in
-[vV] | --verbose) # add verbosity
VERBOSITY='-v'
+ unset QUIET
printf "Verbose mode ${GREEN}ON${NC}\n"
;;
-[dD] | --destination-folder) # add destination folder
@@ -153,8 +156,8 @@ printf "${GREEN}[3/9] Deployed cartesio configs${NC}\n"
# Deploy launch files
mkdir -p ./launch
# - cartesio.launch
-cp $SCRIPT_ROOT/launch/cartesio.launch ./launch/ModularBot_cartesio.launch $VERBOSITY || end_exec
-sed -i -e "s+PACKAGE_NAME+${package_name}+g" ./launch/ModularBot_cartesio.launch
+#cp $SCRIPT_ROOT/launch/cartesio.launch ./launch/ModularBot_cartesio.launch $VERBOSITY || end_exec
+#sed -i -e "s+PACKAGE_NAME+${package_name}+g" ./launch/ModularBot_cartesio.launch
# - ModularBot_ik.launch
cp $SCRIPT_ROOT/launch/ModularBot_ik.launch ./launch/ModularBot_ik.launch $VERBOSITY || end_exec
sed -i -e "s+PACKAGE_NAME+${package_name}+g" ./launch/ModularBot_ik.launch
@@ -183,7 +186,7 @@ printf "${GREEN}[4/9] Deployed ModularBot launch files${NC}\n"
#cp -TRf $SCRIPT_ROOT/moveit_launch ./launch $VERBOSITY || end_exec
#printf "${GREEN}[4.5/9] Deployed moveit configs and launch files${NC}\n"
-# # Deply meshes
+# # Deply meshes
# #NOTE: currently meshes are not deployed and instead taken from the modular_resources or concert_resources packages
# mkdir -p -p ./database/${package_name}_fixed_base
# cp -TRf $SCRIPT_ROOT/../modular_resources/models ./database $VERBOSITY || end_exec
@@ -214,9 +217,10 @@ sed -i -e "s+/tmp/ModularBot+package://${package_name}+g" ./urdf/ModularBot.gaze
# sed -i -e "s+package://modular/src/modular/modular_resources/models/modular/meshes+package://${package_name}/database/modular/meshes+g" ./urdf/ModularBot.gazebo.urdf
printf "${GREEN}[8/9] Deployed URDF${NC}\n"
-# # Deploy gazebo model
-# # - modular_world.sdf
-# cp $SCRIPT_ROOT/database/ModularBot_fixed_base/ModularBot_world.sdf ./database/${package_name}_fixed_base/${package_name}_world.sdf $VERBOSITY || end_exec
+# Deploy gazebo model
+mkdir -p ./gazebo
+# - modular_world.sdf
+cp $SCRIPT_ROOT/database/ModularBot_fixed_base/ModularBot_world.sdf ./gazebo/${package_name}_world.sdf $VERBOSITY || end_exec
# # - manifest.xml
# cp $SCRIPT_ROOT/database/ModularBot_fixed_base/manifest.xml ./database/${package_name}_fixed_base/manifest.xml $VERBOSITY || end_exec
# sed -i -e "s+PACKAGE_NAME+${package_name}+g" ./database/${package_name}_fixed_base/manifest.xml
@@ -228,9 +232,15 @@ printf "${GREEN}[8/9] Deployed URDF${NC}\n"
# # $DESTINATION_FOLDER/${package_name}/urdf/ModularBot.urdf > \
# # $DESTINATION_FOLDER/${package_name}/database/${package_name}_fixed_base/${package_name}.sdf \
# # || end_exec
-# printf "${GREEN}[9/9] Deployed gazebo model${NC}\n"
+printf "${GREEN}[9/9] Deployed gazebo model${NC}\n"
+
+# Deployment completed
+printf "\n${GREEN}[ \xE2\x9C\x94 ] Package ${YELLOW}${package_name}${GREEN} succesfully deployed into ${YELLOW}$DESTINATION_FOLDER${NC}\n"
+
+# create Zip for download
+zip -r $QUIET $VERBOSITY /tmp/${package_name}.zip ./* || end_exec
+printf "${GREEN}[ \xE2\x9C\x94 ] Generated temporary zip file ${YELLOW}/tmp/${package_name}.zip${NC}\n\n"
# All done
popd > /dev/null #hide print
-printf "\n${GREEN}[ \xE2\x9C\x94 ] Package ${YELLOW}${package_name}${GREEN} succesfully deployed into ${YELLOW}$DESTINATION_FOLDER${NC}\n\n"
-unset DESTINATION_FOLDER VERBOSITY SCRIPT_ROOT RED PURPLE GREEN ORANGE YELLOW NC package_name
+unset DESTINATION_FOLDER VERBOSITY QUIET SCRIPT_ROOT RED PURPLE GREEN ORANGE YELLOW NC package_name
diff --git a/src/modular/modular_data/launch/ModularBot_gazebo.launch b/src/modular/modular_data/launch/ModularBot_gazebo.launch
index 1d47a00..ad63a42 100644
--- a/src/modular/modular_data/launch/ModularBot_gazebo.launch
+++ b/src/modular/modular_data/launch/ModularBot_gazebo.launch
@@ -28,7 +28,7 @@
-
+
diff --git a/src/modular/modular_data/urdf/ModularBot.library.urdf.xacro b/src/modular/modular_data/urdf/ModularBot.library.urdf.xacro
index 9ef39a5..2c0f3fc 100644
--- a/src/modular/modular_data/urdf/ModularBot.library.urdf.xacro
+++ b/src/modular/modular_data/urdf/ModularBot.library.urdf.xacro
@@ -52,6 +52,12 @@
+
+
+
+
+
+
@@ -160,6 +166,10 @@
+
+
+
+
@@ -177,6 +187,14 @@
+
+
+
+
+
+
+
+
@@ -185,8 +203,8 @@
-
-
+
+
@@ -219,7 +237,7 @@
-
+
@@ -262,21 +280,9 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
@@ -301,24 +307,6 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
@@ -450,8 +438,7 @@
-
-
+
diff --git a/src/modular/modular_resources b/src/modular/modular_resources
index fe03604..4546e75 160000
--- a/src/modular/modular_resources
+++ b/src/modular/modular_resources
@@ -1 +1 @@
-Subproject commit fe0360418d3057a76f95e9d7add9e38be613a356
+Subproject commit 4546e75f6990b521c2174433785f0f79d3bc378b
diff --git a/src/modular/module_params.yaml b/src/modular/module_params.yaml
index ad9b328..2ac29de 100644
--- a/src/modular/module_params.yaml
+++ b/src/modular/module_params.yaml
@@ -34,12 +34,18 @@
1: # base cube module
2: #size PINO flange
0: master_cube.yaml # rev 0
+ 2: # non-structural base cube module / albero-box
+ 0: # no size associated
+ 0: master_cube_non_structural.yaml # rev 0
3: # mobile base pwrboard
0: # no size associated
0: concert/mobile_platform_concert.json
4: # mobile base ecat hub
0: #no size associated
- 0: concert/mobile_platform_concert.json
+ 0: concert/mobile_platform_concert_non_structural.json
+ 5: # Y module (torso)
+ 4: #size CONCERT arm flange
+ 0: concert/module_Y_torso_concert.json
# ...
3: #end effector module
@@ -66,26 +72,31 @@
0: module_link_elbow_90.yaml # rev 0
3: #passive link 10 cm
2: #size PINO flange
- 0: module_link_straight_10_fraunhofer.yaml
+ 0: module_link_straight_100_fraunhofer.json
4: #size CONCERT arm flange
- 0: concert/module_link_straight_10_concert.json
+ 0: concert/module_link_straight_100_concert.json
4: #passive link 20 cm
2: #size PINO flange
- 0: concert/module_link_straight_20_fraunhofer.json
+ 0: module_link_straight_200_fraunhofer.json
4: #size CONCERT arm flange
- 0: concert/module_link_straight_20_concert.json
+ 0: concert/module_link_straight_200_concert.json
5: #passive link 50 cm
2: #size PINO flange
- 0: concert/module_link_straight_50_fraunhofer.json
+ 0: module_link_straight_500_fraunhofer.json
4: #size CONCERT arm flange
- 0: concert/module_link_straight_50_concert.json
+ 0: concert/module_link_straight_500_concert.json
6: #passive link 40 cm
4: #size CONCERT arm flange
- 0: concert/module_link_straight_40_concert.json
+ 0: concert/module_link_straight_400_concert.json
7: #passive link 30 cm
4: #size CONCERT arm flange
- 0: concert/module_link_straight_30_concert.json
+ 0: concert/module_link_straight_300_concert.json
+
+ 8: #passive link elbow 45°
+ 4: #size CONCERT arm flange
+ 0: concert/module_link_elbow_45_concert.json
+
# ...
5: #wheel module
diff --git a/src/modular/robot_id.yaml b/src/modular/robot_id.yaml
index ec443c7..2a9656c 100644
--- a/src/modular/robot_id.yaml
+++ b/src/modular/robot_id.yaml
@@ -44,3 +44,9 @@
# 54: concert/module_joint_elbow_B_concert.json # A0245
# 55: concert/module_joint_yaw_B_concert.json # A0246
# 56: concert/module_joint_yaw_B_concert.json # A0247
+
+# new manipulator joints
+# 61: concert/module_joint_yaw_A_concert.json # A0276
+62: concert/module_joint_yaw_A_concert.json # A0285
+63: concert/module_joint_elbow_A_concert.json # A0286
+64: concert/module_joint_yaw_A_concert.json # A0287
diff --git a/src/modular/utils.py b/src/modular/utils.py
index a7be592..34dbf66 100644
--- a/src/modular/utils.py
+++ b/src/modular/utils.py
@@ -3,34 +3,56 @@
import os
import subprocess
import io
+import json
+import re
+from numbers import Number
+from collections.abc import Sequence
class ResourceFinder:
+ """Class to find resources in the package"""
def __init__(self, config_file='config_file.yaml'):
self.cfg = self.get_yaml(config_file)
+ self.resources_paths = self.get_all_resources_paths()
+
+ def get_all_resources_paths(self):
+ resources_paths = []
+ # Add internal resources path. By default the path to the resources is at cfg['resources_path']
+ resources_paths.append(['resources_path'])
+ # Add external resources paths. The paths are mapped at cfg['external_resources']
+ for path in self.nested_access(['external_resources']):
+ resources_paths.append(['external_resources', path])
+ return resources_paths
+
def nested_access(self, keylist):
+ """Access a nested dictionary"""
val = dict(self.cfg)
for key in keylist:
val = val[key]
return val
def get_expanded_path(self, relative_path):
- expanded_dir = os.path.expanduser(self.nested_access(relative_path))
- expanded_dir = os.path.expandvars(expanded_dir)
- if '$' in expanded_dir:
- expanded_dir = expanded_dir[1:]
+ # Expand the home directory
+ expanded_path = os.path.expanduser(self.nested_access(relative_path))
+ # Expand environment variables
+ expanded_path = os.path.expandvars(expanded_path)
+ def path_substitution(match):
+ # Get the command to execute: $(cmd)
+ cmd = re.search(r"\$\(([^\)]+)\)", match.group()).group(1)
+ # Return the output of the command
+ cmd_output = subprocess.check_output(cmd.split(), stderr=subprocess.DEVNULL).decode('utf-8').rstrip()
+ return cmd_output
+ try:
+ # The dollar sign is used to execute a command and get the output. What is inside the parenthesis is substituted with the output of the command: $(cmd) -> output of cmd
+ expanded_path = re.sub(r"\$\(([^\)]+)\)", path_substitution, expanded_path)
+ except (subprocess.CalledProcessError, TypeError):
+ msg = 'Executing ' + expanded_path + ' resulted in an error. Path substitution cannot be completed. Are the required environment variables set?'
+ raise RuntimeError(msg)
- if (expanded_dir.startswith('{',) and expanded_dir.endswith('}')) or (expanded_dir.startswith('(',) and expanded_dir.endswith(')')):
- expanded_dir = expanded_dir[1:-1]
-
- try:
- expanded_dir = subprocess.check_output(expanded_dir.split(), stderr=subprocess.DEVNULL).decode('utf-8').rstrip()
- except subprocess.CalledProcessError:
- expanded_dir = ''
-
- return expanded_dir
+ return expanded_path
def find_resource_path(self, resource_name, relative_path=None):
+ """Return a relative filesystem path for specified resource"""
if relative_path:
if 'external_resources' in relative_path:
resource_path = self.find_external_resource_path(resource_name, relative_path)
@@ -41,10 +63,12 @@ def find_resource_path(self, resource_name, relative_path=None):
return resource_path
def find_external_resource_path(self, resource_name, relative_path=None):
+ """Return a filesystem path for specified external resource"""
resource_path = '/'.join((self.get_expanded_path(relative_path), resource_name))
return resource_path
def find_resource_absolute_path(self, resource_name, relative_path=None):
+ """Return an absolute filesystem path for specified resource"""
curr_dir = os.path.dirname(os.path.abspath(__file__))
if relative_path:
if 'external_resources' in relative_path:
@@ -57,12 +81,14 @@ def find_resource_absolute_path(self, resource_name, relative_path=None):
@staticmethod
def is_resource_external(relative_path=None):
+ """Does the relative path means this is an external resource?"""
if relative_path:
if 'external_resources' in relative_path:
return True
return False
def get_string(self, resource_name, relative_path=None):
+ """Return specified resource as a string"""
resource_package = __name__
resource_path = self.find_resource_path(resource_name, relative_path)
if self.is_resource_external(relative_path):
@@ -74,6 +100,7 @@ def get_string(self, resource_name, relative_path=None):
return resource_string
def get_stream(self, resource_name, relative_path=None):
+ """Return a readable file-like object for specified resource"""
resource_package = __name__
resource_path = self.find_resource_path(resource_name, relative_path)
if self.is_resource_external(relative_path):
@@ -83,6 +110,7 @@ def get_stream(self, resource_name, relative_path=None):
return resource_stream
def get_filename(self, resource_name, relative_path=None):
+ """Return a true filesystem path for specified resource"""
resource_package = __name__
resource_path = self.find_resource_path(resource_name, relative_path)
if self.is_resource_external(relative_path):
@@ -90,8 +118,42 @@ def get_filename(self, resource_name, relative_path=None):
else:
resource_filename = pkg_resources.resource_filename(resource_package, resource_path)
return resource_filename
+
+ def get_listdir(self, resource_name, relative_path=None):
+ """List the contents of the named resource directory"""
+ resource_package = __name__
+ resource_path = self.find_resource_path(resource_name, relative_path)
+ if self.resource_exists(resource_name, relative_path):
+ if self.is_resource_external(relative_path):
+ resource_listdir = os.listdir(resource_path)
+ else:
+ resource_listdir = pkg_resources.resource_listdir(resource_package, resource_path)
+ else:
+ resource_listdir = []
+ return resource_listdir
+
+ def resource_exists(self, resource_name, relative_path=None):
+ """Does the named resource exist?"""
+ resource_package = __name__
+ resource_path = self.find_resource_path(resource_name, relative_path)
+ if self.is_resource_external(relative_path):
+ resource_exists = os.path.exists(resource_path) # TODO: check if correct
+ else:
+ resource_exists = pkg_resources.resource_exists(resource_package, resource_path)
+ return resource_exists
+
+ def resource_isdir(self, resource_name, relative_path=None):
+ """Is the named resource a directory?"""
+ resource_package = __name__
+ resource_path = self.find_resource_path(resource_name, relative_path)
+ if self.is_resource_external(relative_path):
+ resource_isdir = os.path.isdir(resource_path)
+ else:
+ resource_isdir = pkg_resources.resource_isdir(resource_package, resource_path)
+ return resource_isdir
def get_yaml(self, resource_name, relative_path=None):
+ """Load the yaml file specified resource and return it as a dict"""
with self.get_stream(resource_name, relative_path) as stream:
try:
yaml_dict = yaml.safe_load(stream)
@@ -99,3 +161,186 @@ def get_yaml(self, resource_name, relative_path=None):
yaml_dict = {}
print(exc)
return yaml_dict
+
+ def get_json(self, resource_name, relative_path=None):
+ """Load the json file specified resource and return it as a dict"""
+ with self.get_stream(resource_name, relative_path) as stream:
+ try:
+ json_dict = json.load(stream)
+ except json.JSONDecodeError as exc:
+ json_dict = {}
+ print(exc)
+ return json_dict
+
+class ModularResourcesManager:
+ def __init__(self, resource_finder):
+ self.resource_finder = resource_finder
+
+ self.default_offset_values = {"x":0.0, "y":0.0, "z": 0.0, "roll":0.0, "pitch":0.0, "yaw":0.0}
+ # dictionary with the keys being the module name and the values being a dictionary specifing
+ # the default values for the keys x, y, z, roll, pitch, yaw
+ self.default_offsets_dict = {}
+ # dictionary with the keys being the module name and the values being a dictionary specifing
+ # the allowed values for the keys x, y, z, roll, pitch, yaw (or a subset of them)
+ self.allowed_offsets_dict = {}
+
+ self.available_modules_dict = {}
+ self.available_modules_headers = []
+ self.init_available_modules()
+
+ self.available_families = []
+ self.init_available_families()
+
+ self.available_addons_dict = {}
+ self.available_addons_headers = []
+ self.init_available_addons()
+
+ def expand_listdir(self, starting_path, res_path):
+ """Expand listdir to include subdirectories recursively"""
+ listdir = self.resource_finder.get_listdir(starting_path, res_path)
+ list_to_remove = []
+ list_to_add = []
+ for el in listdir:
+ if self.resource_finder.resource_isdir(starting_path + '/' + el, res_path):
+ new_listdir = self.expand_listdir(starting_path + '/'+ el, res_path)
+ new_listdir = [el + '/' + new_el for new_el in new_listdir]
+ list_to_remove.append(el)
+ list_to_add += new_listdir
+ for el in list_to_remove:
+ listdir.remove(el)
+ listdir += list_to_add
+ return listdir
+
+ def set_default_offset_values(self, name, offset_dict):
+ """
+ Set the default offset values for the modules and addons
+ The offset_dict is a dictionary with the keys x, y, z, roll, pitch, yaw (or a subset of them) and the values can be numbers or sequences.
+
+ - If the value a number, the user can set any value for the offset (default is the dictionary entry value).
+ - If the value is an empty list, the user can set any value for the offset (default is 0.0).
+ - If the value is a sequence of allowed elements. The first element of the sequence is the default value.
+ This elements can either be numbers or a dictionaries with the keys 'label' and 'value' to show a label in the GUI and its numerical value respectively.
+
+ example (yaml format):
+
+ offsets:
+ x: 0.1
+ y: []
+ yaw:[0, {label: "-π/2", value: -1.5707963267948966}]
+ """
+ if not isinstance(offset_dict, dict):
+ return
+
+ self.default_offsets_dict[name] = self.default_offset_values.copy()
+ self.allowed_offsets_dict[name] = {}
+
+ for key in offset_dict:
+ # If the value is is a number, set the default value
+ if isinstance(offset_dict[key], Number):
+ self.default_offset_values[name][key]=float(offset_dict[key])
+
+ # if the value is a sequence, use the first element to set the default value
+ elif isinstance(offset_dict[key], Sequence) and len(offset_dict[key]) > 0:
+ # if the first element is a number, set it as the default value
+ if isinstance(offset_dict[key][0], Number):
+ self.default_offset_values[name][key]=float(offset_dict[key][0])
+
+ # if the first element is a dictionary, set the default value to the value of the key 'value'
+ elif isinstance(offset_dict[key], dict) and 'value' in offset_dict[key][0]:
+ self.default_offset_values[name][key]=float(offset_dict[key][0]["value"])
+
+ # store the allowed values in a separate dictionary
+ self.allowed_offsets_dict[name][key]=[]
+ for subkey in offset_dict[key]:
+ if isinstance(offset_dict[key][subkey], Number):
+ self.allowed_offsets_dict[name][key].append(float(offset_dict[key][subkey]))
+ if isinstance(subkey, dict) and 'value' in offset_dict[key][subkey]:
+ self.allowed_offsets_dict[name][key].append(float(offset_dict[key][subkey]['value']))
+
+ def get_default_offset_values(self, name):
+ """
+ Get the default offset values for the modules and addons
+ return a dictionary with the keys x, y, z, roll, pitch, yaw and float values.
+ """
+ if name in self.default_offsets_dict:
+ return self.default_offsets_dict[name]
+ return self.default_offset_values
+
+ def get_allowed_offset_values(self, name):
+ """
+ Get the allowed offset values for the modules and addons
+ return a dictionary with the keys x, y, z, roll, pitch, yaw (or a subset of them) and float values.
+ """
+ if name in self.allowed_offsets_dict:
+ return self.allowed_offsets_dict[name]
+ return {}
+
+
+ def init_available_modules(self):
+ for res_path in self.resource_finder.resources_paths:
+ resource_names_list = ['yaml/' + el for el in self.expand_listdir('yaml', res_path)]
+ resource_names_list += ['json/' + el for el in self.expand_listdir('json', res_path)]
+ for res_name in resource_names_list:
+ if res_name.endswith('.json'):
+ res_dict = self.resource_finder.get_json(res_name, res_path)
+ self.available_modules_dict[res_dict['header']['name']] = res_dict
+ self.available_modules_headers.append(res_dict['header'])
+ if 'offset' in res_dict['header']:
+ self.set_default_offset_values(res_dict['header']['name'], res_dict['header']['offset'])
+ elif res_name.endswith('.yaml'):
+ res_dict = self.resource_finder.get_yaml(res_name, res_path)
+ self.available_modules_dict[res_dict['header']['name']] = res_dict
+ self.available_modules_headers.append(res_dict['header'])
+ if 'offset' in res_dict['header']:
+ self.set_default_offset_values(res_dict['header']['name'], res_dict['header']['offset'])
+
+ def init_available_families(self):
+ for res_path in self.resource_finder.resources_paths:
+ if self.resource_finder.resource_exists('families.yaml', res_path):
+ self.available_families += (self.resource_finder.get_yaml('families.yaml', res_path)['families'])
+
+ def init_available_addons(self):
+ for res_path in self.resource_finder.resources_paths:
+ resource_names_list = ['module_addons/yaml/' + el for el in self.expand_listdir('module_addons/yaml', res_path)]
+ resource_names_list += ['module_addons/json/' + el for el in self.expand_listdir('module_addons/json', res_path)]
+ for res_name in resource_names_list:
+ if res_name.endswith('.json'):
+ res_dict = self.resource_finder.get_json(res_name, res_path)
+ self.available_addons_dict[res_dict['header']['name']] = res_dict
+ self.available_addons_headers.append(res_dict['header'])
+ elif res_name.endswith('.yaml'):
+ res_dict = self.resource_finder.get_yaml(res_name, res_path)
+ self.available_addons_dict[res_dict['header']['name']] = res_dict
+ self.available_addons_headers.append(res_dict['header'])
+
+ def get_available_modules(self):
+ return self.available_modules_headers
+
+ def get_available_modules_dict(self):
+ return self.available_modules_dict
+
+ def get_available_module_types(self):
+ module_types = [el['type'] for el in self.available_modules_headers]
+ return list(dict.fromkeys(module_types))
+
+ def get_available_families(self):
+ return self.available_families
+
+ def get_available_family_ids(self):
+ family_ids = [el['id'] for el in self.available_families]
+ return list(dict.fromkeys(family_ids))
+
+ def get_available_family_groups(self):
+ family_groups = [el['group'] for el in self.available_families]
+ return list(dict.fromkeys(family_groups))
+
+ def get_available_addons(self):
+ return self.available_addons_headers
+
+ def get_available_addons_dict(self):
+ return self.available_addons_dict
+
+ def get_available_addon_types(self):
+ addon_types = [el['type'] for el in self.available_addons_headers]
+ return list(dict.fromkeys(addon_types))
+
\ No newline at end of file
diff --git a/src/modular/web/RobotDesignStudio.py b/src/modular/web/RobotDesignStudio.py
index 1fa6c3c..eb0fd25 100755
--- a/src/modular/web/RobotDesignStudio.py
+++ b/src/modular/web/RobotDesignStudio.py
@@ -3,32 +3,84 @@
# see https://pylint.pycqa.org/en/latest/user_guide/messages/message_control.html#block-disables
# pylint: disable=logging-too-many-args
# pylint: disable=protected-access, global-statement, broad-except, unused-variable
-# pylint: disable=line-too-long, missing-function-docstring
+# pylint: disable=line-too-long, missing-function-docstring, missing-module-docstring
+# pylint: disable=wrong-import-position
+# pylint: disable=import-error
# import yaml
import json
import os
import logging
import sys
+import re
+import argparse
+import subprocess
from importlib import reload, util
+from configparser import ConfigParser, ExtendedInterpolation
+from typing import TypedDict
+from datetime import datetime, timedelta
+from uuid import uuid4
+
+import numpy as np
import rospy
-from flask import Flask, Response, render_template, request, jsonify, send_from_directory, abort
-from flask.logging import create_logger
-import zmq
+from flask import Flask, Response, render_template, request, jsonify, send_from_directory, abort, session, send_file
+from apscheduler.schedulers.background import BackgroundScheduler
import werkzeug
from modular.URDF_writer import UrdfWriter
+import modular.ModuleNode as ModuleNode
+from modular.enums import ModuleClass
+
ec_srvs_spec = util.find_spec('ec_srvs')
if ec_srvs_spec is not None:
- from ec_srvs.srv import GetSlaveInfo, GetSlaveInfoRequest, GetSlaveInfoResponse
+ from ec_srvs.srv import GetSlaveInfo
+
+
+# get backend version from git
+try:
+ backend_version = subprocess.check_output(['git', 'describe', '--abbrev=1', '--always', '--dirty'], cwd=os.path.dirname(__file__)).decode().strip()
+except subprocess.CalledProcessError as e:
+ backend_version = 'Unknown'
+
+# get fronetend version from manisfest file
+frontend_version = 'Unknown'
+manifest_path = os.path.join(os.path.dirname(__file__), 'modular_frontend', 'manifest.json')
+with open(manifest_path) as f:
+ manifest_data = json.load(f)
+ if 'version' in manifest_data:
+ frontend_version = manifest_data['version']
+ elif 'version_name' in manifest_data:
+ frontend_version = manifest_data['version_name']
+
+
+parser = argparse.ArgumentParser(prog='robot-design-studio', description='Robot Design Studio server')
+parser.add_argument('-d', '--debug', required=False, action='store_true', default=False)
+parser.add_argument('-v', '--verbose', required=False, action='store_true', default=False)
+parser.add_argument('--use_ros_logger', required=False, action='store_true', default=False)
+parser.add_argument('--slave_desc_mode', required=False, choices=('use_ids', 'use_pos'), default='use_pos')
+
+# parse only known args, see https://stackoverflow.com/a/59067873/22225741
+args = parser.parse_known_args()[0]
+
+# import custom server config (if any)
+base_path, _ = os.path.split(__file__)
+config = ConfigParser(interpolation=ExtendedInterpolation(), allow_no_value=True)
+config.read(os.path.join(base_path, 'web_config.ini'))
+host = config.get('MODULAR_SERVER', 'host', fallback='0.0.0.0')
+port = config.getint('MODULAR_SERVER','port',fallback=5003)
+gui_route = config.get('MODULAR_API','gui_route',fallback='')
+api_base_route = config.get('MODULAR_API','base_route',fallback='')
+secret_key = config.get('MODULAR_API','secret_key',fallback='secret_key')
+enable_sessions = config.getboolean('MODULAR_API','enable_sessions',fallback=False)
+enable_discovery = config.getboolean('MODULAR_API','enable_discovery',fallback=True)
+download_on_deploy = config.getboolean('MODULAR_API','download_on_deploy',fallback=False)
# initialize ros node
rospy.init_node('robot_builder', disable_signals=True) # , log_level=rospy.DEBUG)
# set if ROS logger should be used
-use_ros_logger = False
-if use_ros_logger:
+if args.use_ros_logger:
# roslogger = logging.getLogger('rosout')
roslogger = logging.getLogger(f'rosout.{__name__}')
logger = roslogger
@@ -44,27 +96,28 @@
werkzeug_logger = logging.getLogger('werkzeug')
# set verbosity levels
-verbose=False
-if verbose:
+if args.verbose:
logger.setLevel(logging.DEBUG)
logger.debug('Starting server')
werkzeug_logger.setLevel(logging.INFO)
else:
logger.setLevel(logging.INFO)
werkzeug_logger.setLevel(logging.ERROR)
-
+
+
+template_folder='modular_frontend'
+static_folder = 'modular_frontend' # '/static'
+static_url_path = ''
# determine if it's running on a Pyinstaller bundle
if getattr(sys, 'frozen', False) and hasattr(sys, '_MEIPASS'):
- template_folder = os.path.join(sys._MEIPASS, 'modular/web/templates')
- static_folder = os.path.join(sys._MEIPASS, 'modular/web/static')
+ template_folder = os.path.join(sys._MEIPASS, 'modular/web',template_folder)
+ static_folder = os.path.join(sys._MEIPASS, 'modular/web',static_folder)
is_pyinstaller_bundle=True
else:
- static_folder='static'
- template_folder='templates'
- static_url_path=''
is_pyinstaller_bundle=False
-app = Flask(__name__, static_folder=static_folder, template_folder=template_folder, static_url_path='')
+app = Flask(__name__, static_folder=static_folder, template_folder=template_folder, static_url_path=static_url_path)
+app.secret_key = secret_key
app.logger = logger
if is_pyinstaller_bundle:
@@ -74,335 +127,986 @@
app.logger.debug(static_folder)
else:
app.logger.debug('running in a normal Python process')
-
+
urdfwriter_kwargs_dict={
- 'verbose': verbose,
- 'logger': logger
+ 'verbose': args.verbose,
+ 'logger': logger,
+ 'slave_desc_mode': args.slave_desc_mode
}
-# Instance of UrdfWriter class
-urdf_writer = UrdfWriter(**urdfwriter_kwargs_dict)
-# 2nd instance of UrdfWriter class for the robot got from HW
-urdf_writer_fromHW = UrdfWriter(**urdfwriter_kwargs_dict)
+class SessionData(TypedDict):
+ # Instance of UrdfWriter class
+ urdf_writer: UrdfWriter
+ # 2nd instance of UrdfWriter class for the robot got from HW
+ urdf_writer_fromHW: UrdfWriter
+ # Flags defining which mode are in
+ building_mode_ON: bool
+ # Last time the session was updated
+ last_updated: datetime
-# Flags defining which mode are in
-building_mode_ON = True
+# dictionary of sessions data
+# sessions:dict[str, SessionData] = {}
+sessions = {}
-# load view_urdf.html
-@app.route('/')
-def index():
- return render_template('view_urdf.html')
-
-@app.route('/test')
-def test():
- return render_template('test.html')
-
-
-# call URDF_writer.py to modify the urdf
-@app.route('/changeURDF/', methods=['POST'])
-def changeURDF():
- filename = request.form.get('module_name', 0)
- app.logger.debug(filename)
- parent = request.form.get('parent', 0)
- app.logger.debug(parent)
- offset = float(request.form.get('angle_offset', 0))
- app.logger.debug(offset)
- reverse = True if request.form.get('reverse', 0) == 'true' else False
- app.logger.debug(reverse)
- data = urdf_writer.add_module(filename, offset, reverse)
- data = jsonify(data)
- return data
-
-# call URDF_writer.py to modify the urdf
-@app.route('/addWheel/', methods=['POST'])
-def addWheel():
- wheel_filename = request.form.get('wheel_module_name', 0)
- app.logger.debug(wheel_filename)
- steering_filename = request.form.get('steering_module_name', 0)
- app.logger.debug(steering_filename)
- parent = request.form.get('parent', 0)
- app.logger.debug(parent)
- offset = float(request.form.get('angle_offset', 0))
- app.logger.debug(offset)
- reverse = True if request.form.get('reverse', 0) == 'true' else False
- app.logger.debug(reverse)
- wheel_data, steering_data = urdf_writer.add_wheel_module(wheel_filename, steering_filename, offset, reverse)
- data = jsonify(wheel_data)
- return data
-
-
-@app.route('/writeURDF/', methods=['POST'])
-def writeURDF():
- global building_mode_ON
- #string = request.form.get('string', 0)
- # app.logger.debug(string)
- # app.logger.debug (building_mode_ON)
- app.logger.debug('jointMap')
- json_jm = request.form.get('jointMap', 0)
- app.logger.debug(json_jm)
- builder_jm = json.loads(json_jm)
- building_mode_ON = True if request.form.get('buildingModeON', 0) == 'true' else False
- if building_mode_ON :
- data = urdf_writer.write_urdf()
- srdf = urdf_writer.write_srdf(builder_jm)
- app.logger.debug(srdf)
- joint_map = urdf_writer.write_joint_map()
- lowlevel_config = urdf_writer.write_lowlevel_config()
- # probdesc = urdf_writer.write_problem_description()
- probdesc = urdf_writer.write_problem_description_multi()
- # cartesio_stack = urdf_writer.write_cartesio_stack()
- else:
- data = urdf_writer_fromHW.write_urdf()
- srdf = urdf_writer_fromHW.write_srdf(builder_jm)
- app.logger.debug(srdf)
- joint_map = urdf_writer_fromHW.write_joint_map(use_robot_id=True)
- lowlevel_config = urdf_writer_fromHW.write_lowlevel_config(use_robot_id=True)
- # probdesc = urdf_writer_fromHW.write_problem_description()
- probdesc = urdf_writer_fromHW.write_problem_description_multi()
- # cartesio_stack = urdf_writer_fromHW.write_cartesio_stack()
- # app.logger.debug("\nSRDF\n")
- # app.logger.debug(srdf)
- # app.logger.debug("\nJoint Map\n")
- # app.logger.debug(joint_map)
- # app.logger.debug("\nCartesIO stack\n")
- # app.logger.debug(cartesio_stack)
- # data = jsonify(data)
- return data
-
-
-# call URDF_writer.py to add another master cube
-@app.route('/addMasterCube/', methods=['POST'])
-def addCube():
- filename = request.form.get('module_name', 0)
- app.logger.debug(filename)
- parent = request.form.get('parent', 0)
- app.logger.debug(parent)
- offset = float(request.form.get('angle_offset', 0))
- app.logger.debug(offset)
- data = urdf_writer.add_slave_cube(offset)
- data = jsonify(data)
- return data
-
-# call URDF_writer.py to add another master cube
-@app.route('/addMobilePlatform/', methods=['POST'])
-def addMobilePlatform():
- filename = request.form.get('module_name', 0)
- app.logger.debug(filename)
- parent = request.form.get('parent', 0)
- app.logger.debug(parent)
- offset = float(request.form.get('angle_offset', 0))
- app.logger.debug(offset)
- data = urdf_writer.add_mobile_platform(offset)
- data = jsonify(data)
- return data
-
-
-# call URDF_writer.py to add another socket
-@app.route('/addSocket/', methods=['POST'])
-def addSocket():
- values = json.loads(request.form.get('values'))
- offset = values['offset']
- app.logger.debug(offset)
- angle_offset = values['angle_offset']
- app.logger.debug(angle_offset)
-
- global building_mode_ON
-
- building_mode_ON = True if request.form.get('buildingModeON', 0) == 'true' else False
-
- if building_mode_ON :
- data = urdf_writer.add_socket(float(offset.get('x_offset')), float(offset.get('y_offset')),
- float(offset.get('z_offset')), float(angle_offset))
- else:
- data = urdf_writer_fromHW.move_socket("L_0_B", float(offset.get('x_offset')), float(offset.get('y_offset')),
- float(offset.get('z_offset')), float(angle_offset))
- data = jsonify(data)
- return data
+def cleanup():
+ now = datetime.now()
+ expired_sessions = [sid for sid, session_data in sessions.items() if now - session_data['last_updated'] > timedelta(minutes=30)]
+ for sid in expired_sessions:
+ del sessions[sid]
+scheduler = BackgroundScheduler(daemon=True)
+scheduler.add_job(cleanup, 'interval', minutes=30)
+scheduler.start()
-#TODO: to be included in the next versions
-# call URDF_writer.py to move socket. TODO: remove hard-code of L_0_B socket for AutomationWare demo
-@app.route('/moveSocket/', methods=['POST'])
-def moveSocket():
- values = json.loads(request.form.get('values'))
- app.logger.debug(values)
- offset = values['offset']
- app.logger.debug(offset)
- angle_offset = values['angle_offset']
- app.logger.debug(angle_offset)
- data = urdf_writer_fromHW.move_socket("L_0_B", float(offset.get('x_offset')), float(offset.get('y_offset')),
- float(offset.get('z_offset')), float(angle_offset))
- data = jsonify(data)
- return data
+def get_writer(sid:str) -> UrdfWriter:
+ if sid not in sessions:
+ raise 'No session found, refresh the page to start a new one'
+ if sessions[sid]['building_mode_ON'] :
+ return sessions[sid]['urdf_writer']
+ else:
+ return sessions[sid]['urdf_writer_fromHW']
-# call URDF_writer.py to remove the last module
-@app.route('/removeModule/', methods=['POST'])
-def remove():
- parent = request.form.get('parent', 0)
- data = urdf_writer.remove_module()
- data = jsonify(data)
- return data
+def get_building_mode_ON(sid:str) -> bool:
+ if sid not in sessions:
+ raise 'No session found, refresh the page to start a new one'
+ return sessions[sid]['building_mode_ON']
+# load view_urdf.html
+@app.route(f'{gui_route}/', methods=['GET'])
+def index():
+ if enable_sessions :
+ if'session_id' not in session:
+ session['session_id'] = str(uuid4())
+ sid = session['session_id']
+ else:
+ sid = 'default'
+
+ if sid not in sessions:
+ sessions[sid] = SessionData(
+ urdf_writer= UrdfWriter(**urdfwriter_kwargs_dict),
+ urdf_writer_fromHW= UrdfWriter(**urdfwriter_kwargs_dict),
+ building_mode_ON= True,
+ last_updated= datetime.now(),
+ )
+
+ return render_template('index.html')
+
+# Get workspace mode
+@app.route(f'{api_base_route}/mode', methods=['GET'])
+def getMode():
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+
+ building_mode_ON=get_building_mode_ON(sid)
+ mode = 'Build' if building_mode_ON else 'Discover'
+ return jsonify({'mode': mode}), 200
+
+# Get info about dicovery mode status
+@app.route(f'{api_base_route}/mode/discovery', methods=['GET'])
+def getDiscoveryStatus():
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
-# update "last module" (and so shown buttons) when clicking on it
-@app.route('/updateLastModule/', methods=['POST'])
-def accessModule():
- parent = request.form.get('parent', 0)
- data = urdf_writer.select_module_from_name(parent)
- data = jsonify(data)
- return data
+ try:
+ return Response(
+ status=200,
+ response=json.dumps({ 'available': enable_discovery}),
+ )
+ except Exception as e:
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+# Change mode and reset
+# Request payload:
+# - mode: [string]: "Build" or "Discover"
+@app.route(f'{api_base_route}/mode', methods=['POST'])
+def setMode():
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
-#TODO: to be included in the next versions
-# upload a URDF file and display it
-@app.route('/openFile/', methods=['POST'])
-def openFile():
- file_str = request.form.get('file', 0)
- app.logger.debug(file_str)
- data = urdf_writer.read_file(file_str)
- app.logger.debug('data: %s', data)
- data = jsonify(data)
+ try:
+ # Get the state of the toggle switch. Convert the boolean from Javascript to Python
+ mode = request.get_json()['mode']
+ if mode!='Build' and mode!= 'Discover':
+ raise ValueError(f"Illegal value for mode: exprected 'Build' or 'Discover' but found {mode}.")
+
+ sessions[sid]['building_mode_ON'] = mode == 'Build'
+ app.logger.debug(sessions[sid]['building_mode_ON'])
+
+ # Re-initialize the two object instances
+ sessions[sid]['urdf_writer'].reset(**urdfwriter_kwargs_dict)
+ sessions[sid]['urdf_writer_fromHW'].reset(**urdfwriter_kwargs_dict)
+
+ app.logger.info("Switched workspace mode to '%s'", mode)
+ return Response(status=204)
+
+ except ValueError as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=400,
+ mimetype="application/json"
+ )
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+# Get details about the current version of the app
+@app.route(f'{api_base_route}/info', methods=['GET'])
+def getInfo():
+ """Get details about the current version of the app"""
+ try:
+ return Response(
+ status=200,
+ response=json.dumps({ "backend_version": backend_version,
+ "frontend_version": frontend_version }),
+ )
+ except Exception as e:
+ # validation failed
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+# Get a list of the available modules
+@app.route(f'{api_base_route}/resources/modules', methods=['GET'])
+def resources_modules_get():
+ """Get available modules
+
+ :param families: Optionally the returned list can be filtered by their family of module.
+ :type families: List[str]
+ :param types: Optionally the returned list can filter results by their type of module.
+ :type types: List[str]
+
+ :rtype: List[ModuleBase]
+ """
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+
+ query_params = request.args
+ try:
+ # Get the right writer instance depending on the mode
+ writer = get_writer(sid)
+
+ #get complete list
+ modules = writer.modular_resources_manager.get_available_modules()
+
+ # filter by family (from query params)
+ valid_families = writer.modular_resources_manager.get_available_family_ids()
+
+ filter_families = query_params.getlist('families[]')
+ for t in filter_families:
+ if t not in valid_families:
+ raise ValueError(f"Illegal value for filter families: expected one of {valid_families} but found '{t}'.")
+ if len(filter_families) > 0:
+ modules = [el for el in modules if el['family'] in filter_families]
+
+ # filter by type (from query params)
+ valid_types = writer.modular_resources_manager.get_available_module_types()
+ filter_types = query_params.getlist('types[]')
+ for t in filter_types:
+ if t not in valid_types:
+ raise ValueError(f"Illegal value for filter types: expected one of {valid_types} but found '{t}'.")
+ if len(filter_types) > 0:
+ modules = [el for el in modules if el['type'] in filter_types]
+
+ # return filtered list
+ return Response(
+ response=json.dumps({"modules": modules}),
+ status=200,
+ mimetype="application/json"
+ )
+
+ except ValueError as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=400,
+ mimetype="application/json"
+ )
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+# Get a list of the module types that can currently be added to the model.
+@app.route(f'{api_base_route}/resources/modules/allowed', methods=['GET'])
+def resources_modules_allowed_get():
+ """Get a list of the module types that can currently be added to the model.
+
+ :param ids: Optionally, you can provide one or more IDs of modules. (Currently not supported)
+ :type ids: List[str]
+
+ :rtype: List[str]
+ """
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+
+ query_params = request.args
+ try:
+ # Get the right writer instance depending on the mode
+ writer = get_writer(sid)
+ building_mode_ON=get_building_mode_ON(sid)
+
+ # get complete list of modules
+ # modules = writer.modular_resources_manager.get_available_modules()
+
+ ids = query_params.getlist('ids[]')
+ if len(ids)>1:
+ return Response(
+ response=json.dumps({"message": 'Use of multiple ids at once is currently not supported'}),
+ status=501,
+ mimetype="application/json"
+ )
+ elif len(ids)==1:
+ parent_type = writer.parent_module.type
+
+ if building_mode_ON:
+ valid_types = writer.modular_resources_manager.get_available_module_types()
+ else:
+ # TODO: this list should come from a config file
+ valid_types = ['end_effector', 'interface_adapter']
+
+
+ return Response(
+ response=json.dumps({"type": valid_types}),
+ status=200,
+ mimetype="application/json"
+ )
+
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+# Get a list of the available module addons
+@app.route(f'{api_base_route}/resources/addons', methods=['GET'])
+def resources_addons_get():
+ """Get available addons
+
+ :param families: Optionally the returned list can be filtered by their family of addons.
+ :type families: List[str]
+ :param types: Optionally the returned list can filter results by their type of addons.
+ :type types: List[str]
+
+ :rtype: List[ModuleAddonsBase]
+ """
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+
+ query_params = request.args
+ try:
+ # Get the right writer instance depending on the mode
+ writer = get_writer(sid)
+ building_mode_ON=get_building_mode_ON(sid)
+
+ #get complete list
+ addons = writer.modular_resources_manager.get_available_addons()
+
+ # filter by family (from query params)
+ valid_families = writer.modular_resources_manager.get_available_family_ids()
+
+ filter_families = query_params.getlist('families[]')
+ for t in filter_families:
+ if t not in valid_families:
+ raise ValueError(f"Illegal value for filter families: expected one of {valid_families} but found '{t}'.")
+ if len(filter_families) > 0:
+ addons = [el for el in addons if el['family'] in filter_families]
+
+ # filter by type (from query params)
+ valid_types = writer.modular_resources_manager.get_available_addon_types()
+ filter_types = query_params.getlist('types[]')
+ for t in filter_types:
+ if t not in valid_types:
+ raise ValueError(f"Illegal value for filter types: expected one of {valid_types} but found '{t}'.")
+ if len(filter_types) > 0:
+ addons = [el for el in addons if el['type'] in filter_types]
+
+ # return filtered list
+ return Response(
+ response=json.dumps({"addons": addons}),
+ status=200,
+ mimetype="application/json"
+ )
+
+ except ValueError as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=400,
+ mimetype="application/json"
+ )
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+# Get a list of the available families of modules
+@app.route(f'{api_base_route}/resources/families', methods=['GET'])
+def resources_families_get():
+ """Get a list of families of the available modules
+
+ :param families: Optionally the returned list can be filtered by their family of module.
+ :type families: List[str]
+ :param groups: Optionally the returned list can filter results by their gruop.
+ :type groups: List[str]
+
+ :rtype: List[ModuleFamilies]
+ """
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+
+ query_params = request.args
+ try:
+ # Get the right writer instance depending on the mode
+ writer = get_writer(sid)
+ building_mode_ON=get_building_mode_ON(sid)
+
+ #get complete list
+ families = writer.modular_resources_manager.get_available_families()
+
+ # filter by family (from query params)
+ valid_families = writer.modular_resources_manager.get_available_family_ids()
+ filter_families = query_params.getlist('families')
+ for t in filter_families:
+ if t not in valid_families:
+ raise ValueError(f"Illegal value for filter families: expected one of {valid_families} but found '{t}'.")
+ if len(filter_families) > 0:
+ families = [el for el in families if el['family'] in filter_families]
+
+ # filter by group (from query params)
+ valid_groups = writer.modular_resources_manager.get_available_family_groups()
+ filter_groups = query_params.getlist('groups')
+ for t in filter_groups:
+ if t not in valid_groups:
+ raise ValueError(f"Illegal value for filter groups: expected one of {valid_groups} but found '{t}'.")
+ if len(filter_groups) > 0:
+ families = [el for el in families if el['group'] in filter_groups]
+
+ # return filtered list
+ return Response(
+ response=json.dumps({"families": families}),
+ status=200,
+ mimetype="application/json"
+ )
+
+ except ValueError as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=400,
+ mimetype="application/json"
+ )
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+# Validate the offsets provided by the user
+def validate_offsets(writer, filename, offsets):
+ default_offsets = writer.modular_resources_manager.get_default_offset_values(filename)
+ allowed_offsets = writer.modular_resources_manager.get_allowed_offset_values(filename)
+
+ # Analyze provided offsets and fill empty values
+ for key in ['x', 'y', 'z', 'roll', 'pitch', 'yaw']:
+ # if empty use default value
+ if key not in offsets:
+ offsets[key] = default_offsets[key]
+
+ #otherwise the offset value must comply with the definition (when applicable)
+ elif key in allowed_offsets and offsets[key] not in allowed_offsets[key]:
+ raise ValueError('Offset value for '+key+' is inconsistent with the definition provided in'+filename+'!')
+
+ return offsets
+
+@app.route(f'{api_base_route}/model/urdf/modules', methods=['POST'])
+def addNewModule():
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+
+ req = request.get_json()
+ try:
+ writer = get_writer(sid)
+ building_mode_ON=get_building_mode_ON(sid)
+
+ if building_mode_ON:
+ valid_types = writer.modular_resources_manager.get_available_module_types()
+ else:
+ # TODO: this list should come from a config file
+ valid_types = ['end_effector', 'interface_adapter']
+
+ if req['type'] not in valid_types:
+ return Response(
+ response=json.dumps({"message": f"In {'Build' if building_mode_ON else 'Discovery'} mode, modules of type {req['type']} cannot be added"}),
+ status=409,
+ mimetype="application/json"
+ )
+
+
+ filename = req['name']
+ app.logger.debug(filename)
+
+ parent = req['parent'] if 'parent' in req else None
+ app.logger.debug(parent)
+
+ # We update the selected module to the one selected in the GUI. If no module is selected, we don't update it, since the BE will keep track of the current parent
+ if parent:
+ writer.select_module_from_name(parent, None)
+
+ offsets_requested = req['offsets_requested'] if 'offsets_requested' in req else {} # we use RPY notation
+ offsets_requested = validate_offsets(writer, filename, offsets_requested)
+ app.logger.debug(offsets_requested)
+
+ reverse = True if 'reverse' in req and req['reverse'] == 'true' else False
+ app.logger.debug(reverse)
+
+ addons = req['addons'] if 'addons' in req else []
+ app.logger.debug(addons)
+
+ module_data = writer.add_module(filename, offsets_requested, reverse, addons)
+
+ return Response(response=json.dumps({'id': module_data['selected_connector'],
+ 'meshes': module_data['selected_meshes']}),
+ status=200,
+ mimetype="application/json")
+
+ except ValueError as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=400,
+ mimetype="application/json"
+ )
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+def writeRobotURDF(building_mode_ON, writer, builder_jm):
+ data = writer.write_urdf()
+ srdf = writer.write_srdf(builder_jm)
+ app.logger.debug(srdf)
+ if building_mode_ON :
+ joint_map = writer.write_joint_map()
+ lowlevel_config = writer.write_lowlevel_config()
+ else:
+ joint_map = writer.write_joint_map(use_robot_id=True)
+ lowlevel_config = writer.write_lowlevel_config(use_robot_id=True)
+ # probdesc = writer.write_problem_description()
+ probdesc = writer.write_problem_description_multi()
+ # cartesio_stack = writer.write_cartesio_stack()
+
+ app.logger.debug("\nSRDF\n")
+ app.logger.debug(srdf)
+ app.logger.debug("\nJoint Map\n")
+ app.logger.debug(joint_map)
+ # app.logger.debug("\nCartesIO stack\n")
+ # app.logger.debug(cartesio_stack)
return data
-
# request the urdf generated from the currently stored tree
-@app.route('/requestURDF/', methods=['POST'])
-def requestURDF():
- # building_mode_on_str = request.form.get('mode', 0)
- # app.logger.debug(building_mode_on_str)
- urdf_string = urdf_writer.process_urdf()
- data = {'string': urdf_string}
- app.logger.debug('data: %s', data)
- data = jsonify(data)
- return data
+@app.route(f'{api_base_route}/model/urdf', methods=['GET'])
+def getURDF():
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
-# NOTE: this should not be needed anymore! Setting the static folder in the app constructor should be enough
-# # upload on the server the /static folder
-# @app.route('/')
-# def send_file(path):
-# return send_from_directory(app.static_folder, path)
+ try:
+ # Get the right writer instance depending on the mode
+ writer = get_writer(sid)
+ urdf_string = writer.urdf_string
+
+ # replace path for remote access of STL meshes that will be served with '/meshes/' route
+ frontend_urdf_string = re.sub(r"(package:/)(/[^/]+)(/.*)", fr"\1{api_base_route}/resources/meshes\3", urdf_string)
+
+ return Response(
+ response=frontend_urdf_string,
+ status=200,
+ mimetype='application/xml'
+ )
+ except Exception as e:
+ # validation failed
+ app.logger.error( f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+# upload on the server the /modular_resources folder and the ones under cfg['esternal_resources']
+# This is needed to load the meshes of the modules (withot the need to put them in the /static folder)
+@app.route(f'{api_base_route}/resources/meshes/', methods=['GET'])
+def get_resources_meshes_file(path):
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+ # Get the right writer instance depending on the mode
+ writer = get_writer(sid)
-# upload on the server the /modular_resources folder.
-# This is needed to load the meshes of the modules (withot the need to put them in the /static folder)
-@app.route('/modular_resources/')
-def send_file(path):
resources_paths = []
- resources_paths += [urdf_writer.resource_finder.find_resource_absolute_path('', ['resources_path'])]
-
- # upload also external resources (concert_resources, etc.)
- external_paths_dict = urdf_writer.resource_finder.nested_access(['external_resources'])
- external_paths = [ urdf_writer.resource_finder.get_expanded_path(['external_resources', p]) for p in external_paths_dict]
- resources_paths += external_paths
+ for res_path in writer.resource_finder.resources_paths:
+ resources_paths += [writer.resource_finder.find_resource_absolute_path('', res_path)]
- # if isinstance(resources_path, str):
- # return send_from_directory(resources_path, path)
- # else:
- for res_path in resources_paths:
+ for res_path in resources_paths:
try:
return send_from_directory(res_path, path)
except werkzeug.exceptions.NotFound:
continue
abort(404)
-
-#TODO: to be included in the next versions (requires ROS etc.)
# send a request to the poller thread to get ECat topology and synchronize with hardware
-@app.route('/syncHW/', methods=['POST'])
-def syncHW():
+@app.route(f'{api_base_route}/model/urdf', methods=['PUT'])
+def generateUrdfModelFromHardware():
+ if not enable_discovery:
+ return Response(
+ response=json.dumps({"message": 'Robot discovery is disabled.'}),
+ status=409,
+ mimetype="application/json"
+ )
+
srv_name = '/ec_client/get_slaves_description'
- rospy.wait_for_service(srv_name)
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+ building_mode_ON = get_building_mode_ON(sid)
+
+ if building_mode_ON:
+ return Response(
+ response=json.dumps({"message": 'Cannot generate model from connected hardware in Building mode.'}),
+ status=409,
+ mimetype="application/json"
+ )
try:
- slave_description = rospy.ServiceProxy(srv_name, GetSlaveInfo) # pylint: disable=undefined-variable
+ rospy.wait_for_service(srv_name, 5)
- except rospy.ServiceException as e:
- app.logger.debug("Service call failed: %s",e)
+ try:
+ slave_description = rospy.ServiceProxy(srv_name, GetSlaveInfo) # pylint: disable=undefined-variable
+
+ except rospy.ServiceException as e:
+ app.logger.debug("Service call failed: %s",e)
+ raise e
+
+ reply = slave_description()
+ reply = reply.cmd_info.msg
+ app.logger.debug("Exit")
+
+ writer = get_writer(sid)
+ writer.read_from_json(reply)
+ if writer.verbose:
+ writer.render_tree()
+
+ return Response(status=204)
+
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+def getModulesMap(sid:str):
+ chains=[]
+
+ writer = get_writer(sid)
+ chains = writer.listofchains
+
+ module_map={}
+ for chain in chains:
+ for el in chain:
+ try:
+ module_map[el.name] = ModuleNode.as_dumpable_dict(el.header)
+ except AttributeError as e:
+ continue
+ return module_map
+
+def getJointMap(sid:str):
+ chains=[]
+
+ writer = get_writer(sid)
+ chains = writer.get_actuated_modules_chains()
+
+ joint_map={}
+ for chain in chains:
+ for el in chain:
+ if el.type in ModuleClass.actuated_modules():
+ try:
+ joint_name = writer.get_joint_name(el)
+ joint_data = {
+ 'type': el.actuator_data.type, # revolute, continuos, prismatic, etc.
+ 'value': 0.0, # homing position
+ 'min': el.actuator_data.lower_limit, # lower limit
+ 'max': el.actuator_data.upper_limit # upper limit
+ }
+ joint_map[joint_name] = joint_data
+ except AttributeError as e:
+ continue
+ return joint_map
+
+# get map of modules of robot: module_name -> module_data (header)
+@app.route(f'{api_base_route}/model/urdf/modules/map', methods=['GET'])
+def getModelModules():
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
- reply = slave_description()
- reply = reply.cmd_info.msg
- app.logger.debug("Exit")
+ try:
+ ids = request.args.getlist('ids[]')
+
+ module_map = getModulesMap(sid)
+
+ if len(ids)==0:
+ filtered_module_map = module_map # if no ids are provided, return all modules
+ else:
+ filtered_module_map = {key: module_map[key] for key in ids} # filter modules by ids
+
+ return Response(
+ response=json.dumps(filtered_module_map),
+ status=200,
+ mimetype="application/json"
+ )
+
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+# get map of joints of robot: joint_name -> joint_data (type, value, min, max)
+@app.route(f'{api_base_route}/model/urdf/joints/map', methods=['GET'])
+def getModelJointMap():
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
- data = urdf_writer_fromHW.read_from_json(reply)
- # data = urdf_writer_fromHW.read_from_json_alt(reply)
- if urdf_writer_fromHW.verbose:
- urdf_writer_fromHW.render_tree()
- app.logger.debug('data: %s', data)
- data = jsonify(data)
- return data
+ try:
+ joint_map = getJointMap(sid)
+
+ return Response(
+ response=json.dumps(joint_map),
+ status=200,
+ mimetype="application/json"
+ )
+
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+# Get the id of the module associated to a mesh and the list of all meshes associated to a module
+@app.route(f'{api_base_route}/model/urdf/modules/meshes', methods=['GET'])
+def module_meshes_get():
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+
+ writer = get_writer(sid)
+ mesh_ids = request.args.getlist('ids[]')
+
+ if len(mesh_ids)>1:
+ return Response(
+ response=json.dumps({"message": 'Only one id at a time should be provided'}),
+ status=501,
+ mimetype="application/json"
+ )
+ elif len(mesh_ids)==1:
+ mesh_id = mesh_ids[0]
+ # From the name of the mesh clicked on the GUI select the module associated to it
+ # Also sets the selected_connector to the one associated to the mesh
+ associated_module_data = writer.select_module_from_name(mesh_id, None)
+
+ return Response(response=json.dumps({'id': associated_module_data['selected_connector'],
+ 'meshes': associated_module_data['selected_meshes']}),
+ status=200,
+ mimetype="application/json")
+# call URDF_writer.py to remove the last module
+@app.route(f'{api_base_route}/model/urdf/modules', methods=['DELETE'])
+def removeModules():
+ """Delete one or more modules from the robot model. By default it removes the last element.
+
+ :param ids: Optionally, you can provide one or more IDs of modules to remove. (Currently not supported)
+ :type ids: List[str]
+ """
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+ building_mode_ON=get_building_mode_ON(sid)
+
+ if not building_mode_ON:
+ return Response(
+ response=json.dumps({"message": 'Cannot delete modules in Discovery mode.'}),
+ status=409,
+ mimetype="application/json"
+ )
-# Change mode and reset
-@app.route('/changeMode/', methods=['POST'])
-def changeMode():
- global building_mode_ON
-
- # Get the state of the toggle switch. Convert the boolean from Javascript to Python
- building_mode_ON = True if request.form.get('buildingModeON', 0) == 'true' else False
+ try:
+ # Get the right writer instance depending on the mode
+ writer = get_writer(sid)
+
+ ids = request.args.getlist('ids[]')
+ if len(ids)>1:
+ return Response(
+ response=json.dumps({"message": 'Deletion of multiple ids at once is currently not supported'}),
+ status=501,
+ mimetype="application/json"
+ )
+ elif len(ids)==1:
+ writer.select_module_from_name(ids[0], None)
+ father_module_data = writer.remove_module()
+ return Response(response=json.dumps({'id': father_module_data['selected_connector'],
+ 'meshes': father_module_data['selected_meshes']}),
+ status=200,
+ mimetype="application/json")
+
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+
+# call URDF_writer.py to update the last module
+@app.route(f'{api_base_route}/model/urdf/modules', methods=['PUT'])
+def updateModule():
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
+
+ req = request.get_json()
+
+ # Get the right writer instance depending on the mode
+ writer = get_writer(sid)
- app.logger.debug(building_mode_ON)
+ try:
+ ids = request.args.getlist('ids[]')
+ if len(ids)>1:
+ return Response(
+ response=json.dumps({"message": 'Deletion of multiple ids at once is currently not supported'}),
+ status=501,
+ mimetype="application/json"
+ )
+ elif len(ids)==1:
+ writer.select_module_from_name(ids[0], None)
+
+ app.logger.debug(req['parent'] if 'parent' in req else 'no parent')
+
+ offsets_requested = req['offsets_requested'] if 'offsets_requested' in req else {} # we use RPY notation
+ app.logger.debug(offsets_requested)
+
+ reverse = True if 'reverse' in req and req['reverse'] == 'true' else False
+ app.logger.debug(reverse)
+
+ addons = req['addons'] if 'addons' in req else []
+
+ updated_module_data = writer.update_module(offsets=offsets_requested, reverse=reverse, addons=addons)
+
+ return Response(response=json.dumps({'id': updated_module_data['selected_connector'],
+ 'meshes': updated_module_data['selected_meshes']}),
+ status=200,
+ mimetype="application/json")
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
- # Re-initialize the two object instances
- urdf_writer.__init__(**urdfwriter_kwargs_dict)
- urdf_writer_fromHW.__init__(**urdfwriter_kwargs_dict)
+# deploy the package of the built robot
+@app.route(f'{api_base_route}/model/urdf', methods=['POST'])
+def deployROSModel():
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
- #data = urdf_writer_fromHW.read_file(file_str)
- data = {'building mode': building_mode_ON}
+ try:
+ req = request.get_json()
+ name = req['name']
+ builder_jm = req['jointMap']
- data = jsonify(data)
- return data
+ # Get the right writer instance depending on the mode
+ writer = get_writer(sid)
+ building_mode_ON=get_building_mode_ON(sid)
+ writer.remove_all_connectors() # taken from removeConnectors(), to be removed and itergrated inside .deploy_robot()
-# deploy the package of the built robot
-@app.route('/deployRobot/', methods=['POST'])
-def deployRobot():
- global building_mode_ON
+ writeRobotURDF(building_mode_ON, writer, builder_jm)
- building_mode_ON = True if request.form.get('buildingModeON', 0) == 'true' else False
-
- if building_mode_ON :
- name = request.form.get('name', 'ModularBot')
app.logger.debug(name)
- data = urdf_writer.deploy_robot(name)
- else:
- data = urdf_writer_fromHW.deploy_robot('modularbot')
- #time.sleep(10)
- return data
+ writer.deploy_robot(name)
+
+ if download_on_deploy:
+ return send_file(f'/tmp/{name}.zip', as_attachment=True)
+ else:
+ return Response(status=204)
+
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+# get current model stats
+@app.route(f'{api_base_route}/model/stats', methods=['GET'])
+def getModelStats():
+ """Returns a set of statistics for the curent robot model.
+ """
+ sid = session.get('session_id') if enable_sessions else 'default'
+ if sid not in sessions:
+ return 'No session found, refresh the page to start a new one', 404
+ sessions[sid]['last_updated'] = datetime.now()
+ session.modified = True
-
-@app.route('/removeConnectors/', methods=['POST'])
-def removeConnectors():
- global building_mode_ON
-
- building_mode_ON = True if request.form.get('buildingModeON', 0) == 'true' else False
-
- if building_mode_ON :
- data = urdf_writer.remove_connectors()
- else:
- data = urdf_writer_fromHW.remove_connectors()
- return data
-
-
-def byteify(input):
- if isinstance(input, dict):
+ try:
+ # Get the right writer instance depending on the mode
+ writer = get_writer(sid)
+
+ stats = writer.compute_stats(samples=1000)
+
+ response = dict()
+ if stats['modules']:
+ response["modules"]= { "label": 'Modules', "value": str(stats['modules']) }
+ if stats['payload'] and np.isfinite(stats['payload']):
+ response["payload"]= { "label": 'Payload', "value":"{:.2f}".format(stats['payload']), "unit": 'Kg' }
+ if stats['max_reach'] and np.isfinite(stats['max_reach']):
+ response["max_reach"]= { "label": 'Reach', "value": "{:.2f}".format(stats['max_reach']), "unit": 'm' }
+ if stats['joint_modules']:
+ response["joint_modules"]= { "label": 'Joints', "value": str(stats['modules']) }
+
+ return Response(
+ response=json.dumps(response),
+ status=200,
+ mimetype="application/json"
+ )
+ except RuntimeError as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'Error in computing stats -> {type(e).__name__}: {e}'}),
+ status=400,
+ mimetype="application/json"
+ )
+ except Exception as e:
+ # validation failed
+ app.logger.error(f'{type(e).__name__}: {e}')
+ return Response(
+ response=json.dumps({"message": f'{type(e).__name__}: {e}'}),
+ status=500,
+ mimetype="application/json"
+ )
+
+def byteify(input_raw):
+ if isinstance(input_raw, dict):
return {byteify(key): byteify(value)
- for key, value in input.items()}
- elif isinstance(input, list):
- return [byteify(element) for element in input]
- elif isinstance(input, str):
- return input.encode('utf-8')
+ for key, value in input_raw.items()}
+ elif isinstance(input_raw, list):
+ return [byteify(element) for element in input_raw]
+ elif isinstance(input_raw, str):
+ return input_raw.encode('utf-8')
else:
- return input
+ return input_raw
def main():
- # Start Flask web-server
- app.run(host='0.0.0.0', port=5000, debug=False, threaded=True)
- # app.run(debug=False, threaded=True)
+ app.run(host=host, port=port, debug=args.debug, threaded=True)
if __name__ == '__main__':
diff --git a/src/modular/web/docs/index.html b/src/modular/web/docs/index.html
index 8341e4c..dbfbc25 100644
--- a/src/modular/web/docs/index.html
+++ b/src/modular/web/docs/index.html
@@ -3,7 +3,7 @@
- linfa_backend_data docs
+ modular docs
diff --git a/src/modular/web/docs/modular_swagger.yaml b/src/modular/web/docs/modular_swagger.yaml
index 645a197..8527094 100644
--- a/src/modular/web/docs/modular_swagger.yaml
+++ b/src/modular/web/docs/modular_swagger.yaml
@@ -1,173 +1,114 @@
openapi: 3.0.0
info:
title: Modular
- version: 0.0.3
+ version: 1.0.0-alpha.7.0
# description: Alberobitcs API for RobotBuilder
contact:
- email: edoardo.romiti@iit.it
- name: Edoardo Romiti
+ email: alberobotics@iit.it
+ name: Alberobotics Team
servers:
- - url: http://0.0.0.0:5000
+ # - url: http://localhost:5003
+ - url: /linfa/api/v1/modular
externalDocs:
description: Github repository
url: https://github.com/ADVRHumanoids/modular
-components:
- schemas:
- FeedbackResponse:
- type: object
- properties:
- result: # the updated URDF to render!
- type: string
- lastModule_type:
- type: string
- lastModule_name:
- type: string
- size:
- type: number
- format: integer
- count:
- type: number
- format: integer
- example:
- result: "the updated URDF to render!"
- lastModule_type: "joint"
- lastModule_name: "L3_A"
- size: 3
- count: 1
-
- AddModuleRequest:
- type: object
- properties:
- module_name: # The name of the type of module to add
- type: string
- parent: # The parent name
- type: string
- angle_offset: # The angle offset w.r.t the parent
- type: number
- format: float
- reverse:
- type: boolean
- example:
- module_name: "module_joint_yaw_ORANGE"
- parent: "L3_A"
- angle_offset: 0.5
- reverse: false
-
paths:
- /changeURDF:
- post:
+ /mode:
+ get:
tags:
- - modular
- summary: makes an ajax request to the server to modify the URDF by adding the requested module
- requestBody:
- description: JSON containing the name of the module to add, the parent module and their respective orientation.
- required: true
- content:
- application/json:
- schema:
- $ref: "#/components/schemas/AddModuleRequest"
+ - Workspace
+ summary: get workspace mode
responses:
- "200":
+ 200:
description: OK
content:
application/json:
schema:
- $ref: "#/components/schemas/FeedbackResponse"
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/WorkspaceModeGetResponse"
+ 500:
+ description: "INTERNAL SERVER ERROR"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
- /addMasterCube: # TODO: This should be merged under changeURDF
post:
tags:
- - modular
- summary: makes an ajax request to the server to modify the URDF by adding the requested cube
+ - Workspace
+ summary: set workspace mode and reset the robot instance
requestBody:
- description: JSON containing the name of the module to add, the parent module and their respective orientation.
required: true
content:
application/json:
schema:
- $ref: "#/components/schemas/AddModuleRequest"
+ type: object
+ required:
+ - mode
+ properties:
+ mode:
+ type: string
+ example: Discovery
responses:
- "200":
- description: OK
+ 204:
+ description: "NO CONTENT: The server successfully processed the request, and is not returning any content."
+ 400:
+ description: "BAD REQUEST"
content:
application/json:
schema:
- $ref: "#/components/schemas/FeedbackResponse"
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Missing required parameter 'mode'."
+ 500:
+ description: "INTERNAL SERVER ERROR"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
- /addSocket:
- post:
+ /model/urdf:
+ get:
tags:
- - modular
- summary: add a Socket to the robot model (meaning adding a kinematic chain to the robot in practice)
- requestBody:
- description: JSON containing position and orientation of the socket.
- required: true
- content:
- application/json:
- schema:
- type: object
- properties:
- values:
- type: object
- properties:
- offset:
- type: array
- items:
- type: number
- format: float
- example: [0.1, 0.2, 0.3]
- angle_offset:
- type: number
- format: float
- buildingModeON:
- type: boolean
- example:
- values:
- offset: [0.1, 0.2, 0.3]
- angle_offset: 0.0
- buildingModeON: true
+ - Robot Model
+ summary: get the urdf generated from the currently stored tree
+ parameters:
+ - $ref: "#/components/parameters/modelIdFromQuery"
responses:
- "200":
- description: OK
+ 200:
+ description: "OK: the URDF to render!"
+ content:
+ application/xml:
+ schema:
+ type: object
+ 500:
+ description: "INTERNAL SERVER ERROR"
content:
application/json:
schema:
- $ref: "#/components/schemas/FeedbackResponse"
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/ErrorMessage"
- /writeURDF:
- post: # PUT?
+ post:
tags:
- - modular
- summary: makes an ajax request to the server to write the URDF in the filesystem (and SRDF, configs, etc.)
+ - Robot Model
+ summary: deploy the URDF of the robot in a ROS pakage
requestBody:
- description: JSON containing a boolean to determine whether or not building mode is activated and a joint map containing the value for the homing of the joints
+ description: JSON containing a mapping of the joint names and their homing value and the name of the ROS package to save
required: true
content:
application/json:
schema:
type: object
+ required:
+ - jointMap
properties:
+ name:
+ type: string
+ description: The name of the ROS package (default:'ModularBot')
+ example: "ModularBot5"
jointMap:
type: object
+ description: Mapping of the joint names and their homing value
additionalProperties:
type: object
properties:
@@ -179,234 +120,738 @@ paths:
example:
J1_A: 0.1
J2_A: 0.2
- buildingModeON:
+ path:
+ description: deployment path
+ type: string
+ overwrite:
+ description: Overwrite ROS package if already existing
type: boolean
responses:
- "200":
- description: OK
+ 204:
+ description: "NO CONTENT: The server successfully processed the request, and is not returning any content."
+ 400:
+ description: "BAD REQUEST"
content:
- text/plain:
+ application/json:
schema:
- type: string
- example: "the URDF string. for logging purposes"
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Missing required parameter jointMap."
+ 500:
+ description: "INTERNAL SERVER ERROR"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: string
- /removeModule:
- post: # DELETE?
+ put:
tags:
- - modular
- summary: makes an ajax request to the server to remove the **last selected module** and its **children**
- # requestBody:
- # description: ....
- # required: false
- # content:
- # application/json:
- # schema: ...
+ - Robot Model
+ summary: Generate the URDF of the robot from the connected hardware modules
responses:
- "200":
- description: OK
+ 200:
+ description: "OK: the gost URDF to render! (if in Build mode)"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/UrdfGetResponse"
+ application/xml:
+ schema:
+ type: string
+ 204:
+ description: "NO CONTENT: The server successfully processed the request, and is not returning any content (if in Discovery mode)."
+ # 409:
+ # description: "CONFLICT: The request could not be processed because of conflict in the current state of the resource"
+ # content:
+ # application/json:
+ # schema:
+ # $ref: '#/components/schemas/ErrorMessage'
+ # example:
+ # message: "Cannot generate robot model in Build mode."
+ 500:
+ description: "INTERNAL SERVER ERROR"
content:
application/json:
schema:
- $ref: "#/components/schemas/FeedbackResponse"
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/ErrorMessage"
- /updateLastModule:
- post: # PUT?
+ /model/urdf/modules:
+ get:
tags:
- - modular
- summary: makes an ajax request to the server to update the "last selected module" (and so shown buttons) when clicking on it from the front-end
- requestBody:
- description: JSON containing the name of the current parent module (last selected one)
- required: true
- content:
- application/json:
- schema:
- type: object
- properties:
- parent:
- type: string
- example: "L2_A"
+ - Robot Model
+ summary: Get a list of the modules in the robot model
+ parameters:
+ - $ref: "#/components/parameters/familiesFromQuery"
+ - $ref: "#/components/parameters/moduleTypesFromQuery"
responses:
- "200":
- description: OK
+ 200:
+ description: "OK"
+ content:
+ application/json:
+ schema:
+ type: array
+ items:
+ $ref: "#/components/schemas/Module"
+ example:
+ modules:
+ - id: "J1_A"
+ family: "alberoboticsGenA"
+ type: "ActiveJoint"
+ product: "module_joint_yaw_ORANGE"
+ label: "Straight Joint"
+ offset: {}
+ - id: "J2_A"
+ family: "alberoboticsGenA"
+ type: "ActiveJoint"
+ product: "module_joint_double_elbow_ORANGE"
+ label: "Elbow Joint"
+ offset: {}
+ - id: "J3_A"
+ family: "alberoboticsGenA"
+ type: "EndEffector"
+ product: "module_tool_exchanger_heavy"
+ label: "Tool Exchanger"
+ offset: {}
+ - id: "J4_A"
+ family: "alberoboticsGenB"
+ type: "EndEffector"
+ product: "module_gripper"
+ label: "Gripper"
+ offset:
+ x: 1
+ y: 2
+ 400:
+ description: "BAD REQUEST"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Requested invalid 'types'"
+ 404:
+ description: "NOT FOUND"
content:
application/json:
schema:
- $ref: "#/components/schemas/FeedbackResponse"
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Family 'foo' not found."
+ 500:
+ description: "INTERNAL SERVER ERROR"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ 501:
+ description: "NOT IMPLEMENTED: This implies future availability (e.g., a new feature of the API)."
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Filtering by family is currently not supported"
- /openFile:
post:
tags:
- - modular
- summary: makes an ajax request to the server to upload a URDF file and display it
+ - Robot Model
+ summary: Add a new module to the robot model
requestBody:
- description: JSON containing the string of the read URDF
required: true
content:
application/json:
schema:
- type: object
- properties:
- file:
- type: string
+ $ref: "#/components/schemas/ModuleCreateDTO"
+ example:
+ family: "alberoboticsGenA"
+ type: "ActiveJoint"
+ product: "module_joint_yaw_ORANGE"
+ offset:
+ z: 0.05
+ yaw: -1.571
+ reverse: false
+ parent: "J1_A"
+
responses:
- "200":
- description: OK
+ 204:
+ description: "NO CONTENT: The server successfully processed the request, and is not returning any content."
+ 400:
+ description: "BAD REQUEST"
content:
application/json:
schema:
- type: object
- properties:
- parent:
- type: string
- example: "the updated URDF to render!"
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Missing required parameter 'product'."
+ 403:
+ description: FORBIDDEN
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Cannot place module with type 'PassiveLink' after a module of type 'EndEffector'"
+ 404:
+ description: "NOT FOUND"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "No module found with varint 'foo'."
+ 409:
+ description: "CONFLICT: The request could not be processed because of conflict in the current state of the resource"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Cannot add modules in Discovery mode."
+ 500:
+ description: "INTERNAL SERVER ERROR"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ 501:
+ description: "NOT IMPLEMENTED: This implies future availability (e.g., a new feature of the API)."
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Offset along x,y,z axis is currently not supported"
- /requestURDF:
- post: # GET?
+ put: # or patch?
tags:
- - modular
- summary: makes an ajax request to get the urdf generated from the currently stored tree
+ - Robot Model
+ summary: Edit a module's parameters
requestBody:
- description: JSON specifying if we are in building mode (true) or not (false)
required: true
content:
application/json:
schema:
- type: object
- properties:
- mode:
- type: boolean # True for building mode ON
+ $ref: "#/components/schemas/Module"
+
responses:
- "200":
- description: OK
+ 204:
+ description: "NO CONTENT: The server successfully processed the request, and is not returning any content."
+ 400:
+ description: "BAD REQUEST"
content:
application/json:
schema:
- type: object
- properties:
- parent:
- type: string # the updated URDF to render!
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Missing required parameter 'product'."
+ 403:
+ description: "FORBIDDEN"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Cannot place module with type 'PassiveLink' after a module of type 'EndEffector'"
+ 404:
+ description: "NOT FOUND"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "No module found with id 'foo'."
+ 409:
+ description: "CONFLICT: The request could not be processed because of conflict in the current state of the resource"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Cannot change module type in Discovery mode."
+ 500:
+ description: "INTERNAL SERVER ERROR"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ 501:
+ description: "NOT IMPLEMENTED: This implies future availability (e.g., a new feature of the API)."
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Offset along x,y,z axis is currently not supported"
- /changeMode:
- post: # GET?
+ delete:
tags:
- - modular
- summary: makes an ajax request to change mode (Building vs Discovery) and reset the robot instance
- requestBody:
- description: JSON specifying if switching in building (true) or dicovery mode (false)
- required: true
- content:
- application/json:
- schema:
- type: object
- properties:
- buildingModeON:
- type: boolean # True for building mode ON
+ - Robot Model
+ summary: Delete a module from the robot model
+ parameters:
+ - in: query
+ name: ids
+ description: Optionally, you can provide one or more IDs of modules to remove. By default it removes the last element.
+ schema:
+ type: array
+ items:
+ type: string
+ style: form
+ explode: false
+ examples:
+ oneId:
+ summary: Example of a single ID
+ description: "equals to =`?ids=J1_A`"
+ value: ["J5_A"] # ?ids=5
+ multipleIds:
+ summary: Example of multiple IDs
+ description: "equals to =`?ids=J1_A,J5_B,J0_D`"
+ value: ["J1_A", "J5_B", "J0_D"] # ?ids=J1_A,J5_B,J0_D
responses:
- "200":
- description: OK
+ 204:
+ description: "NO CONTENT: The server successfully processed the request, and is not returning any content."
+ 304:
+ description: "NOT MODIFIED"
content:
application/json:
schema:
- type: object
- properties:
- buildingModeON:
- type: boolean # True for building mode ON
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "The current model has no modules"
+ 404:
+ description: "NOT FOUND"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "No module found with id 'J1_A'."
+ 409:
+ description: "CONFLICT: The request could not be processed because of conflict in the current state of the resource"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Cannot delete modules in Discovery mode."
+ 500:
+ description: "INTERNAL SERVER ERROR"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ 501:
+ description: "NOT IMPLEMENTED: This implies future availability (e.g., a new feature of the API)."
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Deletion of multiple modules at once is currently not supported"
- /deployRobot:
- post: # PUT?
+ /model/stats:
+ get:
tags:
- - modular
- summary: makes an ajax request to the server to deploy the URDF of the robot in a ROS pakage to be saved in the filesystem
- requestBody:
- description: JSON containing a boolean to determine whether or not building mode is activated and the name of the ROS package to save
- required: true
- content:
- application/json:
- schema:
- type: object
- properties:
- name:
- type: string
- example: "ModularBot"
- buildingModeON:
- type: boolean
+ - Robot Model
+ summary: Get a set of statistics for the curent robot model
responses:
- "200":
- description: OK
+ # 200:
+ # description: "OK: the URDF to render!"
+ # content:
+ # application/xml:
+ # schema:
+ # type: object
+ 500:
+ description: "INTERNAL SERVER ERROR"
content:
- text/plain:
+ application/json:
schema:
- type: string
- example: "The URDF sting. Returned just for logging purposes..."
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/ErrorMessage"
+ 501:
+ description: "NOT IMPLEMENTED: This implies future availability (e.g., a new feature of the API)."
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Model statistics are currently not supported"
- /removeConnectors:
- post: # PUT?
+ /resources/modules:
+ get:
tags:
- - modular
- summary: makes an ajax request to the server to remove the connectors from the model. To be called before making a write request and deploying a robot.
- requestBody:
- description: JSON containing a boolean to determine whether or not building mode is activated
- required: true
- content:
- application/json:
- schema:
- type: object
- properties:
- buildingModeON:
- type: boolean
+ - Store
+ summary: Get available modules
+ parameters:
+ - $ref: "#/components/parameters/familiesFromQuery"
+ - $ref: "#/components/parameters/moduleTypesFromQuery"
responses:
- "200":
- description: OK
+ 200:
+ description: "OK"
content:
- text/plain:
+ application/json:
schema:
- type: string
- example: "The URDF string without connectors"
- #TBD
- "400":
- description: Bad Request
- #TBD
- "500":
- description: Server Error
+ $ref: "#/components/schemas/ModuleBaseGetResponse"
+ 400:
+ description: "BAD REQUEST"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Requested invalid 'types'"
+ 404:
+ description: "NOT FOUND"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Family 'foo' not found."
+ 500:
+ description: "INTERNAL SERVER ERROR"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ 501:
+ description: "NOT IMPLEMENTED: This implies future availability (e.g., a new feature of the API)."
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Filtering by type is currently not supported"
+
+ /resources/families:
+ get:
+ tags:
+ - Store
+ summary: Get a list of families of the available modules
+ parameters:
+ - $ref: "#/components/parameters/familiesFromQuery"
+ - $ref: "#/components/parameters/familyGroupFromQuery"
+ responses:
+ 200:
+ description: "OK"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ModuleFamiliesGetResponse"
+ 500:
+ description: "INTERNAL SERVER ERROR"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ 501:
+ description: "NOT IMPLEMENTED: This implies future availability (e.g., a new feature of the API)."
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "Filtering by families is currently not supported"
+
+ /resources/meshes/{path}:
+ parameters:
+ - $ref: "#/components/parameters/stlPathFromPath"
+
+ get:
+ tags:
+ - Store
+ summary: file access for STL meshes
+ responses:
+ 200:
+ description: "OK: the STL to render!"
+ content:
+ model/stl:
+ schema:
+ type: object
+ 404:
+ description: "NOT FOUND"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+ example:
+ message: "No mesh found for path 'foo/bar/baz.stl'"
+ 500:
+ description: "INTERNAL SERVER ERROR"
+ content:
+ application/json:
+ schema:
+ $ref: "#/components/schemas/ErrorMessage"
+# Components
+components:
+ #/components/parameters
+ parameters:
+ stlPathFromPath:
+ in: path
+ name: path
+ required: true
+ schema:
+ type: string
+ example: "foo/bar/baz.stl"
+ modelIdFromQuery:
+ in: query
+ name: id
+ description: "This query variable is unused and has been added to avoid [`react-three-fiber`](https://github.com/pmndrs/react-three-fiber) taking the cached model robot instead of fully reloading it. For details see "
+ schema:
+ type: string
+ examples:
+ id:
+ description: "equals to =`?id=u2lyCEBi`"
+ value: "u2lyCEBi" # ?ids=u2lyCEBi
+ familiesFromQuery:
+ in: query
+ name: "families[]"
+ description: "Optionally the returned list can be filtered by their family of module."
+ schema:
+ type: array
+ items:
+ type: string
+ style: form
+ explode: false
+ examples:
+ multipleTypes:
+ summary: Example of multiple families
+ description: "equals to `?families[]=alberoboticsGenA&families[]=alberoboticsGenB`"
+ value: ["alberoboticsGenA", "alberoboticsGenB"] # ?families[]=alberoboticsGenA&families[]=alberoboticsGenB
+ oneType:
+ summary: Example of a single family
+ description: "equals to `?families[]=alberoboticsGenA`"
+ value: ["alberoboticsGenA"] # ?families[]=alberoboticsGenA
+ familyGroupFromQuery:
+ in: query
+ name: "groups[]"
+ description: "Optionally the returned list can be filtered by their group."
+ schema:
+ type: array
+ items:
+ type: string
+ style: form
+ explode: false
+ examples:
+ multipleTypes:
+ summary: Example of multiple groups
+ description: "equals to `?groups[]=Alberobotics&families[]=CONCERT`"
+ value: ["Alberobotics", "CONCERT"] # ?groups[]=Alberobotics&groups[]=CONCERT
+ oneType:
+ summary: Example of a single group
+ description: "equals to `?groups[]=Alberobotics`"
+ value: ["Alberobotics"] # ?groups[]=Alberobotics
+ moduleTypesFromQuery:
+ in: query
+ name: "types[]"
+ description: "Optionally the returned list can filter results by their type of module."
+ schema:
+ type: array
+ items:
+ type: string
+ style: form
+ explode: false
+ examples:
+ multipleTypes:
+ summary: Example of multiple types
+ description: "equals to `?types[]=joint&types[]=link`"
+ value: ["joint", "link"] # ?types[]=joint,types[]=link
+ oneType:
+ summary: Example of a single type
+ description: "equals to `?types[]=Socket`"
+ value: ["Socket"] # ?types[]=Socket
+ #/components/schemas
+ schemas:
+ #ErrorMessage
+ ErrorMessage:
+ type: object
+ properties:
+ message:
+ type: string
+ description: "The error that triggered an exception"
+ WorkspaceModeGetResponse:
+ type: object
+ properties:
+ mode:
+ type: string
+ description: "The current workspace mode: 'Build' or 'Discover'"
+ example: "Build" # | 'Discover'
+ #URDF_model
+ UrdfGetResponse:
+ type: object
+ properties:
+ urdf:
+ description: the updated URDF to render!
+ type: string
+ # Families
+ ModuleFamily:
+ type: object
+ required:
+ - id
+ - group
+ - label
+ properties:
+ id:
+ type: string
+ description: family Id
+ example: alberoboticsGenB
+ group:
+ type: string
+ description: used to group similar families # potentially Ethercat's 0x1018:01, see https://infosys.beckhoff.com/content/1033/el252x/1856726667.html
+ example: Alberobotics
+ label:
+ type: string
+ description: label shown in the frontend
+ example: "CONCERT"
+ disabled:
+ type: boolean
+ description: represent the family as not selectable
+ example: true
+ ModuleFamiliesGetResponse:
+ type: object
+ required:
+ - families
+ properties:
+ families:
+ type: array
+ items:
+ $ref: "#/components/schemas/ModuleFamily"
+ example:
+ families:
+ - id: "alberoboticsGenA"
+ group: "Alberobotics"
+ label: "PINO v1"
+ - id: "alberoboticsGenB"
+ group: "Alberobotics"
+ label: "CONCERT"
+ disabled: true
+ # Modules
+ ModuleBase:
+ type: object
+ required:
+ - family
+ - type
+ - product
+ - label
+ properties:
+ family:
+ type: string
+ description: "Family Id"
+ example: "alberoboticsGenA"
+ type:
+ type: string
+ description: "Type of module ('ActiveJoint', 'PassiveJoint', 'EndEffector', 'Socket')"
+ example: "EndEffector"
+ product:
+ type: string
+ description: "product code / name of the module" # potentially Ethercat's 0x1018:02, see https://infosys.beckhoff.com/content/1033/el252x/1856726667.html
+ example: "module_joint_yaw_ORANGE"
+ label:
+ type: string
+ description: label shown in the frontend
+ example: "Straight Joint"
+ disabled:
+ type: boolean
+ description: represent the module as not selectable
+ example: true
+ ModuleBaseGetResponse:
+ type: object
+ required:
+ - modules
+ properties:
+ modules:
+ type: array
+ items:
+ $ref: "#/components/schemas/ModuleBase"
+ example:
+ modules:
+ - family: "alberoboticsGenA"
+ type: "ActiveJoint"
+ product: "module_joint_yaw_ORANGE"
+ label: "Straight Joint"
+ - family: "alberoboticsGenA"
+ type: "ActiveJoint"
+ product: "module_joint_double_elbow_ORANGE"
+ label: "Elbow Joint"
+ - family: "alberoboticsGenA"
+ type: "EndEffector"
+ product: "module_tool_exchanger_heavy"
+ label: "Tool Exchanger"
+ disabled: true
+ - family: "alberoboticsGenB"
+ type: "EndEffector"
+ product: "module_gripper"
+ label: "Gripper"
+ ModuleCreateDTO:
+ allOf:
+ - type: object
+ properties:
+ parentId:
+ type: string
+ offset:
+ $ref: "#/components/schemas/offset"
+ - $ref: "#/components/schemas/ModuleBase"
+ Module:
+ allOf:
+ - type: object
+ required:
+ - id
+ properties:
+ id:
+ type: string
+ - $ref: "#/components/schemas/ModuleCreateDTO"
+ example:
+ id: "J2_A"
+ family: "alberoboticsGenA"
+ type: "ActiveJoint"
+ product: "module_joint_yaw_ORANGE"
+ offset:
+ z: 0.05
+ yaw: -1.571
+ reverse: false
+ parent: "J1_A"
+ #Offset
+ poseQuat:
+ type: object
+ description: Pose with quaternion notation
+ properties:
+ x:
+ type: number
+ y:
+ type: number
+ z:
+ type: number
+ rx:
+ type: number
+ ry:
+ type: number
+ rz:
+ type: number
+ rw:
+ type: number
+ example:
+ x: 0.03
+ ry: 0.083
+ rz: 0.05
+ poseRPY:
+ type: object
+ description: Pose with RPY notation
+ properties:
+ x:
+ type: number
+ y:
+ type: number
+ z:
+ type: number
+ roll:
+ type: number
+ pitch:
+ type: number
+ yaw:
+ type: number
+ example:
+ z: 0.05
+ yaw: -1.571
+ offset:
+ oneOf:
+ - $ref: "#/components/schemas/poseQuat"
+ - $ref: "#/components/schemas/poseRPY"
diff --git a/src/modular/web/modular_frontend/asset-manifest.json b/src/modular/web/modular_frontend/asset-manifest.json
new file mode 100644
index 0000000..d9a6ed6
--- /dev/null
+++ b/src/modular/web/modular_frontend/asset-manifest.json
@@ -0,0 +1,13 @@
+{
+ "files": {
+ "main.js": "/static/js/main.1ff7d330.js",
+ "static/js/915.89514730.chunk.js": "/static/js/915.89514730.chunk.js",
+ "service-worker.js": "/service-worker.js",
+ "index.html": "/index.html",
+ "main.1ff7d330.js.map": "/static/js/main.1ff7d330.js.map",
+ "915.89514730.chunk.js.map": "/static/js/915.89514730.chunk.js.map"
+ },
+ "entrypoints": [
+ "static/js/main.1ff7d330.js"
+ ]
+}
\ No newline at end of file
diff --git a/src/modular/web/modular_frontend/assets/index-BqFtD4jC.js b/src/modular/web/modular_frontend/assets/index-BqFtD4jC.js
new file mode 100644
index 0000000..70ae32f
--- /dev/null
+++ b/src/modular/web/modular_frontend/assets/index-BqFtD4jC.js
@@ -0,0 +1,4157 @@
+var dj=Object.defineProperty;var fj=(t,e,n)=>e in t?dj(t,e,{enumerable:!0,configurable:!0,writable:!0,value:n}):t[e]=n;var io=(t,e,n)=>(fj(t,typeof e!="symbol"?e+"":e,n),n),dE=(t,e,n)=>{if(!e.has(t))throw TypeError("Cannot "+n)};var Ae=(t,e,n)=>(dE(t,e,"read from private field"),n?n.call(t):e.get(t)),rn=(t,e,n)=>{if(e.has(t))throw TypeError("Cannot add the same private member more than once");e instanceof WeakSet?e.add(t):e.set(t,n)},jt=(t,e,n,r)=>(dE(t,e,"write to private field"),r?r.call(t,n):e.set(t,n),n);var S_=(t,e,n,r)=>({set _(i){jt(t,e,i,n)},get _(){return Ae(t,e,r)}}),jn=(t,e,n)=>(dE(t,e,"access private method"),n);function hj(t,e){for(var n=0;nr[i]})}}}return Object.freeze(Object.defineProperty(t,Symbol.toStringTag,{value:"Module"}))}(function(){const e=document.createElement("link").relList;if(e&&e.supports&&e.supports("modulepreload"))return;for(const i of document.querySelectorAll('link[rel="modulepreload"]'))r(i);new MutationObserver(i=>{for(const s of i)if(s.type==="childList")for(const o of s.addedNodes)o.tagName==="LINK"&&o.rel==="modulepreload"&&r(o)}).observe(document,{childList:!0,subtree:!0});function n(i){const s={};return i.integrity&&(s.integrity=i.integrity),i.referrerPolicy&&(s.referrerPolicy=i.referrerPolicy),i.crossOrigin==="use-credentials"?s.credentials="include":i.crossOrigin==="anonymous"?s.credentials="omit":s.credentials="same-origin",s}function r(i){if(i.ep)return;i.ep=!0;const s=n(i);fetch(i.href,s)}})();var h1=typeof globalThis<"u"?globalThis:typeof window<"u"?window:typeof global<"u"?global:typeof self<"u"?self:{};function By(t){return t&&t.__esModule&&Object.prototype.hasOwnProperty.call(t,"default")?t.default:t}function Uu(t){if(t.__esModule)return t;var e=t.default;if(typeof e=="function"){var n=function r(){return this instanceof r?Reflect.construct(e,arguments,this.constructor):e.apply(this,arguments)};n.prototype=e.prototype}else n={};return Object.defineProperty(n,"__esModule",{value:!0}),Object.keys(t).forEach(function(r){var i=Object.getOwnPropertyDescriptor(t,r);Object.defineProperty(n,r,i.get?i:{enumerable:!0,get:function(){return t[r]}})}),n}var ND={exports:{}},I2={},DD={exports:{}},er={};/**
+ * @license React
+ * react.production.min.js
+ *
+ * Copyright (c) Facebook, Inc. and its affiliates.
+ *
+ * This source code is licensed under the MIT license found in the
+ * LICENSE file in the root directory of this source tree.
+ */var Hy=Symbol.for("react.element"),pj=Symbol.for("react.portal"),mj=Symbol.for("react.fragment"),gj=Symbol.for("react.strict_mode"),vj=Symbol.for("react.profiler"),yj=Symbol.for("react.provider"),xj=Symbol.for("react.context"),_j=Symbol.for("react.forward_ref"),bj=Symbol.for("react.suspense"),Sj=Symbol.for("react.memo"),wj=Symbol.for("react.lazy"),$4=Symbol.iterator;function Mj(t){return t===null||typeof t!="object"?null:(t=$4&&t[$4]||t["@@iterator"],typeof t=="function"?t:null)}var FD={isMounted:function(){return!1},enqueueForceUpdate:function(){},enqueueReplaceState:function(){},enqueueSetState:function(){}},UD=Object.assign,zD={};function og(t,e,n){this.props=t,this.context=e,this.refs=zD,this.updater=n||FD}og.prototype.isReactComponent={};og.prototype.setState=function(t,e){if(typeof t!="object"&&typeof t!="function"&&t!=null)throw Error("setState(...): takes an object of state variables to update or a function which returns an object of state variables.");this.updater.enqueueSetState(this,t,e,"setState")};og.prototype.forceUpdate=function(t){this.updater.enqueueForceUpdate(this,t,"forceUpdate")};function BD(){}BD.prototype=og.prototype;function $A(t,e,n){this.props=t,this.context=e,this.refs=zD,this.updater=n||FD}var VA=$A.prototype=new BD;VA.constructor=$A;UD(VA,og.prototype);VA.isPureReactComponent=!0;var V4=Array.isArray,HD=Object.prototype.hasOwnProperty,WA={current:null},$D={key:!0,ref:!0,__self:!0,__source:!0};function VD(t,e,n){var r,i={},s=null,o=null;if(e!=null)for(r in e.ref!==void 0&&(o=e.ref),e.key!==void 0&&(s=""+e.key),e)HD.call(e,r)&&!$D.hasOwnProperty(r)&&(i[r]=e[r]);var a=arguments.length-2;if(a===1)i.children=n;else if(1>>1,Ce=z[de];if(0>>1;dei(me,oe))pei(Se,me)?(z[de]=Se,z[pe]=oe,de=pe):(z[de]=me,z[V]=oe,de=V);else if(pei(Se,oe))z[de]=Se,z[pe]=oe,de=pe;else break e}}return te}function i(z,te){var oe=z.sortIndex-te.sortIndex;return oe!==0?oe:z.id-te.id}if(typeof performance=="object"&&typeof performance.now=="function"){var s=performance;t.unstable_now=function(){return s.now()}}else{var o=Date,a=o.now();t.unstable_now=function(){return o.now()-a}}var l=[],c=[],f=1,p=null,g=3,v=!1,x=!1,_=!1,b=typeof setTimeout=="function"?setTimeout:null,y=typeof clearTimeout=="function"?clearTimeout:null,S=typeof setImmediate<"u"?setImmediate:null;typeof navigator<"u"&&navigator.scheduling!==void 0&&navigator.scheduling.isInputPending!==void 0&&navigator.scheduling.isInputPending.bind(navigator.scheduling);function w(z){for(var te=n(c);te!==null;){if(te.callback===null)r(c);else if(te.startTime<=z)r(c),te.sortIndex=te.expirationTime,e(l,te);else break;te=n(c)}}function T(z){if(_=!1,w(z),!x)if(n(l)!==null)x=!0,ee(L);else{var te=n(c);te!==null&&ue(T,te.startTime-z)}}function L(z,te){x=!1,_&&(_=!1,y(F),F=-1),v=!0;var oe=g;try{for(w(te),p=n(l);p!==null&&(!(p.expirationTime>te)||z&&!H());){var de=p.callback;if(typeof de=="function"){p.callback=null,g=p.priorityLevel;var Ce=de(p.expirationTime<=te);te=t.unstable_now(),typeof Ce=="function"?p.callback=Ce:p===n(l)&&r(l),w(te)}else r(l);p=n(l)}if(p!==null)var Le=!0;else{var V=n(c);V!==null&&ue(T,V.startTime-te),Le=!1}return Le}finally{p=null,g=oe,v=!1}}var R=!1,P=null,F=-1,O=5,I=-1;function H(){return!(t.unstable_now()-Iz||125de?(z.sortIndex=oe,e(c,z),n(l)===null&&z===n(c)&&(_?(y(F),F=-1):_=!0,ue(T,oe-de))):(z.sortIndex=Ce,e(l,z),x||v||(x=!0,ee(L))),z},t.unstable_shouldYield=H,t.unstable_wrapCallback=function(z){var te=g;return function(){var oe=g;g=te;try{return z.apply(this,arguments)}finally{g=oe}}}})(qD);XD.exports=qD;var Nj=XD.exports;/**
+ * @license React
+ * react-dom.production.min.js
+ *
+ * Copyright (c) Facebook, Inc. and its affiliates.
+ *
+ * This source code is licensed under the MIT license found in the
+ * LICENSE file in the root directory of this source tree.
+ */var Dj=D,Ea=Nj;function Ct(t){for(var e="https://reactjs.org/docs/error-decoder.html?invariant="+t,n=1;n"u"||typeof window.document>"u"||typeof window.document.createElement>"u"),gC=Object.prototype.hasOwnProperty,Fj=/^[:A-Z_a-z\u00C0-\u00D6\u00D8-\u00F6\u00F8-\u02FF\u0370-\u037D\u037F-\u1FFF\u200C-\u200D\u2070-\u218F\u2C00-\u2FEF\u3001-\uD7FF\uF900-\uFDCF\uFDF0-\uFFFD][:A-Z_a-z\u00C0-\u00D6\u00D8-\u00F6\u00F8-\u02FF\u0370-\u037D\u037F-\u1FFF\u200C-\u200D\u2070-\u218F\u2C00-\u2FEF\u3001-\uD7FF\uF900-\uFDCF\uFDF0-\uFFFD\-.0-9\u00B7\u0300-\u036F\u203F-\u2040]*$/,j4={},G4={};function Uj(t){return gC.call(G4,t)?!0:gC.call(j4,t)?!1:Fj.test(t)?G4[t]=!0:(j4[t]=!0,!1)}function zj(t,e,n,r){if(n!==null&&n.type===0)return!1;switch(typeof e){case"function":case"symbol":return!0;case"boolean":return r?!1:n!==null?!n.acceptsBooleans:(t=t.toLowerCase().slice(0,5),t!=="data-"&&t!=="aria-");default:return!1}}function Bj(t,e,n,r){if(e===null||typeof e>"u"||zj(t,e,n,r))return!0;if(r)return!1;if(n!==null)switch(n.type){case 3:return!e;case 4:return e===!1;case 5:return isNaN(e);case 6:return isNaN(e)||1>e}return!1}function So(t,e,n,r,i,s,o){this.acceptsBooleans=e===2||e===3||e===4,this.attributeName=r,this.attributeNamespace=i,this.mustUseProperty=n,this.propertyName=t,this.type=e,this.sanitizeURL=s,this.removeEmptyString=o}var Os={};"children dangerouslySetInnerHTML defaultValue defaultChecked innerHTML suppressContentEditableWarning suppressHydrationWarning style".split(" ").forEach(function(t){Os[t]=new So(t,0,!1,t,null,!1,!1)});[["acceptCharset","accept-charset"],["className","class"],["htmlFor","for"],["httpEquiv","http-equiv"]].forEach(function(t){var e=t[0];Os[e]=new So(e,1,!1,t[1],null,!1,!1)});["contentEditable","draggable","spellCheck","value"].forEach(function(t){Os[t]=new So(t,2,!1,t.toLowerCase(),null,!1,!1)});["autoReverse","externalResourcesRequired","focusable","preserveAlpha"].forEach(function(t){Os[t]=new So(t,2,!1,t,null,!1,!1)});"allowFullScreen async autoFocus autoPlay controls default defer disabled disablePictureInPicture disableRemotePlayback formNoValidate hidden loop noModule noValidate open playsInline readOnly required reversed scoped seamless itemScope".split(" ").forEach(function(t){Os[t]=new So(t,3,!1,t.toLowerCase(),null,!1,!1)});["checked","multiple","muted","selected"].forEach(function(t){Os[t]=new So(t,3,!0,t,null,!1,!1)});["capture","download"].forEach(function(t){Os[t]=new So(t,4,!1,t,null,!1,!1)});["cols","rows","size","span"].forEach(function(t){Os[t]=new So(t,6,!1,t,null,!1,!1)});["rowSpan","start"].forEach(function(t){Os[t]=new So(t,5,!1,t.toLowerCase(),null,!1,!1)});var GA=/[\-:]([a-z])/g;function XA(t){return t[1].toUpperCase()}"accent-height alignment-baseline arabic-form baseline-shift cap-height clip-path clip-rule color-interpolation color-interpolation-filters color-profile color-rendering dominant-baseline enable-background fill-opacity fill-rule flood-color flood-opacity font-family font-size font-size-adjust font-stretch font-style font-variant font-weight glyph-name glyph-orientation-horizontal glyph-orientation-vertical horiz-adv-x horiz-origin-x image-rendering letter-spacing lighting-color marker-end marker-mid marker-start overline-position overline-thickness paint-order panose-1 pointer-events rendering-intent shape-rendering stop-color stop-opacity strikethrough-position strikethrough-thickness stroke-dasharray stroke-dashoffset stroke-linecap stroke-linejoin stroke-miterlimit stroke-opacity stroke-width text-anchor text-decoration text-rendering underline-position underline-thickness unicode-bidi unicode-range units-per-em v-alphabetic v-hanging v-ideographic v-mathematical vector-effect vert-adv-y vert-origin-x vert-origin-y word-spacing writing-mode xmlns:xlink x-height".split(" ").forEach(function(t){var e=t.replace(GA,XA);Os[e]=new So(e,1,!1,t,null,!1,!1)});"xlink:actuate xlink:arcrole xlink:role xlink:show xlink:title xlink:type".split(" ").forEach(function(t){var e=t.replace(GA,XA);Os[e]=new So(e,1,!1,t,"http://www.w3.org/1999/xlink",!1,!1)});["xml:base","xml:lang","xml:space"].forEach(function(t){var e=t.replace(GA,XA);Os[e]=new So(e,1,!1,t,"http://www.w3.org/XML/1998/namespace",!1,!1)});["tabIndex","crossOrigin"].forEach(function(t){Os[t]=new So(t,1,!1,t.toLowerCase(),null,!1,!1)});Os.xlinkHref=new So("xlinkHref",1,!1,"xlink:href","http://www.w3.org/1999/xlink",!0,!1);["src","href","action","formAction"].forEach(function(t){Os[t]=new So(t,1,!1,t.toLowerCase(),null,!0,!0)});function qA(t,e,n,r){var i=Os.hasOwnProperty(e)?Os[e]:null;(i!==null?i.type!==0:r||!(2a||i[o]!==s[a]){var l=`
+`+i[o].replace(" at new "," at ");return t.displayName&&l.includes("")&&(l=l.replace("",t.displayName)),l}while(1<=o&&0<=a);break}}}finally{pE=!1,Error.prepareStackTrace=n}return(t=t?t.displayName||t.name:"")?Z1(t):""}function Hj(t){switch(t.tag){case 5:return Z1(t.type);case 16:return Z1("Lazy");case 13:return Z1("Suspense");case 19:return Z1("SuspenseList");case 0:case 2:case 15:return t=mE(t.type,!1),t;case 11:return t=mE(t.type.render,!1),t;case 1:return t=mE(t.type,!0),t;default:return""}}function _C(t){if(t==null)return null;if(typeof t=="function")return t.displayName||t.name||null;if(typeof t=="string")return t;switch(t){case Zm:return"Fragment";case qm:return"Portal";case vC:return"Profiler";case ZA:return"StrictMode";case yC:return"Suspense";case xC:return"SuspenseList"}if(typeof t=="object")switch(t.$$typeof){case KD:return(t.displayName||"Context")+".Consumer";case YD:return(t._context.displayName||"Context")+".Provider";case YA:var e=t.render;return t=t.displayName,t||(t=e.displayName||e.name||"",t=t!==""?"ForwardRef("+t+")":"ForwardRef"),t;case KA:return e=t.displayName||null,e!==null?e:_C(t.type)||"Memo";case kd:e=t._payload,t=t._init;try{return _C(t(e))}catch{}}return null}function $j(t){var e=t.type;switch(t.tag){case 24:return"Cache";case 9:return(e.displayName||"Context")+".Consumer";case 10:return(e._context.displayName||"Context")+".Provider";case 18:return"DehydratedFragment";case 11:return t=e.render,t=t.displayName||t.name||"",e.displayName||(t!==""?"ForwardRef("+t+")":"ForwardRef");case 7:return"Fragment";case 5:return e;case 4:return"Portal";case 3:return"Root";case 6:return"Text";case 16:return _C(e);case 8:return e===ZA?"StrictMode":"Mode";case 22:return"Offscreen";case 12:return"Profiler";case 21:return"Scope";case 13:return"Suspense";case 19:return"SuspenseList";case 25:return"TracingMarker";case 1:case 0:case 17:case 2:case 14:case 15:if(typeof e=="function")return e.displayName||e.name||null;if(typeof e=="string")return e}return null}function lf(t){switch(typeof t){case"boolean":case"number":case"string":case"undefined":return t;case"object":return t;default:return""}}function JD(t){var e=t.type;return(t=t.nodeName)&&t.toLowerCase()==="input"&&(e==="checkbox"||e==="radio")}function Vj(t){var e=JD(t)?"checked":"value",n=Object.getOwnPropertyDescriptor(t.constructor.prototype,e),r=""+t[e];if(!t.hasOwnProperty(e)&&typeof n<"u"&&typeof n.get=="function"&&typeof n.set=="function"){var i=n.get,s=n.set;return Object.defineProperty(t,e,{configurable:!0,get:function(){return i.call(this)},set:function(o){r=""+o,s.call(this,o)}}),Object.defineProperty(t,e,{enumerable:n.enumerable}),{getValue:function(){return r},setValue:function(o){r=""+o},stopTracking:function(){t._valueTracker=null,delete t[e]}}}}function E_(t){t._valueTracker||(t._valueTracker=Vj(t))}function e6(t){if(!t)return!1;var e=t._valueTracker;if(!e)return!0;var n=e.getValue(),r="";return t&&(r=JD(t)?t.checked?"true":"false":t.value),t=r,t!==n?(e.setValue(t),!0):!1}function FS(t){if(t=t||(typeof document<"u"?document:void 0),typeof t>"u")return null;try{return t.activeElement||t.body}catch{return t.body}}function bC(t,e){var n=e.checked;return ci({},e,{defaultChecked:void 0,defaultValue:void 0,value:void 0,checked:n??t._wrapperState.initialChecked})}function q4(t,e){var n=e.defaultValue==null?"":e.defaultValue,r=e.checked!=null?e.checked:e.defaultChecked;n=lf(e.value!=null?e.value:n),t._wrapperState={initialChecked:r,initialValue:n,controlled:e.type==="checkbox"||e.type==="radio"?e.checked!=null:e.value!=null}}function t6(t,e){e=e.checked,e!=null&&qA(t,"checked",e,!1)}function SC(t,e){t6(t,e);var n=lf(e.value),r=e.type;if(n!=null)r==="number"?(n===0&&t.value===""||t.value!=n)&&(t.value=""+n):t.value!==""+n&&(t.value=""+n);else if(r==="submit"||r==="reset"){t.removeAttribute("value");return}e.hasOwnProperty("value")?wC(t,e.type,n):e.hasOwnProperty("defaultValue")&&wC(t,e.type,lf(e.defaultValue)),e.checked==null&&e.defaultChecked!=null&&(t.defaultChecked=!!e.defaultChecked)}function Z4(t,e,n){if(e.hasOwnProperty("value")||e.hasOwnProperty("defaultValue")){var r=e.type;if(!(r!=="submit"&&r!=="reset"||e.value!==void 0&&e.value!==null))return;e=""+t._wrapperState.initialValue,n||e===t.value||(t.value=e),t.defaultValue=e}n=t.name,n!==""&&(t.name=""),t.defaultChecked=!!t._wrapperState.initialChecked,n!==""&&(t.name=n)}function wC(t,e,n){(e!=="number"||FS(t.ownerDocument)!==t)&&(n==null?t.defaultValue=""+t._wrapperState.initialValue:t.defaultValue!==""+n&&(t.defaultValue=""+n))}var Y1=Array.isArray;function f0(t,e,n,r){if(t=t.options,e){e={};for(var i=0;i"+e.valueOf().toString()+"",e=C_.firstChild;t.firstChild;)t.removeChild(t.firstChild);for(;e.firstChild;)t.appendChild(e.firstChild)}});function Av(t,e){if(e){var n=t.firstChild;if(n&&n===t.lastChild&&n.nodeType===3){n.nodeValue=e;return}}t.textContent=e}var sv={animationIterationCount:!0,aspectRatio:!0,borderImageOutset:!0,borderImageSlice:!0,borderImageWidth:!0,boxFlex:!0,boxFlexGroup:!0,boxOrdinalGroup:!0,columnCount:!0,columns:!0,flex:!0,flexGrow:!0,flexPositive:!0,flexShrink:!0,flexNegative:!0,flexOrder:!0,gridArea:!0,gridRow:!0,gridRowEnd:!0,gridRowSpan:!0,gridRowStart:!0,gridColumn:!0,gridColumnEnd:!0,gridColumnSpan:!0,gridColumnStart:!0,fontWeight:!0,lineClamp:!0,lineHeight:!0,opacity:!0,order:!0,orphans:!0,tabSize:!0,widows:!0,zIndex:!0,zoom:!0,fillOpacity:!0,floodOpacity:!0,stopOpacity:!0,strokeDasharray:!0,strokeDashoffset:!0,strokeMiterlimit:!0,strokeOpacity:!0,strokeWidth:!0},Wj=["Webkit","ms","Moz","O"];Object.keys(sv).forEach(function(t){Wj.forEach(function(e){e=e+t.charAt(0).toUpperCase()+t.substring(1),sv[e]=sv[t]})});function s6(t,e,n){return e==null||typeof e=="boolean"||e===""?"":n||typeof e!="number"||e===0||sv.hasOwnProperty(t)&&sv[t]?(""+e).trim():e+"px"}function o6(t,e){t=t.style;for(var n in e)if(e.hasOwnProperty(n)){var r=n.indexOf("--")===0,i=s6(n,e[n],r);n==="float"&&(n="cssFloat"),r?t.setProperty(n,i):t[n]=i}}var jj=ci({menuitem:!0},{area:!0,base:!0,br:!0,col:!0,embed:!0,hr:!0,img:!0,input:!0,keygen:!0,link:!0,meta:!0,param:!0,source:!0,track:!0,wbr:!0});function CC(t,e){if(e){if(jj[t]&&(e.children!=null||e.dangerouslySetInnerHTML!=null))throw Error(Ct(137,t));if(e.dangerouslySetInnerHTML!=null){if(e.children!=null)throw Error(Ct(60));if(typeof e.dangerouslySetInnerHTML!="object"||!("__html"in e.dangerouslySetInnerHTML))throw Error(Ct(61))}if(e.style!=null&&typeof e.style!="object")throw Error(Ct(62))}}function TC(t,e){if(t.indexOf("-")===-1)return typeof e.is=="string";switch(t){case"annotation-xml":case"color-profile":case"font-face":case"font-face-src":case"font-face-uri":case"font-face-format":case"font-face-name":case"missing-glyph":return!1;default:return!0}}var AC=null;function QA(t){return t=t.target||t.srcElement||window,t.correspondingUseElement&&(t=t.correspondingUseElement),t.nodeType===3?t.parentNode:t}var RC=null,h0=null,p0=null;function Q4(t){if(t=Wy(t)){if(typeof RC!="function")throw Error(Ct(280));var e=t.stateNode;e&&(e=D2(e),RC(t.stateNode,t.type,e))}}function a6(t){h0?p0?p0.push(t):p0=[t]:h0=t}function l6(){if(h0){var t=h0,e=p0;if(p0=h0=null,Q4(t),e)for(t=0;t>>=0,t===0?32:31-(nG(t)/rG|0)|0}var T_=64,A_=4194304;function K1(t){switch(t&-t){case 1:return 1;case 2:return 2;case 4:return 4;case 8:return 8;case 16:return 16;case 32:return 32;case 64:case 128:case 256:case 512:case 1024:case 2048:case 4096:case 8192:case 16384:case 32768:case 65536:case 131072:case 262144:case 524288:case 1048576:case 2097152:return t&4194240;case 4194304:case 8388608:case 16777216:case 33554432:case 67108864:return t&130023424;case 134217728:return 134217728;case 268435456:return 268435456;case 536870912:return 536870912;case 1073741824:return 1073741824;default:return t}}function HS(t,e){var n=t.pendingLanes;if(n===0)return 0;var r=0,i=t.suspendedLanes,s=t.pingedLanes,o=n&268435455;if(o!==0){var a=o&~i;a!==0?r=K1(a):(s&=o,s!==0&&(r=K1(s)))}else o=n&~i,o!==0?r=K1(o):s!==0&&(r=K1(s));if(r===0)return 0;if(e!==0&&e!==r&&!(e&i)&&(i=r&-r,s=e&-e,i>=s||i===16&&(s&4194240)!==0))return e;if(r&4&&(r|=n&16),e=t.entangledLanes,e!==0)for(t=t.entanglements,e&=r;0n;n++)e.push(t);return e}function $y(t,e,n){t.pendingLanes|=e,e!==536870912&&(t.suspendedLanes=0,t.pingedLanes=0),t=t.eventTimes,e=31-Hl(e),t[e]=n}function aG(t,e){var n=t.pendingLanes&~e;t.pendingLanes=e,t.suspendedLanes=0,t.pingedLanes=0,t.expiredLanes&=e,t.mutableReadLanes&=e,t.entangledLanes&=e,e=t.entanglements;var r=t.eventTimes;for(t=t.expirationTimes;0=av),aI=" ",lI=!1;function A6(t,e){switch(t){case"keyup":return NG.indexOf(e.keyCode)!==-1;case"keydown":return e.keyCode!==229;case"keypress":case"mousedown":case"focusout":return!0;default:return!1}}function R6(t){return t=t.detail,typeof t=="object"&&"data"in t?t.data:null}var Ym=!1;function FG(t,e){switch(t){case"compositionend":return R6(e);case"keypress":return e.which!==32?null:(lI=!0,aI);case"textInput":return t=e.data,t===aI&&lI?null:t;default:return null}}function UG(t,e){if(Ym)return t==="compositionend"||!o3&&A6(t,e)?(t=C6(),cS=r3=Xd=null,Ym=!1,t):null;switch(t){case"paste":return null;case"keypress":if(!(e.ctrlKey||e.altKey||e.metaKey)||e.ctrlKey&&e.altKey){if(e.char&&1=e)return{node:n,offset:e-t};t=r}e:{for(;n;){if(n.nextSibling){n=n.nextSibling;break e}n=n.parentNode}n=void 0}n=fI(n)}}function k6(t,e){return t&&e?t===e?!0:t&&t.nodeType===3?!1:e&&e.nodeType===3?k6(t,e.parentNode):"contains"in t?t.contains(e):t.compareDocumentPosition?!!(t.compareDocumentPosition(e)&16):!1:!1}function O6(){for(var t=window,e=FS();e instanceof t.HTMLIFrameElement;){try{var n=typeof e.contentWindow.location.href=="string"}catch{n=!1}if(n)t=e.contentWindow;else break;e=FS(t.document)}return e}function a3(t){var e=t&&t.nodeName&&t.nodeName.toLowerCase();return e&&(e==="input"&&(t.type==="text"||t.type==="search"||t.type==="tel"||t.type==="url"||t.type==="password")||e==="textarea"||t.contentEditable==="true")}function XG(t){var e=O6(),n=t.focusedElem,r=t.selectionRange;if(e!==n&&n&&n.ownerDocument&&k6(n.ownerDocument.documentElement,n)){if(r!==null&&a3(n)){if(e=r.start,t=r.end,t===void 0&&(t=e),"selectionStart"in n)n.selectionStart=e,n.selectionEnd=Math.min(t,n.value.length);else if(t=(e=n.ownerDocument||document)&&e.defaultView||window,t.getSelection){t=t.getSelection();var i=n.textContent.length,s=Math.min(r.start,i);r=r.end===void 0?s:Math.min(r.end,i),!t.extend&&s>r&&(i=r,r=s,s=i),i=hI(n,s);var o=hI(n,r);i&&o&&(t.rangeCount!==1||t.anchorNode!==i.node||t.anchorOffset!==i.offset||t.focusNode!==o.node||t.focusOffset!==o.offset)&&(e=e.createRange(),e.setStart(i.node,i.offset),t.removeAllRanges(),s>r?(t.addRange(e),t.extend(o.node,o.offset)):(e.setEnd(o.node,o.offset),t.addRange(e)))}}for(e=[],t=n;t=t.parentNode;)t.nodeType===1&&e.push({element:t,left:t.scrollLeft,top:t.scrollTop});for(typeof n.focus=="function"&&n.focus(),n=0;n=document.documentMode,Km=null,NC=null,cv=null,DC=!1;function pI(t,e,n){var r=n.window===n?n.document:n.nodeType===9?n:n.ownerDocument;DC||Km==null||Km!==FS(r)||(r=Km,"selectionStart"in r&&a3(r)?r={start:r.selectionStart,end:r.selectionEnd}:(r=(r.ownerDocument&&r.ownerDocument.defaultView||window).getSelection(),r={anchorNode:r.anchorNode,anchorOffset:r.anchorOffset,focusNode:r.focusNode,focusOffset:r.focusOffset}),cv&&Ov(cv,r)||(cv=r,r=WS(NC,"onSelect"),0e0||(t.current=$C[e0],$C[e0]=null,e0--)}function Vr(t,e){e0++,$C[e0]=t.current,t.current=e}var cf={},qs=ff(cf),Bo=ff(!1),tp=cf;function F0(t,e){var n=t.type.contextTypes;if(!n)return cf;var r=t.stateNode;if(r&&r.__reactInternalMemoizedUnmaskedChildContext===e)return r.__reactInternalMemoizedMaskedChildContext;var i={},s;for(s in n)i[s]=e[s];return r&&(t=t.stateNode,t.__reactInternalMemoizedUnmaskedChildContext=e,t.__reactInternalMemoizedMaskedChildContext=i),i}function Ho(t){return t=t.childContextTypes,t!=null}function GS(){Zr(Bo),Zr(qs)}function bI(t,e,n){if(qs.current!==cf)throw Error(Ct(168));Vr(qs,e),Vr(Bo,n)}function V6(t,e,n){var r=t.stateNode;if(e=e.childContextTypes,typeof r.getChildContext!="function")return n;r=r.getChildContext();for(var i in r)if(!(i in e))throw Error(Ct(108,$j(t)||"Unknown",i));return ci({},n,r)}function XS(t){return t=(t=t.stateNode)&&t.__reactInternalMemoizedMergedChildContext||cf,tp=qs.current,Vr(qs,t),Vr(Bo,Bo.current),!0}function SI(t,e,n){var r=t.stateNode;if(!r)throw Error(Ct(169));n?(t=V6(t,e,tp),r.__reactInternalMemoizedMergedChildContext=t,Zr(Bo),Zr(qs),Vr(qs,t)):Zr(Bo),Vr(Bo,n)}var mu=null,F2=!1,RE=!1;function W6(t){mu===null?mu=[t]:mu.push(t)}function sX(t){F2=!0,W6(t)}function hf(){if(!RE&&mu!==null){RE=!0;var t=0,e=wr;try{var n=mu;for(wr=1;t>=o,i-=o,bu=1<<32-Hl(e)+i|n<F?(O=P,P=null):O=P.sibling;var I=g(y,P,w[F],T);if(I===null){P===null&&(P=O);break}t&&P&&I.alternate===null&&e(y,P),S=s(I,S,F),R===null?L=I:R.sibling=I,R=I,P=O}if(F===w.length)return n(y,P),ei&&hh(y,F),L;if(P===null){for(;FF?(O=P,P=null):O=P.sibling;var H=g(y,P,I.value,T);if(H===null){P===null&&(P=O);break}t&&P&&H.alternate===null&&e(y,P),S=s(H,S,F),R===null?L=H:R.sibling=H,R=H,P=O}if(I.done)return n(y,P),ei&&hh(y,F),L;if(P===null){for(;!I.done;F++,I=w.next())I=p(y,I.value,T),I!==null&&(S=s(I,S,F),R===null?L=I:R.sibling=I,R=I);return ei&&hh(y,F),L}for(P=r(y,P);!I.done;F++,I=w.next())I=v(P,y,F,I.value,T),I!==null&&(t&&I.alternate!==null&&P.delete(I.key===null?F:I.key),S=s(I,S,F),R===null?L=I:R.sibling=I,R=I);return t&&P.forEach(function(Q){return e(y,Q)}),ei&&hh(y,F),L}function b(y,S,w,T){if(typeof w=="object"&&w!==null&&w.type===Zm&&w.key===null&&(w=w.props.children),typeof w=="object"&&w!==null){switch(w.$$typeof){case M_:e:{for(var L=w.key,R=S;R!==null;){if(R.key===L){if(L=w.type,L===Zm){if(R.tag===7){n(y,R.sibling),S=i(R,w.props.children),S.return=y,y=S;break e}}else if(R.elementType===L||typeof L=="object"&&L!==null&&L.$$typeof===kd&&EI(L)===R.type){n(y,R.sibling),S=i(R,w.props),S.ref=x1(y,R,w),S.return=y,y=S;break e}n(y,R);break}else e(y,R);R=R.sibling}w.type===Zm?(S=Gh(w.props.children,y.mode,T,w.key),S.return=y,y=S):(T=vS(w.type,w.key,w.props,null,y.mode,T),T.ref=x1(y,S,w),T.return=y,y=T)}return o(y);case qm:e:{for(R=w.key;S!==null;){if(S.key===R)if(S.tag===4&&S.stateNode.containerInfo===w.containerInfo&&S.stateNode.implementation===w.implementation){n(y,S.sibling),S=i(S,w.children||[]),S.return=y,y=S;break e}else{n(y,S);break}else e(y,S);S=S.sibling}S=FE(w,y.mode,T),S.return=y,y=S}return o(y);case kd:return R=w._init,b(y,S,R(w._payload),T)}if(Y1(w))return x(y,S,w,T);if(p1(w))return _(y,S,w,T);N_(y,w)}return typeof w=="string"&&w!==""||typeof w=="number"?(w=""+w,S!==null&&S.tag===6?(n(y,S.sibling),S=i(S,w),S.return=y,y=S):(n(y,S),S=DE(w,y.mode,T),S.return=y,y=S),o(y)):n(y,S)}return b}var z0=q6(!0),Z6=q6(!1),YS=ff(null),KS=null,r0=null,d3=null;function f3(){d3=r0=KS=null}function h3(t){var e=YS.current;Zr(YS),t._currentValue=e}function jC(t,e,n){for(;t!==null;){var r=t.alternate;if((t.childLanes&e)!==e?(t.childLanes|=e,r!==null&&(r.childLanes|=e)):r!==null&&(r.childLanes&e)!==e&&(r.childLanes|=e),t===n)break;t=t.return}}function g0(t,e){KS=t,d3=r0=null,t=t.dependencies,t!==null&&t.firstContext!==null&&(t.lanes&e&&(Fo=!0),t.firstContext=null)}function ll(t){var e=t._currentValue;if(d3!==t)if(t={context:t,memoizedValue:e,next:null},r0===null){if(KS===null)throw Error(Ct(308));r0=t,KS.dependencies={lanes:0,firstContext:t}}else r0=r0.next=t;return e}var Ch=null;function p3(t){Ch===null?Ch=[t]:Ch.push(t)}function Y6(t,e,n,r){var i=e.interleaved;return i===null?(n.next=n,p3(e)):(n.next=i.next,i.next=n),e.interleaved=n,ku(t,r)}function ku(t,e){t.lanes|=e;var n=t.alternate;for(n!==null&&(n.lanes|=e),n=t,t=t.return;t!==null;)t.childLanes|=e,n=t.alternate,n!==null&&(n.childLanes|=e),n=t,t=t.return;return n.tag===3?n.stateNode:null}var Od=!1;function m3(t){t.updateQueue={baseState:t.memoizedState,firstBaseUpdate:null,lastBaseUpdate:null,shared:{pending:null,interleaved:null,lanes:0},effects:null}}function K6(t,e){t=t.updateQueue,e.updateQueue===t&&(e.updateQueue={baseState:t.baseState,firstBaseUpdate:t.firstBaseUpdate,lastBaseUpdate:t.lastBaseUpdate,shared:t.shared,effects:t.effects})}function Eu(t,e){return{eventTime:t,lane:e,tag:0,payload:null,callback:null,next:null}}function nf(t,e,n){var r=t.updateQueue;if(r===null)return null;if(r=r.shared,ur&2){var i=r.pending;return i===null?e.next=e:(e.next=i.next,i.next=e),r.pending=e,ku(t,n)}return i=r.interleaved,i===null?(e.next=e,p3(r)):(e.next=i.next,i.next=e),r.interleaved=e,ku(t,n)}function dS(t,e,n){if(e=e.updateQueue,e!==null&&(e=e.shared,(n&4194240)!==0)){var r=e.lanes;r&=t.pendingLanes,n|=r,e.lanes=n,e3(t,n)}}function CI(t,e){var n=t.updateQueue,r=t.alternate;if(r!==null&&(r=r.updateQueue,n===r)){var i=null,s=null;if(n=n.firstBaseUpdate,n!==null){do{var o={eventTime:n.eventTime,lane:n.lane,tag:n.tag,payload:n.payload,callback:n.callback,next:null};s===null?i=s=o:s=s.next=o,n=n.next}while(n!==null);s===null?i=s=e:s=s.next=e}else i=s=e;n={baseState:r.baseState,firstBaseUpdate:i,lastBaseUpdate:s,shared:r.shared,effects:r.effects},t.updateQueue=n;return}t=n.lastBaseUpdate,t===null?n.firstBaseUpdate=e:t.next=e,n.lastBaseUpdate=e}function QS(t,e,n,r){var i=t.updateQueue;Od=!1;var s=i.firstBaseUpdate,o=i.lastBaseUpdate,a=i.shared.pending;if(a!==null){i.shared.pending=null;var l=a,c=l.next;l.next=null,o===null?s=c:o.next=c,o=l;var f=t.alternate;f!==null&&(f=f.updateQueue,a=f.lastBaseUpdate,a!==o&&(a===null?f.firstBaseUpdate=c:a.next=c,f.lastBaseUpdate=l))}if(s!==null){var p=i.baseState;o=0,f=c=l=null,a=s;do{var g=a.lane,v=a.eventTime;if((r&g)===g){f!==null&&(f=f.next={eventTime:v,lane:0,tag:a.tag,payload:a.payload,callback:a.callback,next:null});e:{var x=t,_=a;switch(g=e,v=n,_.tag){case 1:if(x=_.payload,typeof x=="function"){p=x.call(v,p,g);break e}p=x;break e;case 3:x.flags=x.flags&-65537|128;case 0:if(x=_.payload,g=typeof x=="function"?x.call(v,p,g):x,g==null)break e;p=ci({},p,g);break e;case 2:Od=!0}}a.callback!==null&&a.lane!==0&&(t.flags|=64,g=i.effects,g===null?i.effects=[a]:g.push(a))}else v={eventTime:v,lane:g,tag:a.tag,payload:a.payload,callback:a.callback,next:null},f===null?(c=f=v,l=p):f=f.next=v,o|=g;if(a=a.next,a===null){if(a=i.shared.pending,a===null)break;g=a,a=g.next,g.next=null,i.lastBaseUpdate=g,i.shared.pending=null}}while(!0);if(f===null&&(l=p),i.baseState=l,i.firstBaseUpdate=c,i.lastBaseUpdate=f,e=i.shared.interleaved,e!==null){i=e;do o|=i.lane,i=i.next;while(i!==e)}else s===null&&(i.shared.lanes=0);ip|=o,t.lanes=o,t.memoizedState=p}}function TI(t,e,n){if(t=e.effects,e.effects=null,t!==null)for(e=0;en?n:4,t(!0);var r=IE.transition;IE.transition={};try{t(!1),e()}finally{wr=n,IE.transition=r}}function pF(){return cl().memoizedState}function cX(t,e,n){var r=sf(t);if(n={lane:r,action:n,hasEagerState:!1,eagerState:null,next:null},mF(t))gF(e,n);else if(n=Y6(t,e,n,r),n!==null){var i=go();$l(n,t,r,i),vF(n,e,r)}}function uX(t,e,n){var r=sf(t),i={lane:r,action:n,hasEagerState:!1,eagerState:null,next:null};if(mF(t))gF(e,i);else{var s=t.alternate;if(t.lanes===0&&(s===null||s.lanes===0)&&(s=e.lastRenderedReducer,s!==null))try{var o=e.lastRenderedState,a=s(o,n);if(i.hasEagerState=!0,i.eagerState=a,Vl(a,o)){var l=e.interleaved;l===null?(i.next=i,p3(e)):(i.next=l.next,l.next=i),e.interleaved=i;return}}catch{}finally{}n=Y6(t,e,i,r),n!==null&&(i=go(),$l(n,t,r,i),vF(n,e,r))}}function mF(t){var e=t.alternate;return t===li||e!==null&&e===li}function gF(t,e){uv=e2=!0;var n=t.pending;n===null?e.next=e:(e.next=n.next,n.next=e),t.pending=e}function vF(t,e,n){if(n&4194240){var r=e.lanes;r&=t.pendingLanes,n|=r,e.lanes=n,e3(t,n)}}var t2={readContext:ll,useCallback:Bs,useContext:Bs,useEffect:Bs,useImperativeHandle:Bs,useInsertionEffect:Bs,useLayoutEffect:Bs,useMemo:Bs,useReducer:Bs,useRef:Bs,useState:Bs,useDebugValue:Bs,useDeferredValue:Bs,useTransition:Bs,useMutableSource:Bs,useSyncExternalStore:Bs,useId:Bs,unstable_isNewReconciler:!1},dX={readContext:ll,useCallback:function(t,e){return hc().memoizedState=[t,e===void 0?null:e],t},useContext:ll,useEffect:RI,useImperativeHandle:function(t,e,n){return n=n!=null?n.concat([t]):null,hS(4194308,4,cF.bind(null,e,t),n)},useLayoutEffect:function(t,e){return hS(4194308,4,t,e)},useInsertionEffect:function(t,e){return hS(4,2,t,e)},useMemo:function(t,e){var n=hc();return e=e===void 0?null:e,t=t(),n.memoizedState=[t,e],t},useReducer:function(t,e,n){var r=hc();return e=n!==void 0?n(e):e,r.memoizedState=r.baseState=e,t={pending:null,interleaved:null,lanes:0,dispatch:null,lastRenderedReducer:t,lastRenderedState:e},r.queue=t,t=t.dispatch=cX.bind(null,li,t),[r.memoizedState,t]},useRef:function(t){var e=hc();return t={current:t},e.memoizedState=t},useState:AI,useDebugValue:w3,useDeferredValue:function(t){return hc().memoizedState=t},useTransition:function(){var t=AI(!1),e=t[0];return t=lX.bind(null,t[1]),hc().memoizedState=t,[e,t]},useMutableSource:function(){},useSyncExternalStore:function(t,e,n){var r=li,i=hc();if(ei){if(n===void 0)throw Error(Ct(407));n=n()}else{if(n=e(),Ss===null)throw Error(Ct(349));rp&30||tF(r,e,n)}i.memoizedState=n;var s={value:n,getSnapshot:e};return i.queue=s,RI(rF.bind(null,r,s,t),[t]),r.flags|=2048,$v(9,nF.bind(null,r,s,n,e),void 0,null),n},useId:function(){var t=hc(),e=Ss.identifierPrefix;if(ei){var n=Su,r=bu;n=(r&~(1<<32-Hl(r)-1)).toString(32)+n,e=":"+e+"R"+n,n=Bv++,0<\/script>",t=t.removeChild(t.firstChild)):typeof r.is=="string"?t=o.createElement(n,{is:r.is}):(t=o.createElement(n),n==="select"&&(o=t,r.multiple?o.multiple=!0:r.size&&(o.size=r.size))):t=o.createElementNS(t,n),t[wc]=e,t[Fv]=r,TF(t,e,!1,!1),e.stateNode=t;e:{switch(o=TC(n,r),n){case"dialog":Xr("cancel",t),Xr("close",t),i=r;break;case"iframe":case"object":case"embed":Xr("load",t),i=r;break;case"video":case"audio":for(i=0;i$0&&(e.flags|=128,r=!0,_1(s,!1),e.lanes=4194304)}else{if(!r)if(t=JS(o),t!==null){if(e.flags|=128,r=!0,n=t.updateQueue,n!==null&&(e.updateQueue=n,e.flags|=4),_1(s,!0),s.tail===null&&s.tailMode==="hidden"&&!o.alternate&&!ei)return Hs(e),null}else 2*ki()-s.renderingStartTime>$0&&n!==1073741824&&(e.flags|=128,r=!0,_1(s,!1),e.lanes=4194304);s.isBackwards?(o.sibling=e.child,e.child=o):(n=s.last,n!==null?n.sibling=o:e.child=o,s.last=o)}return s.tail!==null?(e=s.tail,s.rendering=e,s.tail=e.sibling,s.renderingStartTime=ki(),e.sibling=null,n=oi.current,Vr(oi,r?n&1|2:n&1),e):(Hs(e),null);case 22:case 23:return R3(),r=e.memoizedState!==null,t!==null&&t.memoizedState!==null!==r&&(e.flags|=8192),r&&e.mode&1?pa&1073741824&&(Hs(e),e.subtreeFlags&6&&(e.flags|=8192)):Hs(e),null;case 24:return null;case 25:return null}throw Error(Ct(156,e.tag))}function xX(t,e){switch(c3(e),e.tag){case 1:return Ho(e.type)&&GS(),t=e.flags,t&65536?(e.flags=t&-65537|128,e):null;case 3:return B0(),Zr(Bo),Zr(qs),y3(),t=e.flags,t&65536&&!(t&128)?(e.flags=t&-65537|128,e):null;case 5:return v3(e),null;case 13:if(Zr(oi),t=e.memoizedState,t!==null&&t.dehydrated!==null){if(e.alternate===null)throw Error(Ct(340));U0()}return t=e.flags,t&65536?(e.flags=t&-65537|128,e):null;case 19:return Zr(oi),null;case 4:return B0(),null;case 10:return h3(e.type._context),null;case 22:case 23:return R3(),null;case 24:return null;default:return null}}var F_=!1,Gs=!1,_X=typeof WeakSet=="function"?WeakSet:Set,Gt=null;function i0(t,e){var n=t.ref;if(n!==null)if(typeof n=="function")try{n(null)}catch(r){bi(t,e,r)}else n.current=null}function eT(t,e,n){try{n()}catch(r){bi(t,e,r)}}var BI=!1;function bX(t,e){if(FC=$S,t=O6(),a3(t)){if("selectionStart"in t)var n={start:t.selectionStart,end:t.selectionEnd};else e:{n=(n=t.ownerDocument)&&n.defaultView||window;var r=n.getSelection&&n.getSelection();if(r&&r.rangeCount!==0){n=r.anchorNode;var i=r.anchorOffset,s=r.focusNode;r=r.focusOffset;try{n.nodeType,s.nodeType}catch{n=null;break e}var o=0,a=-1,l=-1,c=0,f=0,p=t,g=null;t:for(;;){for(var v;p!==n||i!==0&&p.nodeType!==3||(a=o+i),p!==s||r!==0&&p.nodeType!==3||(l=o+r),p.nodeType===3&&(o+=p.nodeValue.length),(v=p.firstChild)!==null;)g=p,p=v;for(;;){if(p===t)break t;if(g===n&&++c===i&&(a=o),g===s&&++f===r&&(l=o),(v=p.nextSibling)!==null)break;p=g,g=p.parentNode}p=v}n=a===-1||l===-1?null:{start:a,end:l}}else n=null}n=n||{start:0,end:0}}else n=null;for(UC={focusedElem:t,selectionRange:n},$S=!1,Gt=e;Gt!==null;)if(e=Gt,t=e.child,(e.subtreeFlags&1028)!==0&&t!==null)t.return=e,Gt=t;else for(;Gt!==null;){e=Gt;try{var x=e.alternate;if(e.flags&1024)switch(e.tag){case 0:case 11:case 15:break;case 1:if(x!==null){var _=x.memoizedProps,b=x.memoizedState,y=e.stateNode,S=y.getSnapshotBeforeUpdate(e.elementType===e.type?_:Ll(e.type,_),b);y.__reactInternalSnapshotBeforeUpdate=S}break;case 3:var w=e.stateNode.containerInfo;w.nodeType===1?w.textContent="":w.nodeType===9&&w.documentElement&&w.removeChild(w.documentElement);break;case 5:case 6:case 4:case 17:break;default:throw Error(Ct(163))}}catch(T){bi(e,e.return,T)}if(t=e.sibling,t!==null){t.return=e.return,Gt=t;break}Gt=e.return}return x=BI,BI=!1,x}function dv(t,e,n){var r=e.updateQueue;if(r=r!==null?r.lastEffect:null,r!==null){var i=r=r.next;do{if((i.tag&t)===t){var s=i.destroy;i.destroy=void 0,s!==void 0&&eT(e,n,s)}i=i.next}while(i!==r)}}function B2(t,e){if(e=e.updateQueue,e=e!==null?e.lastEffect:null,e!==null){var n=e=e.next;do{if((n.tag&t)===t){var r=n.create;n.destroy=r()}n=n.next}while(n!==e)}}function tT(t){var e=t.ref;if(e!==null){var n=t.stateNode;switch(t.tag){case 5:t=n;break;default:t=n}typeof e=="function"?e(t):e.current=t}}function PF(t){var e=t.alternate;e!==null&&(t.alternate=null,PF(e)),t.child=null,t.deletions=null,t.sibling=null,t.tag===5&&(e=t.stateNode,e!==null&&(delete e[wc],delete e[Fv],delete e[HC],delete e[rX],delete e[iX])),t.stateNode=null,t.return=null,t.dependencies=null,t.memoizedProps=null,t.memoizedState=null,t.pendingProps=null,t.stateNode=null,t.updateQueue=null}function IF(t){return t.tag===5||t.tag===3||t.tag===4}function HI(t){e:for(;;){for(;t.sibling===null;){if(t.return===null||IF(t.return))return null;t=t.return}for(t.sibling.return=t.return,t=t.sibling;t.tag!==5&&t.tag!==6&&t.tag!==18;){if(t.flags&2||t.child===null||t.tag===4)continue e;t.child.return=t,t=t.child}if(!(t.flags&2))return t.stateNode}}function nT(t,e,n){var r=t.tag;if(r===5||r===6)t=t.stateNode,e?n.nodeType===8?n.parentNode.insertBefore(t,e):n.insertBefore(t,e):(n.nodeType===8?(e=n.parentNode,e.insertBefore(t,n)):(e=n,e.appendChild(t)),n=n._reactRootContainer,n!=null||e.onclick!==null||(e.onclick=jS));else if(r!==4&&(t=t.child,t!==null))for(nT(t,e,n),t=t.sibling;t!==null;)nT(t,e,n),t=t.sibling}function rT(t,e,n){var r=t.tag;if(r===5||r===6)t=t.stateNode,e?n.insertBefore(t,e):n.appendChild(t);else if(r!==4&&(t=t.child,t!==null))for(rT(t,e,n),t=t.sibling;t!==null;)rT(t,e,n),t=t.sibling}var Is=null,Dl=!1;function bd(t,e,n){for(n=n.child;n!==null;)LF(t,e,n),n=n.sibling}function LF(t,e,n){if(Cc&&typeof Cc.onCommitFiberUnmount=="function")try{Cc.onCommitFiberUnmount(L2,n)}catch{}switch(n.tag){case 5:Gs||i0(n,e);case 6:var r=Is,i=Dl;Is=null,bd(t,e,n),Is=r,Dl=i,Is!==null&&(Dl?(t=Is,n=n.stateNode,t.nodeType===8?t.parentNode.removeChild(n):t.removeChild(n)):Is.removeChild(n.stateNode));break;case 18:Is!==null&&(Dl?(t=Is,n=n.stateNode,t.nodeType===8?AE(t.parentNode,n):t.nodeType===1&&AE(t,n),Lv(t)):AE(Is,n.stateNode));break;case 4:r=Is,i=Dl,Is=n.stateNode.containerInfo,Dl=!0,bd(t,e,n),Is=r,Dl=i;break;case 0:case 11:case 14:case 15:if(!Gs&&(r=n.updateQueue,r!==null&&(r=r.lastEffect,r!==null))){i=r=r.next;do{var s=i,o=s.destroy;s=s.tag,o!==void 0&&(s&2||s&4)&&eT(n,e,o),i=i.next}while(i!==r)}bd(t,e,n);break;case 1:if(!Gs&&(i0(n,e),r=n.stateNode,typeof r.componentWillUnmount=="function"))try{r.props=n.memoizedProps,r.state=n.memoizedState,r.componentWillUnmount()}catch(a){bi(n,e,a)}bd(t,e,n);break;case 21:bd(t,e,n);break;case 22:n.mode&1?(Gs=(r=Gs)||n.memoizedState!==null,bd(t,e,n),Gs=r):bd(t,e,n);break;default:bd(t,e,n)}}function $I(t){var e=t.updateQueue;if(e!==null){t.updateQueue=null;var n=t.stateNode;n===null&&(n=t.stateNode=new _X),e.forEach(function(r){var i=PX.bind(null,t,r);n.has(r)||(n.add(r),r.then(i,i))})}}function Al(t,e){var n=e.deletions;if(n!==null)for(var r=0;ri&&(i=o),r&=~s}if(r=i,r=ki()-r,r=(120>r?120:480>r?480:1080>r?1080:1920>r?1920:3e3>r?3e3:4320>r?4320:1960*wX(r/1960))-r,10t?16:t,qd===null)var r=!1;else{if(t=qd,qd=null,i2=0,ur&6)throw Error(Ct(331));var i=ur;for(ur|=4,Gt=t.current;Gt!==null;){var s=Gt,o=s.child;if(Gt.flags&16){var a=s.deletions;if(a!==null){for(var l=0;lki()-T3?jh(t,0):C3|=n),$o(t,e)}function BF(t,e){e===0&&(t.mode&1?(e=A_,A_<<=1,!(A_&130023424)&&(A_=4194304)):e=1);var n=go();t=ku(t,e),t!==null&&($y(t,e,n),$o(t,n))}function RX(t){var e=t.memoizedState,n=0;e!==null&&(n=e.retryLane),BF(t,n)}function PX(t,e){var n=0;switch(t.tag){case 13:var r=t.stateNode,i=t.memoizedState;i!==null&&(n=i.retryLane);break;case 19:r=t.stateNode;break;default:throw Error(Ct(314))}r!==null&&r.delete(e),BF(t,n)}var HF;HF=function(t,e,n){if(t!==null)if(t.memoizedProps!==e.pendingProps||Bo.current)Fo=!0;else{if(!(t.lanes&n)&&!(e.flags&128))return Fo=!1,vX(t,e,n);Fo=!!(t.flags&131072)}else Fo=!1,ei&&e.flags&1048576&&j6(e,ZS,e.index);switch(e.lanes=0,e.tag){case 2:var r=e.type;pS(t,e),t=e.pendingProps;var i=F0(e,qs.current);g0(e,n),i=_3(null,e,r,t,i,n);var s=b3();return e.flags|=1,typeof i=="object"&&i!==null&&typeof i.render=="function"&&i.$$typeof===void 0?(e.tag=1,e.memoizedState=null,e.updateQueue=null,Ho(r)?(s=!0,XS(e)):s=!1,e.memoizedState=i.state!==null&&i.state!==void 0?i.state:null,m3(e),i.updater=z2,e.stateNode=i,i._reactInternals=e,XC(e,r,t,n),e=YC(null,e,r,!0,s,n)):(e.tag=0,ei&&s&&l3(e),fo(null,e,i,n),e=e.child),e;case 16:r=e.elementType;e:{switch(pS(t,e),t=e.pendingProps,i=r._init,r=i(r._payload),e.type=r,i=e.tag=LX(r),t=Ll(r,t),i){case 0:e=ZC(null,e,r,t,n);break e;case 1:e=FI(null,e,r,t,n);break e;case 11:e=NI(null,e,r,t,n);break e;case 14:e=DI(null,e,r,Ll(r.type,t),n);break e}throw Error(Ct(306,r,""))}return e;case 0:return r=e.type,i=e.pendingProps,i=e.elementType===r?i:Ll(r,i),ZC(t,e,r,i,n);case 1:return r=e.type,i=e.pendingProps,i=e.elementType===r?i:Ll(r,i),FI(t,e,r,i,n);case 3:e:{if(MF(e),t===null)throw Error(Ct(387));r=e.pendingProps,s=e.memoizedState,i=s.element,K6(t,e),QS(e,r,null,n);var o=e.memoizedState;if(r=o.element,s.isDehydrated)if(s={element:r,isDehydrated:!1,cache:o.cache,pendingSuspenseBoundaries:o.pendingSuspenseBoundaries,transitions:o.transitions},e.updateQueue.baseState=s,e.memoizedState=s,e.flags&256){i=H0(Error(Ct(423)),e),e=UI(t,e,r,n,i);break e}else if(r!==i){i=H0(Error(Ct(424)),e),e=UI(t,e,r,n,i);break e}else for(_a=tf(e.stateNode.containerInfo.firstChild),Sa=e,ei=!0,Fl=null,n=Z6(e,null,r,n),e.child=n;n;)n.flags=n.flags&-3|4096,n=n.sibling;else{if(U0(),r===i){e=Ou(t,e,n);break e}fo(t,e,r,n)}e=e.child}return e;case 5:return Q6(e),t===null&&WC(e),r=e.type,i=e.pendingProps,s=t!==null?t.memoizedProps:null,o=i.children,zC(r,i)?o=null:s!==null&&zC(r,s)&&(e.flags|=32),wF(t,e),fo(t,e,o,n),e.child;case 6:return t===null&&WC(e),null;case 13:return EF(t,e,n);case 4:return g3(e,e.stateNode.containerInfo),r=e.pendingProps,t===null?e.child=z0(e,null,r,n):fo(t,e,r,n),e.child;case 11:return r=e.type,i=e.pendingProps,i=e.elementType===r?i:Ll(r,i),NI(t,e,r,i,n);case 7:return fo(t,e,e.pendingProps,n),e.child;case 8:return fo(t,e,e.pendingProps.children,n),e.child;case 12:return fo(t,e,e.pendingProps.children,n),e.child;case 10:e:{if(r=e.type._context,i=e.pendingProps,s=e.memoizedProps,o=i.value,Vr(YS,r._currentValue),r._currentValue=o,s!==null)if(Vl(s.value,o)){if(s.children===i.children&&!Bo.current){e=Ou(t,e,n);break e}}else for(s=e.child,s!==null&&(s.return=e);s!==null;){var a=s.dependencies;if(a!==null){o=s.child;for(var l=a.firstContext;l!==null;){if(l.context===r){if(s.tag===1){l=Eu(-1,n&-n),l.tag=2;var c=s.updateQueue;if(c!==null){c=c.shared;var f=c.pending;f===null?l.next=l:(l.next=f.next,f.next=l),c.pending=l}}s.lanes|=n,l=s.alternate,l!==null&&(l.lanes|=n),jC(s.return,n,e),a.lanes|=n;break}l=l.next}}else if(s.tag===10)o=s.type===e.type?null:s.child;else if(s.tag===18){if(o=s.return,o===null)throw Error(Ct(341));o.lanes|=n,a=o.alternate,a!==null&&(a.lanes|=n),jC(o,n,e),o=s.sibling}else o=s.child;if(o!==null)o.return=s;else for(o=s;o!==null;){if(o===e){o=null;break}if(s=o.sibling,s!==null){s.return=o.return,o=s;break}o=o.return}s=o}fo(t,e,i.children,n),e=e.child}return e;case 9:return i=e.type,r=e.pendingProps.children,g0(e,n),i=ll(i),r=r(i),e.flags|=1,fo(t,e,r,n),e.child;case 14:return r=e.type,i=Ll(r,e.pendingProps),i=Ll(r.type,i),DI(t,e,r,i,n);case 15:return bF(t,e,e.type,e.pendingProps,n);case 17:return r=e.type,i=e.pendingProps,i=e.elementType===r?i:Ll(r,i),pS(t,e),e.tag=1,Ho(r)?(t=!0,XS(e)):t=!1,g0(e,n),yF(e,r,i),XC(e,r,i,n),YC(null,e,r,!0,t,n);case 19:return CF(t,e,n);case 22:return SF(t,e,n)}throw Error(Ct(156,e.tag))};function $F(t,e){return m6(t,e)}function IX(t,e,n,r){this.tag=t,this.key=n,this.sibling=this.child=this.return=this.stateNode=this.type=this.elementType=null,this.index=0,this.ref=null,this.pendingProps=e,this.dependencies=this.memoizedState=this.updateQueue=this.memoizedProps=null,this.mode=r,this.subtreeFlags=this.flags=0,this.deletions=null,this.childLanes=this.lanes=0,this.alternate=null}function nl(t,e,n,r){return new IX(t,e,n,r)}function I3(t){return t=t.prototype,!(!t||!t.isReactComponent)}function LX(t){if(typeof t=="function")return I3(t)?1:0;if(t!=null){if(t=t.$$typeof,t===YA)return 11;if(t===KA)return 14}return 2}function of(t,e){var n=t.alternate;return n===null?(n=nl(t.tag,e,t.key,t.mode),n.elementType=t.elementType,n.type=t.type,n.stateNode=t.stateNode,n.alternate=t,t.alternate=n):(n.pendingProps=e,n.type=t.type,n.flags=0,n.subtreeFlags=0,n.deletions=null),n.flags=t.flags&14680064,n.childLanes=t.childLanes,n.lanes=t.lanes,n.child=t.child,n.memoizedProps=t.memoizedProps,n.memoizedState=t.memoizedState,n.updateQueue=t.updateQueue,e=t.dependencies,n.dependencies=e===null?null:{lanes:e.lanes,firstContext:e.firstContext},n.sibling=t.sibling,n.index=t.index,n.ref=t.ref,n}function vS(t,e,n,r,i,s){var o=2;if(r=t,typeof t=="function")I3(t)&&(o=1);else if(typeof t=="string")o=5;else e:switch(t){case Zm:return Gh(n.children,i,s,e);case ZA:o=8,i|=8;break;case vC:return t=nl(12,n,e,i|2),t.elementType=vC,t.lanes=s,t;case yC:return t=nl(13,n,e,i),t.elementType=yC,t.lanes=s,t;case xC:return t=nl(19,n,e,i),t.elementType=xC,t.lanes=s,t;case QD:return $2(n,i,s,e);default:if(typeof t=="object"&&t!==null)switch(t.$$typeof){case YD:o=10;break e;case KD:o=9;break e;case YA:o=11;break e;case KA:o=14;break e;case kd:o=16,r=null;break e}throw Error(Ct(130,t==null?t:typeof t,""))}return e=nl(o,n,e,i),e.elementType=t,e.type=r,e.lanes=s,e}function Gh(t,e,n,r){return t=nl(7,t,r,e),t.lanes=n,t}function $2(t,e,n,r){return t=nl(22,t,r,e),t.elementType=QD,t.lanes=n,t.stateNode={isHidden:!1},t}function DE(t,e,n){return t=nl(6,t,null,e),t.lanes=n,t}function FE(t,e,n){return e=nl(4,t.children!==null?t.children:[],t.key,e),e.lanes=n,e.stateNode={containerInfo:t.containerInfo,pendingChildren:null,implementation:t.implementation},e}function kX(t,e,n,r,i){this.tag=e,this.containerInfo=t,this.finishedWork=this.pingCache=this.current=this.pendingChildren=null,this.timeoutHandle=-1,this.callbackNode=this.pendingContext=this.context=null,this.callbackPriority=0,this.eventTimes=vE(0),this.expirationTimes=vE(-1),this.entangledLanes=this.finishedLanes=this.mutableReadLanes=this.expiredLanes=this.pingedLanes=this.suspendedLanes=this.pendingLanes=0,this.entanglements=vE(0),this.identifierPrefix=r,this.onRecoverableError=i,this.mutableSourceEagerHydrationData=null}function L3(t,e,n,r,i,s,o,a,l){return t=new kX(t,e,n,a,l),e===1?(e=1,s===!0&&(e|=8)):e=0,s=nl(3,null,null,e),t.current=s,s.stateNode=t,s.memoizedState={element:r,isDehydrated:n,cache:null,transitions:null,pendingSuspenseBoundaries:null},m3(s),t}function OX(t,e,n){var r=3"u"||typeof __REACT_DEVTOOLS_GLOBAL_HOOK__.checkDCE!="function"))try{__REACT_DEVTOOLS_GLOBAL_HOOK__.checkDCE(GF)}catch(t){console.error(t)}}GF(),GD.exports=Ra;var X2=GD.exports;const B_=By(X2);var XF,YI=X2;XF=mC.createRoot=YI.createRoot,mC.hydrateRoot=YI.hydrateRoot;function X(){return X=Object.assign?Object.assign.bind():function(t){for(var e=1;e{if(r.toString().match(/^(components|slots)$/))n[r]=X({},t[r],n[r]);else if(r.toString().match(/^(componentsProps|slotProps)$/)){const i=t[r]||{},s=e[r];n[r]={},!s||!Object.keys(s)?n[r]=i:!i||!Object.keys(i)?n[r]=s:(n[r]=X({},s),Object.keys(i).forEach(o=>{n[r][o]=D3(i[o],s[o])}))}else n[r]===void 0&&(n[r]=t[r])}),n}function zX(t){const{theme:e,name:n,props:r}=t;return!e||!e.components||!e.components[n]||!e.components[n].defaultProps?r:D3(e.components[n].defaultProps,r)}function Rt(t,e){if(t==null)return{};var n={},r=Object.keys(t),i,s;for(s=0;s=0)&&(n[i]=t[i]);return n}function yu(t){if(typeof t!="object"||t===null)return!1;const e=Object.getPrototypeOf(t);return(e===null||e===Object.prototype||Object.getPrototypeOf(e)===null)&&!(Symbol.toStringTag in t)&&!(Symbol.iterator in t)}function qF(t){if(!yu(t))return t;const e={};return Object.keys(t).forEach(n=>{e[n]=qF(t[n])}),e}function vo(t,e,n={clone:!0}){const r=n.clone?X({},t):t;return yu(t)&&yu(e)&&Object.keys(e).forEach(i=>{i!=="__proto__"&&(yu(e[i])&&i in t&&yu(t[i])?r[i]=vo(t[i],e[i],n):n.clone?r[i]=yu(e[i])?qF(e[i]):e[i]:r[i]=e[i])}),r}const BX=Object.freeze(Object.defineProperty({__proto__:null,default:vo,isPlainObject:yu},Symbol.toStringTag,{value:"Module"})),HX=["values","unit","step"],$X=t=>{const e=Object.keys(t).map(n=>({key:n,val:t[n]}))||[];return e.sort((n,r)=>n.val-r.val),e.reduce((n,r)=>X({},n,{[r.key]:r.val}),{})};function ZF(t){const{values:e={xs:0,sm:600,md:900,lg:1200,xl:1536},unit:n="px",step:r=5}=t,i=Rt(t,HX),s=$X(e),o=Object.keys(s);function a(g){return`@media (min-width:${typeof e[g]=="number"?e[g]:g}${n})`}function l(g){return`@media (max-width:${(typeof e[g]=="number"?e[g]:g)-r/100}${n})`}function c(g,v){const x=o.indexOf(v);return`@media (min-width:${typeof e[g]=="number"?e[g]:g}${n}) and (max-width:${(x!==-1&&typeof e[o[x]]=="number"?e[o[x]]:v)-r/100}${n})`}function f(g){return o.indexOf(g)+1`@media (min-width:${F3[t]}px)`};function jo(t,e,n){const r=t.theme||{};if(Array.isArray(e)){const s=r.breakpoints||KI;return e.reduce((o,a,l)=>(o[s.up(s.keys[l])]=n(e[l]),o),{})}if(typeof e=="object"){const s=r.breakpoints||KI;return Object.keys(e).reduce((o,a)=>{if(Object.keys(s.values||F3).indexOf(a)!==-1){const l=s.up(a);o[l]=n(e[a],a)}else{const l=a;o[l]=e[l]}return o},{})}return n(e)}function YF(t={}){var e;return((e=t.keys)==null?void 0:e.reduce((r,i)=>{const s=t.up(i);return r[s]={},r},{}))||{}}function KF(t,e){return t.reduce((n,r)=>{const i=n[r];return(!i||Object.keys(i).length===0)&&delete n[r],n},e)}function jX(t,...e){const n=YF(t),r=[n,...e].reduce((i,s)=>vo(i,s),{});return KF(Object.keys(n),r)}function GX(t,e){if(typeof t!="object")return{};const n={},r=Object.keys(e);return Array.isArray(t)?r.forEach((i,s)=>{s{t[i]!=null&&(n[i]=!0)}),n}function Xh({values:t,breakpoints:e,base:n}){const r=n||GX(t,e),i=Object.keys(r);if(i.length===0)return t;let s;return i.reduce((o,a,l)=>(Array.isArray(t)?(o[a]=t[l]!=null?t[l]:t[s],s=l):typeof t=="object"?(o[a]=t[a]!=null?t[a]:t[s],s=a):o[a]=t,o),{})}function op(t){let e="https://mui.com/production-error/?code="+t;for(let n=1;ni&&i[s]?i[s]:null,t);if(r!=null)return r}return e.split(".").reduce((r,i)=>r&&r[i]!=null?r[i]:null,t)}function a2(t,e,n,r=n){let i;return typeof t=="function"?i=t(n):Array.isArray(t)?i=t[n]||r:i=q2(t,n)||r,e&&(i=e(i,r,t)),i}function Ni(t){const{prop:e,cssProperty:n=t.prop,themeKey:r,transform:i}=t,s=o=>{if(o[e]==null)return null;const a=o[e],l=o.theme,c=q2(l,r)||{};return jo(o,a,p=>{let g=a2(c,i,p);return p===g&&typeof p=="string"&&(g=a2(c,i,`${e}${p==="default"?"":gt(p)}`,p)),n===!1?g:{[n]:g}})};return s.propTypes={},s.filterProps=[e],s}function ZX(t){const e={};return n=>(e[n]===void 0&&(e[n]=t(n)),e[n])}const YX={m:"margin",p:"padding"},KX={t:"Top",r:"Right",b:"Bottom",l:"Left",x:["Left","Right"],y:["Top","Bottom"]},QI={marginX:"mx",marginY:"my",paddingX:"px",paddingY:"py"},QX=ZX(t=>{if(t.length>2)if(QI[t])t=QI[t];else return[t];const[e,n]=t.split(""),r=YX[e],i=KX[n]||"";return Array.isArray(i)?i.map(s=>r+s):[r+i]}),U3=["m","mt","mr","mb","ml","mx","my","margin","marginTop","marginRight","marginBottom","marginLeft","marginX","marginY","marginInline","marginInlineStart","marginInlineEnd","marginBlock","marginBlockStart","marginBlockEnd"],z3=["p","pt","pr","pb","pl","px","py","padding","paddingTop","paddingRight","paddingBottom","paddingLeft","paddingX","paddingY","paddingInline","paddingInlineStart","paddingInlineEnd","paddingBlock","paddingBlockStart","paddingBlockEnd"];[...U3,...z3];function Gy(t,e,n,r){var i;const s=(i=q2(t,e,!1))!=null?i:n;return typeof s=="number"?o=>typeof o=="string"?o:s*o:Array.isArray(s)?o=>typeof o=="string"?o:s[o]:typeof s=="function"?s:()=>{}}function B3(t){return Gy(t,"spacing",8)}function ap(t,e){if(typeof e=="string"||e==null)return e;const n=Math.abs(e),r=t(n);return e>=0?r:typeof r=="number"?-r:`-${r}`}function JX(t,e){return n=>t.reduce((r,i)=>(r[i]=ap(e,n),r),{})}function eq(t,e,n,r){if(e.indexOf(n)===-1)return null;const i=QX(n),s=JX(i,r),o=t[n];return jo(t,o,s)}function QF(t,e){const n=B3(t.theme);return Object.keys(t).map(r=>eq(t,e,r,n)).reduce(pv,{})}function yi(t){return QF(t,U3)}yi.propTypes={};yi.filterProps=U3;function xi(t){return QF(t,z3)}xi.propTypes={};xi.filterProps=z3;function tq(t=8){if(t.mui)return t;const e=B3({spacing:t}),n=(...r)=>(r.length===0?[1]:r).map(s=>{const o=e(s);return typeof o=="number"?`${o}px`:o}).join(" ");return n.mui=!0,n}function Z2(...t){const e=t.reduce((r,i)=>(i.filterProps.forEach(s=>{r[s]=i}),r),{}),n=r=>Object.keys(r).reduce((i,s)=>e[s]?pv(i,e[s](r)):i,{});return n.propTypes={},n.filterProps=t.reduce((r,i)=>r.concat(i.filterProps),[]),n}function tl(t){return typeof t!="number"?t:`${t}px solid`}function ml(t,e){return Ni({prop:t,themeKey:"borders",transform:e})}const nq=ml("border",tl),rq=ml("borderTop",tl),iq=ml("borderRight",tl),sq=ml("borderBottom",tl),oq=ml("borderLeft",tl),aq=ml("borderColor"),lq=ml("borderTopColor"),cq=ml("borderRightColor"),uq=ml("borderBottomColor"),dq=ml("borderLeftColor"),fq=ml("outline",tl),hq=ml("outlineColor"),Y2=t=>{if(t.borderRadius!==void 0&&t.borderRadius!==null){const e=Gy(t.theme,"shape.borderRadius",4),n=r=>({borderRadius:ap(e,r)});return jo(t,t.borderRadius,n)}return null};Y2.propTypes={};Y2.filterProps=["borderRadius"];Z2(nq,rq,iq,sq,oq,aq,lq,cq,uq,dq,Y2,fq,hq);const K2=t=>{if(t.gap!==void 0&&t.gap!==null){const e=Gy(t.theme,"spacing",8),n=r=>({gap:ap(e,r)});return jo(t,t.gap,n)}return null};K2.propTypes={};K2.filterProps=["gap"];const Q2=t=>{if(t.columnGap!==void 0&&t.columnGap!==null){const e=Gy(t.theme,"spacing",8),n=r=>({columnGap:ap(e,r)});return jo(t,t.columnGap,n)}return null};Q2.propTypes={};Q2.filterProps=["columnGap"];const J2=t=>{if(t.rowGap!==void 0&&t.rowGap!==null){const e=Gy(t.theme,"spacing",8),n=r=>({rowGap:ap(e,r)});return jo(t,t.rowGap,n)}return null};J2.propTypes={};J2.filterProps=["rowGap"];const pq=Ni({prop:"gridColumn"}),mq=Ni({prop:"gridRow"}),gq=Ni({prop:"gridAutoFlow"}),vq=Ni({prop:"gridAutoColumns"}),yq=Ni({prop:"gridAutoRows"}),xq=Ni({prop:"gridTemplateColumns"}),_q=Ni({prop:"gridTemplateRows"}),bq=Ni({prop:"gridTemplateAreas"}),Sq=Ni({prop:"gridArea"});Z2(K2,Q2,J2,pq,mq,gq,vq,yq,xq,_q,bq,Sq);function y0(t,e){return e==="grey"?e:t}const wq=Ni({prop:"color",themeKey:"palette",transform:y0}),Mq=Ni({prop:"bgcolor",cssProperty:"backgroundColor",themeKey:"palette",transform:y0}),Eq=Ni({prop:"backgroundColor",themeKey:"palette",transform:y0});Z2(wq,Mq,Eq);function ya(t){return t<=1&&t!==0?`${t*100}%`:t}const Cq=Ni({prop:"width",transform:ya}),H3=t=>{if(t.maxWidth!==void 0&&t.maxWidth!==null){const e=n=>{var r,i;const s=((r=t.theme)==null||(r=r.breakpoints)==null||(r=r.values)==null?void 0:r[n])||F3[n];return s?((i=t.theme)==null||(i=i.breakpoints)==null?void 0:i.unit)!=="px"?{maxWidth:`${s}${t.theme.breakpoints.unit}`}:{maxWidth:s}:{maxWidth:ya(n)}};return jo(t,t.maxWidth,e)}return null};H3.filterProps=["maxWidth"];const Tq=Ni({prop:"minWidth",transform:ya}),Aq=Ni({prop:"height",transform:ya}),Rq=Ni({prop:"maxHeight",transform:ya}),Pq=Ni({prop:"minHeight",transform:ya});Ni({prop:"size",cssProperty:"width",transform:ya});Ni({prop:"size",cssProperty:"height",transform:ya});const Iq=Ni({prop:"boxSizing"});Z2(Cq,H3,Tq,Aq,Rq,Pq,Iq);const Lq={border:{themeKey:"borders",transform:tl},borderTop:{themeKey:"borders",transform:tl},borderRight:{themeKey:"borders",transform:tl},borderBottom:{themeKey:"borders",transform:tl},borderLeft:{themeKey:"borders",transform:tl},borderColor:{themeKey:"palette"},borderTopColor:{themeKey:"palette"},borderRightColor:{themeKey:"palette"},borderBottomColor:{themeKey:"palette"},borderLeftColor:{themeKey:"palette"},outline:{themeKey:"borders",transform:tl},outlineColor:{themeKey:"palette"},borderRadius:{themeKey:"shape.borderRadius",style:Y2},color:{themeKey:"palette",transform:y0},bgcolor:{themeKey:"palette",cssProperty:"backgroundColor",transform:y0},backgroundColor:{themeKey:"palette",transform:y0},p:{style:xi},pt:{style:xi},pr:{style:xi},pb:{style:xi},pl:{style:xi},px:{style:xi},py:{style:xi},padding:{style:xi},paddingTop:{style:xi},paddingRight:{style:xi},paddingBottom:{style:xi},paddingLeft:{style:xi},paddingX:{style:xi},paddingY:{style:xi},paddingInline:{style:xi},paddingInlineStart:{style:xi},paddingInlineEnd:{style:xi},paddingBlock:{style:xi},paddingBlockStart:{style:xi},paddingBlockEnd:{style:xi},m:{style:yi},mt:{style:yi},mr:{style:yi},mb:{style:yi},ml:{style:yi},mx:{style:yi},my:{style:yi},margin:{style:yi},marginTop:{style:yi},marginRight:{style:yi},marginBottom:{style:yi},marginLeft:{style:yi},marginX:{style:yi},marginY:{style:yi},marginInline:{style:yi},marginInlineStart:{style:yi},marginInlineEnd:{style:yi},marginBlock:{style:yi},marginBlockStart:{style:yi},marginBlockEnd:{style:yi},displayPrint:{cssProperty:!1,transform:t=>({"@media print":{display:t}})},display:{},overflow:{},textOverflow:{},visibility:{},whiteSpace:{},flexBasis:{},flexDirection:{},flexWrap:{},justifyContent:{},alignItems:{},alignContent:{},order:{},flex:{},flexGrow:{},flexShrink:{},alignSelf:{},justifyItems:{},justifySelf:{},gap:{style:K2},rowGap:{style:J2},columnGap:{style:Q2},gridColumn:{},gridRow:{},gridAutoFlow:{},gridAutoColumns:{},gridAutoRows:{},gridTemplateColumns:{},gridTemplateRows:{},gridTemplateAreas:{},gridArea:{},position:{},zIndex:{themeKey:"zIndex"},top:{},right:{},bottom:{},left:{},boxShadow:{themeKey:"shadows"},width:{transform:ya},maxWidth:{style:H3},minWidth:{transform:ya},height:{transform:ya},maxHeight:{transform:ya},minHeight:{transform:ya},boxSizing:{},fontFamily:{themeKey:"typography"},fontSize:{themeKey:"typography"},fontStyle:{themeKey:"typography"},fontWeight:{themeKey:"typography"},letterSpacing:{},textTransform:{},lineHeight:{},textAlign:{},typography:{cssProperty:!1,themeKey:"typography"}},Xy=Lq;function kq(...t){const e=t.reduce((r,i)=>r.concat(Object.keys(i)),[]),n=new Set(e);return t.every(r=>n.size===Object.keys(r).length)}function Oq(t,e){return typeof t=="function"?t(e):t}function JF(){function t(n,r,i,s){const o={[n]:r,theme:i},a=s[n];if(!a)return{[n]:r};const{cssProperty:l=n,themeKey:c,transform:f,style:p}=a;if(r==null)return null;if(c==="typography"&&r==="inherit")return{[n]:r};const g=q2(i,c)||{};return p?p(o):jo(o,r,x=>{let _=a2(g,f,x);return x===_&&typeof x=="string"&&(_=a2(g,f,`${n}${x==="default"?"":gt(x)}`,x)),l===!1?_:{[l]:_}})}function e(n){var r;const{sx:i,theme:s={}}=n||{};if(!i)return null;const o=(r=s.unstable_sxConfig)!=null?r:Xy;function a(l){let c=l;if(typeof l=="function")c=l(s);else if(typeof l!="object")return l;if(!c)return null;const f=YF(s.breakpoints),p=Object.keys(f);let g=f;return Object.keys(c).forEach(v=>{const x=Oq(c[v],s);if(x!=null)if(typeof x=="object")if(o[v])g=pv(g,t(v,x,s,o));else{const _=jo({theme:s},x,b=>({[v]:b}));kq(_,x)?g[v]=e({sx:x,theme:s}):g=pv(g,_)}else g=pv(g,t(v,x,s,o))}),KF(p,g)}return Array.isArray(i)?i.map(a):a(i)}return e}const cg=JF();cg.filterProps=["sx"];function e8(t,e){const n=this;return n.vars&&typeof n.getColorSchemeSelector=="function"?{[n.getColorSchemeSelector(t).replace(/(\[[^\]]+\])/,"*:where($1)")]:e}:n.palette.mode===t?e:{}}const Nq=["breakpoints","palette","spacing","shape"];function qy(t={},...e){const{breakpoints:n={},palette:r={},spacing:i,shape:s={}}=t,o=Rt(t,Nq),a=ZF(n),l=tq(i);let c=vo({breakpoints:a,direction:"ltr",components:{},palette:X({mode:"light"},r),spacing:l,shape:X({},WX,s)},o);return c.applyStyles=e8,c=e.reduce((f,p)=>vo(f,p),c),c.unstable_sxConfig=X({},Xy,o==null?void 0:o.unstable_sxConfig),c.unstable_sx=function(p){return cg({sx:p,theme:this})},c}const Dq=Object.freeze(Object.defineProperty({__proto__:null,default:qy,private_createBreakpoints:ZF,unstable_applyStyles:e8},Symbol.toStringTag,{value:"Module"}));function t8(t){var e=Object.create(null);return function(n){return e[n]===void 0&&(e[n]=t(n)),e[n]}}var Fq=/^((children|dangerouslySetInnerHTML|key|ref|autoFocus|defaultValue|defaultChecked|innerHTML|suppressContentEditableWarning|suppressHydrationWarning|valueLink|abbr|accept|acceptCharset|accessKey|action|allow|allowUserMedia|allowPaymentRequest|allowFullScreen|allowTransparency|alt|async|autoComplete|autoPlay|capture|cellPadding|cellSpacing|challenge|charSet|checked|cite|classID|className|cols|colSpan|content|contentEditable|contextMenu|controls|controlsList|coords|crossOrigin|data|dateTime|decoding|default|defer|dir|disabled|disablePictureInPicture|disableRemotePlayback|download|draggable|encType|enterKeyHint|form|formAction|formEncType|formMethod|formNoValidate|formTarget|frameBorder|headers|height|hidden|high|href|hrefLang|htmlFor|httpEquiv|id|inputMode|integrity|is|keyParams|keyType|kind|label|lang|list|loading|loop|low|marginHeight|marginWidth|max|maxLength|media|mediaGroup|method|min|minLength|multiple|muted|name|nonce|noValidate|open|optimum|pattern|placeholder|playsInline|poster|preload|profile|radioGroup|readOnly|referrerPolicy|rel|required|reversed|role|rows|rowSpan|sandbox|scope|scoped|scrolling|seamless|selected|shape|size|sizes|slot|span|spellCheck|src|srcDoc|srcLang|srcSet|start|step|style|summary|tabIndex|target|title|translate|type|useMap|value|width|wmode|wrap|about|datatype|inlist|prefix|property|resource|typeof|vocab|autoCapitalize|autoCorrect|autoSave|color|incremental|fallback|inert|itemProp|itemScope|itemType|itemID|itemRef|on|option|results|security|unselectable|accentHeight|accumulate|additive|alignmentBaseline|allowReorder|alphabetic|amplitude|arabicForm|ascent|attributeName|attributeType|autoReverse|azimuth|baseFrequency|baselineShift|baseProfile|bbox|begin|bias|by|calcMode|capHeight|clip|clipPathUnits|clipPath|clipRule|colorInterpolation|colorInterpolationFilters|colorProfile|colorRendering|contentScriptType|contentStyleType|cursor|cx|cy|d|decelerate|descent|diffuseConstant|direction|display|divisor|dominantBaseline|dur|dx|dy|edgeMode|elevation|enableBackground|end|exponent|externalResourcesRequired|fill|fillOpacity|fillRule|filter|filterRes|filterUnits|floodColor|floodOpacity|focusable|fontFamily|fontSize|fontSizeAdjust|fontStretch|fontStyle|fontVariant|fontWeight|format|from|fr|fx|fy|g1|g2|glyphName|glyphOrientationHorizontal|glyphOrientationVertical|glyphRef|gradientTransform|gradientUnits|hanging|horizAdvX|horizOriginX|ideographic|imageRendering|in|in2|intercept|k|k1|k2|k3|k4|kernelMatrix|kernelUnitLength|kerning|keyPoints|keySplines|keyTimes|lengthAdjust|letterSpacing|lightingColor|limitingConeAngle|local|markerEnd|markerMid|markerStart|markerHeight|markerUnits|markerWidth|mask|maskContentUnits|maskUnits|mathematical|mode|numOctaves|offset|opacity|operator|order|orient|orientation|origin|overflow|overlinePosition|overlineThickness|panose1|paintOrder|pathLength|patternContentUnits|patternTransform|patternUnits|pointerEvents|points|pointsAtX|pointsAtY|pointsAtZ|preserveAlpha|preserveAspectRatio|primitiveUnits|r|radius|refX|refY|renderingIntent|repeatCount|repeatDur|requiredExtensions|requiredFeatures|restart|result|rotate|rx|ry|scale|seed|shapeRendering|slope|spacing|specularConstant|specularExponent|speed|spreadMethod|startOffset|stdDeviation|stemh|stemv|stitchTiles|stopColor|stopOpacity|strikethroughPosition|strikethroughThickness|string|stroke|strokeDasharray|strokeDashoffset|strokeLinecap|strokeLinejoin|strokeMiterlimit|strokeOpacity|strokeWidth|surfaceScale|systemLanguage|tableValues|targetX|targetY|textAnchor|textDecoration|textRendering|textLength|to|transform|u1|u2|underlinePosition|underlineThickness|unicode|unicodeBidi|unicodeRange|unitsPerEm|vAlphabetic|vHanging|vIdeographic|vMathematical|values|vectorEffect|version|vertAdvY|vertOriginX|vertOriginY|viewBox|viewTarget|visibility|widths|wordSpacing|writingMode|x|xHeight|x1|x2|xChannelSelector|xlinkActuate|xlinkArcrole|xlinkHref|xlinkRole|xlinkShow|xlinkTitle|xlinkType|xmlBase|xmlns|xmlnsXlink|xmlLang|xmlSpace|y|y1|y2|yChannelSelector|z|zoomAndPan|for|class|autofocus)|(([Dd][Aa][Tt][Aa]|[Aa][Rr][Ii][Aa]|x)-.*))$/,Uq=t8(function(t){return Fq.test(t)||t.charCodeAt(0)===111&&t.charCodeAt(1)===110&&t.charCodeAt(2)<91});function zq(t){if(t.sheet)return t.sheet;for(var e=0;e0?Ls(ug,--Go):0,V0--,Vi===10&&(V0=1,tw--),Vi}function wa(){return Vi=Go2||jv(Vi)>3?"":" "}function Qq(t,e){for(;--e&&wa()&&!(Vi<48||Vi>102||Vi>57&&Vi<65||Vi>70&&Vi<97););return Zy(t,yS()+(e<6&&Ac()==32&&wa()==32))}function cT(t){for(;wa();)switch(Vi){case t:return Go;case 34:case 39:t!==34&&t!==39&&cT(Vi);break;case 40:t===41&&cT(t);break;case 92:wa();break}return Go}function Jq(t,e){for(;wa()&&t+Vi!==57;)if(t+Vi===84&&Ac()===47)break;return"/*"+Zy(e,Go-1)+"*"+ew(t===47?t:wa())}function eZ(t){for(;!jv(Ac());)wa();return Zy(t,Go)}function tZ(t){return a8(_S("",null,null,null,[""],t=o8(t),0,[0],t))}function _S(t,e,n,r,i,s,o,a,l){for(var c=0,f=0,p=o,g=0,v=0,x=0,_=1,b=1,y=1,S=0,w="",T=i,L=s,R=r,P=w;b;)switch(x=S,S=wa()){case 40:if(x!=108&&Ls(P,p-1)==58){lT(P+=pr(xS(S),"&","&\f"),"&\f")!=-1&&(y=-1);break}case 34:case 39:case 91:P+=xS(S);break;case 9:case 10:case 13:case 32:P+=Kq(x);break;case 92:P+=Qq(yS()-1,7);continue;case 47:switch(Ac()){case 42:case 47:H_(nZ(Jq(wa(),yS()),e,n),l);break;default:P+="/"}break;case 123*_:a[c++]=bc(P)*y;case 125*_:case 59:case 0:switch(S){case 0:case 125:b=0;case 59+f:y==-1&&(P=pr(P,/\f/g,"")),v>0&&bc(P)-p&&H_(v>32?eL(P+";",r,n,p-1):eL(pr(P," ","")+";",r,n,p-2),l);break;case 59:P+=";";default:if(H_(R=JI(P,e,n,c,f,i,a,w,T=[],L=[],p),s),S===123)if(f===0)_S(P,e,R,R,T,s,p,a,L);else switch(g===99&&Ls(P,3)===110?100:g){case 100:case 108:case 109:case 115:_S(t,R,R,r&&H_(JI(t,R,R,0,0,i,a,w,i,T=[],p),L),i,L,p,a,r?T:L);break;default:_S(P,R,R,R,[""],L,0,a,L)}}c=f=v=0,_=y=1,w=P="",p=o;break;case 58:p=1+bc(P),v=x;default:if(_<1){if(S==123)--_;else if(S==125&&_++==0&&Yq()==125)continue}switch(P+=ew(S),S*_){case 38:y=f>0?1:(P+="\f",-1);break;case 44:a[c++]=(bc(P)-1)*y,y=1;break;case 64:Ac()===45&&(P+=xS(wa())),g=Ac(),f=p=bc(w=P+=eZ(yS())),S++;break;case 45:x===45&&bc(P)==2&&(_=0)}}return s}function JI(t,e,n,r,i,s,o,a,l,c,f){for(var p=i-1,g=i===0?s:[""],v=W3(g),x=0,_=0,b=0;x0?g[y]+" "+S:pr(S,/&\f/g,g[y])))&&(l[b++]=w);return nw(t,e,n,i===0?$3:a,l,c,f)}function nZ(t,e,n){return nw(t,e,n,n8,ew(Zq()),Wv(t,2,-2),0)}function eL(t,e,n,r){return nw(t,e,n,V3,Wv(t,0,r),Wv(t,r+1,-1),r)}function x0(t,e){for(var n="",r=W3(t),i=0;i6)switch(Ls(t,e+1)){case 109:if(Ls(t,e+4)!==45)break;case 102:return pr(t,/(.+:)(.+)-([^]+)/,"$1"+hr+"$2-$3$1"+l2+(Ls(t,e+3)==108?"$3":"$2-$3"))+t;case 115:return~lT(t,"stretch")?l8(pr(t,"stretch","fill-available"),e)+t:t}break;case 4949:if(Ls(t,e+1)!==115)break;case 6444:switch(Ls(t,bc(t)-3-(~lT(t,"!important")&&10))){case 107:return pr(t,":",":"+hr)+t;case 101:return pr(t,/(.+:)([^;!]+)(;|!.+)?/,"$1"+hr+(Ls(t,14)===45?"inline-":"")+"box$3$1"+hr+"$2$3$1"+js+"$2box$3")+t}break;case 5936:switch(Ls(t,e+11)){case 114:return hr+t+js+pr(t,/[svh]\w+-[tblr]{2}/,"tb")+t;case 108:return hr+t+js+pr(t,/[svh]\w+-[tblr]{2}/,"tb-rl")+t;case 45:return hr+t+js+pr(t,/[svh]\w+-[tblr]{2}/,"lr")+t}return hr+t+js+t+t}return t}var dZ=function(e,n,r,i){if(e.length>-1&&!e.return)switch(e.type){case V3:e.return=l8(e.value,e.length);break;case r8:return x0([S1(e,{value:pr(e.value,"@","@"+hr)})],i);case $3:if(e.length)return qq(e.props,function(s){switch(Xq(s,/(::plac\w+|:read-\w+)/)){case":read-only":case":read-write":return x0([S1(e,{props:[pr(s,/:(read-\w+)/,":"+l2+"$1")]})],i);case"::placeholder":return x0([S1(e,{props:[pr(s,/:(plac\w+)/,":"+hr+"input-$1")]}),S1(e,{props:[pr(s,/:(plac\w+)/,":"+l2+"$1")]}),S1(e,{props:[pr(s,/:(plac\w+)/,js+"input-$1")]})],i)}return""})}},fZ=[dZ],c8=function(e){var n=e.key;if(n==="css"){var r=document.querySelectorAll("style[data-emotion]:not([data-s])");Array.prototype.forEach.call(r,function(_){var b=_.getAttribute("data-emotion");b.indexOf(" ")!==-1&&(document.head.appendChild(_),_.setAttribute("data-s",""))})}var i=e.stylisPlugins||fZ,s={},o,a=[];o=e.container||document.head,Array.prototype.forEach.call(document.querySelectorAll('style[data-emotion^="'+n+' "]'),function(_){for(var b=_.getAttribute("data-emotion").split(" "),y=1;y=4;++r,i-=4)n=t.charCodeAt(r)&255|(t.charCodeAt(++r)&255)<<8|(t.charCodeAt(++r)&255)<<16|(t.charCodeAt(++r)&255)<<24,n=(n&65535)*1540483477+((n>>>16)*59797<<16),n^=n>>>24,e=(n&65535)*1540483477+((n>>>16)*59797<<16)^(e&65535)*1540483477+((e>>>16)*59797<<16);switch(i){case 3:e^=(t.charCodeAt(r+2)&255)<<16;case 2:e^=(t.charCodeAt(r+1)&255)<<8;case 1:e^=t.charCodeAt(r)&255,e=(e&65535)*1540483477+((e>>>16)*59797<<16)}return e^=e>>>13,e=(e&65535)*1540483477+((e>>>16)*59797<<16),((e^e>>>15)>>>0).toString(36)}var MZ={animationIterationCount:1,aspectRatio:1,borderImageOutset:1,borderImageSlice:1,borderImageWidth:1,boxFlex:1,boxFlexGroup:1,boxOrdinalGroup:1,columnCount:1,columns:1,flex:1,flexGrow:1,flexPositive:1,flexShrink:1,flexNegative:1,flexOrder:1,gridRow:1,gridRowEnd:1,gridRowSpan:1,gridRowStart:1,gridColumn:1,gridColumnEnd:1,gridColumnSpan:1,gridColumnStart:1,msGridRow:1,msGridRowSpan:1,msGridColumn:1,msGridColumnSpan:1,fontWeight:1,lineHeight:1,opacity:1,order:1,orphans:1,tabSize:1,widows:1,zIndex:1,zoom:1,WebkitLineClamp:1,fillOpacity:1,floodOpacity:1,stopOpacity:1,strokeDasharray:1,strokeDashoffset:1,strokeMiterlimit:1,strokeOpacity:1,strokeWidth:1},EZ=/[A-Z]|^ms/g,CZ=/_EMO_([^_]+?)_([^]*?)_EMO_/g,g8=function(e){return e.charCodeAt(1)===45},nL=function(e){return e!=null&&typeof e!="boolean"},UE=t8(function(t){return g8(t)?t:t.replace(EZ,"-$&").toLowerCase()}),rL=function(e,n){switch(e){case"animation":case"animationName":if(typeof n=="string")return n.replace(CZ,function(r,i,s){return Sc={name:i,styles:s,next:Sc},i})}return MZ[e]!==1&&!g8(e)&&typeof n=="number"&&n!==0?n+"px":n};function Gv(t,e,n){if(n==null)return"";if(n.__emotion_styles!==void 0)return n;switch(typeof n){case"boolean":return"";case"object":{if(n.anim===1)return Sc={name:n.name,styles:n.styles,next:Sc},n.name;if(n.styles!==void 0){var r=n.next;if(r!==void 0)for(;r!==void 0;)Sc={name:r.name,styles:r.styles,next:Sc},r=r.next;var i=n.styles+";";return i}return TZ(t,e,n)}case"function":{if(t!==void 0){var s=Sc,o=n(t);return Sc=s,Gv(t,e,o)}break}}if(e==null)return n;var a=e[n];return a!==void 0?a:n}function TZ(t,e,n){var r="";if(Array.isArray(n))for(var i=0;i96?LZ:kZ},lL=function(e,n,r){var i;if(n){var s=n.shouldForwardProp;i=e.__emotion_forwardProp&&s?function(o){return e.__emotion_forwardProp(o)&&s(o)}:s}return typeof i!="function"&&r&&(i=e.__emotion_forwardProp),i},OZ=function(e){var n=e.cache,r=e.serialized,i=e.isStringTag;return p8(n,r,i),RZ(function(){return m8(n,r,i)}),null},NZ=function t(e,n){var r=e.__emotion_real===e,i=r&&e.__emotion_base||e,s,o;n!==void 0&&(s=n.label,o=n.target);var a=lL(e,n,r),l=a||aL(i),c=!l("as");return function(){var f=arguments,p=r&&e.__emotion_styles!==void 0?e.__emotion_styles.slice(0):[];if(s!==void 0&&p.push("label:"+s+";"),f[0]==null||f[0].raw===void 0)p.push.apply(p,f);else{p.push(f[0][0]);for(var g=f.length,v=1;ve(UZ(i)?n:i):e;return C.jsx(IZ,{styles:r})}function Z3(t,e){return uT(t,e)}const S8=(t,e)=>{Array.isArray(t.__emotion_styles)&&(t.__emotion_styles=e(t.__emotion_styles))},zZ=Object.freeze(Object.defineProperty({__proto__:null,GlobalStyles:b8,StyledEngineProvider:FZ,ThemeContext:Yy,css:hw,default:Z3,internal_processStyles:S8,keyframes:dg},Symbol.toStringTag,{value:"Module"}));function BZ(t){return Object.keys(t).length===0}function w8(t=null){const e=D.useContext(Yy);return!e||BZ(e)?t:e}const HZ=qy();function pw(t=HZ){return w8(t)}function M8({props:t,name:e,defaultTheme:n,themeId:r}){let i=pw(n);return r&&(i=i[r]||i),zX({theme:i,name:e,props:t})}const $Z=["sx"],VZ=t=>{var e,n;const r={systemProps:{},otherProps:{}},i=(e=t==null||(n=t.theme)==null?void 0:n.unstable_sxConfig)!=null?e:Xy;return Object.keys(t).forEach(s=>{i[s]?r.systemProps[s]=t[s]:r.otherProps[s]=t[s]}),r};function Ky(t){const{sx:e}=t,n=Rt(t,$Z),{systemProps:r,otherProps:i}=VZ(n);let s;return Array.isArray(e)?s=[r,...e]:typeof e=="function"?s=(...o)=>{const a=e(...o);return yu(a)?X({},r,a):r}:s=X({},r,e),X({},i,{sx:s})}const WZ=Object.freeze(Object.defineProperty({__proto__:null,default:cg,extendSxProp:Ky,unstable_createStyleFunctionSx:JF,unstable_defaultSxConfig:Xy},Symbol.toStringTag,{value:"Module"})),cL=t=>t,jZ=()=>{let t=cL;return{configure(e){t=e},generate(e){return t(e)},reset(){t=cL}}},GZ=jZ(),Y3=GZ,E8={active:"active",checked:"checked",completed:"completed",disabled:"disabled",error:"error",expanded:"expanded",focused:"focused",focusVisible:"focusVisible",open:"open",readOnly:"readOnly",required:"required",selected:"selected"};function bn(t,e,n="Mui"){const r=E8[e];return r?`${n}-${r}`:`${Y3.generate(t)}-${e}`}function XZ(t,e){return X({toolbar:{minHeight:56,[t.up("xs")]:{"@media (orientation: landscape)":{minHeight:48}},[t.up("sm")]:{minHeight:64}}},e)}var Di={},C8={exports:{}};(function(t){function e(n){return n&&n.__esModule?n:{default:n}}t.exports=e,t.exports.__esModule=!0,t.exports.default=t.exports})(C8);var pf=C8.exports;const qZ=Uu(XX);function $m(t,e=Number.MIN_SAFE_INTEGER,n=Number.MAX_SAFE_INTEGER){return Math.max(e,Math.min(t,n))}const ZZ=Object.freeze(Object.defineProperty({__proto__:null,default:$m},Symbol.toStringTag,{value:"Module"})),YZ=Uu(ZZ);var T8=pf;Object.defineProperty(Di,"__esModule",{value:!0});var qn=Di.alpha=I8;Di.blend=aY;Di.colorChannel=void 0;var Xv=Di.darken=Q3;Di.decomposeColor=ul;Di.emphasize=L8;var KZ=Di.getContrastRatio=nY;Di.getLuminance=c2;Di.hexToRgb=A8;Di.hslToRgb=P8;var qv=Di.lighten=J3;Di.private_safeAlpha=rY;Di.private_safeColorChannel=void 0;Di.private_safeDarken=iY;Di.private_safeEmphasize=oY;Di.private_safeLighten=sY;Di.recomposeColor=fg;Di.rgbToHex=tY;var uL=T8(qZ),QZ=T8(YZ);function K3(t,e=0,n=1){return(0,QZ.default)(t,e,n)}function A8(t){t=t.slice(1);const e=new RegExp(`.{1,${t.length>=6?2:1}}`,"g");let n=t.match(e);return n&&n[0].length===1&&(n=n.map(r=>r+r)),n?`rgb${n.length===4?"a":""}(${n.map((r,i)=>i<3?parseInt(r,16):Math.round(parseInt(r,16)/255*1e3)/1e3).join(", ")})`:""}function JZ(t){const e=t.toString(16);return e.length===1?`0${e}`:e}function ul(t){if(t.type)return t;if(t.charAt(0)==="#")return ul(A8(t));const e=t.indexOf("("),n=t.substring(0,e);if(["rgb","rgba","hsl","hsla","color"].indexOf(n)===-1)throw new Error((0,uL.default)(9,t));let r=t.substring(e+1,t.length-1),i;if(n==="color"){if(r=r.split(" "),i=r.shift(),r.length===4&&r[3].charAt(0)==="/"&&(r[3]=r[3].slice(1)),["srgb","display-p3","a98-rgb","prophoto-rgb","rec-2020"].indexOf(i)===-1)throw new Error((0,uL.default)(10,i))}else r=r.split(",");return r=r.map(s=>parseFloat(s)),{type:n,values:r,colorSpace:i}}const R8=t=>{const e=ul(t);return e.values.slice(0,3).map((n,r)=>e.type.indexOf("hsl")!==-1&&r!==0?`${n}%`:n).join(" ")};Di.colorChannel=R8;const eY=(t,e)=>{try{return R8(t)}catch{return t}};Di.private_safeColorChannel=eY;function fg(t){const{type:e,colorSpace:n}=t;let{values:r}=t;return e.indexOf("rgb")!==-1?r=r.map((i,s)=>s<3?parseInt(i,10):i):e.indexOf("hsl")!==-1&&(r[1]=`${r[1]}%`,r[2]=`${r[2]}%`),e.indexOf("color")!==-1?r=`${n} ${r.join(" ")}`:r=`${r.join(", ")}`,`${e}(${r})`}function tY(t){if(t.indexOf("#")===0)return t;const{values:e}=ul(t);return`#${e.map((n,r)=>JZ(r===3?Math.round(255*n):n)).join("")}`}function P8(t){t=ul(t);const{values:e}=t,n=e[0],r=e[1]/100,i=e[2]/100,s=r*Math.min(i,1-i),o=(c,f=(c+n/30)%12)=>i-s*Math.max(Math.min(f-3,9-f,1),-1);let a="rgb";const l=[Math.round(o(0)*255),Math.round(o(8)*255),Math.round(o(4)*255)];return t.type==="hsla"&&(a+="a",l.push(e[3])),fg({type:a,values:l})}function c2(t){t=ul(t);let e=t.type==="hsl"||t.type==="hsla"?ul(P8(t)).values:t.values;return e=e.map(n=>(t.type!=="color"&&(n/=255),n<=.03928?n/12.92:((n+.055)/1.055)**2.4)),Number((.2126*e[0]+.7152*e[1]+.0722*e[2]).toFixed(3))}function nY(t,e){const n=c2(t),r=c2(e);return(Math.max(n,r)+.05)/(Math.min(n,r)+.05)}function I8(t,e){return t=ul(t),e=K3(e),(t.type==="rgb"||t.type==="hsl")&&(t.type+="a"),t.type==="color"?t.values[3]=`/${e}`:t.values[3]=e,fg(t)}function rY(t,e,n){try{return I8(t,e)}catch{return t}}function Q3(t,e){if(t=ul(t),e=K3(e),t.type.indexOf("hsl")!==-1)t.values[2]*=1-e;else if(t.type.indexOf("rgb")!==-1||t.type.indexOf("color")!==-1)for(let n=0;n<3;n+=1)t.values[n]*=1-e;return fg(t)}function iY(t,e,n){try{return Q3(t,e)}catch{return t}}function J3(t,e){if(t=ul(t),e=K3(e),t.type.indexOf("hsl")!==-1)t.values[2]+=(100-t.values[2])*e;else if(t.type.indexOf("rgb")!==-1)for(let n=0;n<3;n+=1)t.values[n]+=(255-t.values[n])*e;else if(t.type.indexOf("color")!==-1)for(let n=0;n<3;n+=1)t.values[n]+=(1-t.values[n])*e;return fg(t)}function sY(t,e,n){try{return J3(t,e)}catch{return t}}function L8(t,e=.15){return c2(t)>.5?Q3(t,e):J3(t,e)}function oY(t,e,n){try{return L8(t,e)}catch{return t}}function aY(t,e,n,r=1){const i=(l,c)=>Math.round((l**(1/r)*(1-n)+c**(1/r)*n)**r),s=ul(t),o=ul(e),a=[i(s.values[0],o.values[0]),i(s.values[1],o.values[1]),i(s.values[2],o.values[2])];return fg({type:"rgb",values:a})}const lY={black:"#000",white:"#fff"},Zv=lY,cY={50:"#fafafa",100:"#f5f5f5",200:"#eeeeee",300:"#e0e0e0",400:"#bdbdbd",500:"#9e9e9e",600:"#757575",700:"#616161",800:"#424242",900:"#212121",A100:"#f5f5f5",A200:"#eeeeee",A400:"#bdbdbd",A700:"#616161"},uY=cY,dY={50:"#f3e5f5",100:"#e1bee7",200:"#ce93d8",300:"#ba68c8",400:"#ab47bc",500:"#9c27b0",600:"#8e24aa",700:"#7b1fa2",800:"#6a1b9a",900:"#4a148c",A100:"#ea80fc",A200:"#e040fb",A400:"#d500f9",A700:"#aa00ff"},lm=dY,fY={50:"#ffebee",100:"#ffcdd2",200:"#ef9a9a",300:"#e57373",400:"#ef5350",500:"#f44336",600:"#e53935",700:"#d32f2f",800:"#c62828",900:"#b71c1c",A100:"#ff8a80",A200:"#ff5252",A400:"#ff1744",A700:"#d50000"},cm=fY,hY={50:"#fff3e0",100:"#ffe0b2",200:"#ffcc80",300:"#ffb74d",400:"#ffa726",500:"#ff9800",600:"#fb8c00",700:"#f57c00",800:"#ef6c00",900:"#e65100",A100:"#ffd180",A200:"#ffab40",A400:"#ff9100",A700:"#ff6d00"},w1=hY,pY={50:"#e3f2fd",100:"#bbdefb",200:"#90caf9",300:"#64b5f6",400:"#42a5f5",500:"#2196f3",600:"#1e88e5",700:"#1976d2",800:"#1565c0",900:"#0d47a1",A100:"#82b1ff",A200:"#448aff",A400:"#2979ff",A700:"#2962ff"},um=pY,mY={50:"#e1f5fe",100:"#b3e5fc",200:"#81d4fa",300:"#4fc3f7",400:"#29b6f6",500:"#03a9f4",600:"#039be5",700:"#0288d1",800:"#0277bd",900:"#01579b",A100:"#80d8ff",A200:"#40c4ff",A400:"#00b0ff",A700:"#0091ea"},dm=mY,gY={50:"#e8f5e9",100:"#c8e6c9",200:"#a5d6a7",300:"#81c784",400:"#66bb6a",500:"#4caf50",600:"#43a047",700:"#388e3c",800:"#2e7d32",900:"#1b5e20",A100:"#b9f6ca",A200:"#69f0ae",A400:"#00e676",A700:"#00c853"},fm=gY,vY=["mode","contrastThreshold","tonalOffset"],dL={text:{primary:"rgba(0, 0, 0, 0.87)",secondary:"rgba(0, 0, 0, 0.6)",disabled:"rgba(0, 0, 0, 0.38)"},divider:"rgba(0, 0, 0, 0.12)",background:{paper:Zv.white,default:Zv.white},action:{active:"rgba(0, 0, 0, 0.54)",hover:"rgba(0, 0, 0, 0.04)",hoverOpacity:.04,selected:"rgba(0, 0, 0, 0.08)",selectedOpacity:.08,disabled:"rgba(0, 0, 0, 0.26)",disabledBackground:"rgba(0, 0, 0, 0.12)",disabledOpacity:.38,focus:"rgba(0, 0, 0, 0.12)",focusOpacity:.12,activatedOpacity:.12}},BE={text:{primary:Zv.white,secondary:"rgba(255, 255, 255, 0.7)",disabled:"rgba(255, 255, 255, 0.5)",icon:"rgba(255, 255, 255, 0.5)"},divider:"rgba(255, 255, 255, 0.12)",background:{paper:"#121212",default:"#121212"},action:{active:Zv.white,hover:"rgba(255, 255, 255, 0.08)",hoverOpacity:.08,selected:"rgba(255, 255, 255, 0.16)",selectedOpacity:.16,disabled:"rgba(255, 255, 255, 0.3)",disabledBackground:"rgba(255, 255, 255, 0.12)",disabledOpacity:.38,focus:"rgba(255, 255, 255, 0.12)",focusOpacity:.12,activatedOpacity:.24}};function fL(t,e,n,r){const i=r.light||r,s=r.dark||r*1.5;t[e]||(t.hasOwnProperty(n)?t[e]=t[n]:e==="light"?t.light=qv(t.main,i):e==="dark"&&(t.dark=Xv(t.main,s)))}function yY(t="light"){return t==="dark"?{main:um[200],light:um[50],dark:um[400]}:{main:um[700],light:um[400],dark:um[800]}}function xY(t="light"){return t==="dark"?{main:lm[200],light:lm[50],dark:lm[400]}:{main:lm[500],light:lm[300],dark:lm[700]}}function _Y(t="light"){return t==="dark"?{main:cm[500],light:cm[300],dark:cm[700]}:{main:cm[700],light:cm[400],dark:cm[800]}}function bY(t="light"){return t==="dark"?{main:dm[400],light:dm[300],dark:dm[700]}:{main:dm[700],light:dm[500],dark:dm[900]}}function SY(t="light"){return t==="dark"?{main:fm[400],light:fm[300],dark:fm[700]}:{main:fm[800],light:fm[500],dark:fm[900]}}function wY(t="light"){return t==="dark"?{main:w1[400],light:w1[300],dark:w1[700]}:{main:"#ed6c02",light:w1[500],dark:w1[900]}}function MY(t){const{mode:e="light",contrastThreshold:n=3,tonalOffset:r=.2}=t,i=Rt(t,vY),s=t.primary||yY(e),o=t.secondary||xY(e),a=t.error||_Y(e),l=t.info||bY(e),c=t.success||SY(e),f=t.warning||wY(e);function p(_){return KZ(_,BE.text.primary)>=n?BE.text.primary:dL.text.primary}const g=({color:_,name:b,mainShade:y=500,lightShade:S=300,darkShade:w=700})=>{if(_=X({},_),!_.main&&_[y]&&(_.main=_[y]),!_.hasOwnProperty("main"))throw new Error(op(11,b?` (${b})`:"",y));if(typeof _.main!="string")throw new Error(op(12,b?` (${b})`:"",JSON.stringify(_.main)));return fL(_,"light",S,r),fL(_,"dark",w,r),_.contrastText||(_.contrastText=p(_.main)),_},v={dark:BE,light:dL};return vo(X({common:X({},Zv),mode:e,primary:g({color:s,name:"primary"}),secondary:g({color:o,name:"secondary",mainShade:"A400",lightShade:"A200",darkShade:"A700"}),error:g({color:a,name:"error"}),warning:g({color:f,name:"warning"}),info:g({color:l,name:"info"}),success:g({color:c,name:"success"}),grey:uY,contrastThreshold:n,getContrastText:p,augmentColor:g,tonalOffset:r},v[e]),i)}const EY=["fontFamily","fontSize","fontWeightLight","fontWeightRegular","fontWeightMedium","fontWeightBold","htmlFontSize","allVariants","pxToRem"];function CY(t){return Math.round(t*1e5)/1e5}const hL={textTransform:"uppercase"},pL='"Roboto", "Helvetica", "Arial", sans-serif';function TY(t,e){const n=typeof e=="function"?e(t):e,{fontFamily:r=pL,fontSize:i=14,fontWeightLight:s=300,fontWeightRegular:o=400,fontWeightMedium:a=500,fontWeightBold:l=700,htmlFontSize:c=16,allVariants:f,pxToRem:p}=n,g=Rt(n,EY),v=i/14,x=p||(y=>`${y/c*v}rem`),_=(y,S,w,T,L)=>X({fontFamily:r,fontWeight:y,fontSize:x(S),lineHeight:w},r===pL?{letterSpacing:`${CY(T/S)}em`}:{},L,f),b={h1:_(s,96,1.167,-1.5),h2:_(s,60,1.2,-.5),h3:_(o,48,1.167,0),h4:_(o,34,1.235,.25),h5:_(o,24,1.334,0),h6:_(a,20,1.6,.15),subtitle1:_(o,16,1.75,.15),subtitle2:_(a,14,1.57,.1),body1:_(o,16,1.5,.15),body2:_(o,14,1.43,.15),button:_(a,14,1.75,.4,hL),caption:_(o,12,1.66,.4),overline:_(o,12,2.66,1,hL),inherit:{fontFamily:"inherit",fontWeight:"inherit",fontSize:"inherit",lineHeight:"inherit",letterSpacing:"inherit"}};return vo(X({htmlFontSize:c,pxToRem:x,fontFamily:r,fontSize:i,fontWeightLight:s,fontWeightRegular:o,fontWeightMedium:a,fontWeightBold:l},b),g,{clone:!1})}const AY=.2,RY=.14,PY=.12;function Jr(...t){return[`${t[0]}px ${t[1]}px ${t[2]}px ${t[3]}px rgba(0,0,0,${AY})`,`${t[4]}px ${t[5]}px ${t[6]}px ${t[7]}px rgba(0,0,0,${RY})`,`${t[8]}px ${t[9]}px ${t[10]}px ${t[11]}px rgba(0,0,0,${PY})`].join(",")}const IY=["none",Jr(0,2,1,-1,0,1,1,0,0,1,3,0),Jr(0,3,1,-2,0,2,2,0,0,1,5,0),Jr(0,3,3,-2,0,3,4,0,0,1,8,0),Jr(0,2,4,-1,0,4,5,0,0,1,10,0),Jr(0,3,5,-1,0,5,8,0,0,1,14,0),Jr(0,3,5,-1,0,6,10,0,0,1,18,0),Jr(0,4,5,-2,0,7,10,1,0,2,16,1),Jr(0,5,5,-3,0,8,10,1,0,3,14,2),Jr(0,5,6,-3,0,9,12,1,0,3,16,2),Jr(0,6,6,-3,0,10,14,1,0,4,18,3),Jr(0,6,7,-4,0,11,15,1,0,4,20,3),Jr(0,7,8,-4,0,12,17,2,0,5,22,4),Jr(0,7,8,-4,0,13,19,2,0,5,24,4),Jr(0,7,9,-4,0,14,21,2,0,5,26,4),Jr(0,8,9,-5,0,15,22,2,0,6,28,5),Jr(0,8,10,-5,0,16,24,2,0,6,30,5),Jr(0,8,11,-5,0,17,26,2,0,6,32,5),Jr(0,9,11,-5,0,18,28,2,0,7,34,6),Jr(0,9,12,-6,0,19,29,2,0,7,36,6),Jr(0,10,13,-6,0,20,31,3,0,8,38,7),Jr(0,10,13,-6,0,21,33,3,0,8,40,7),Jr(0,10,14,-6,0,22,35,3,0,8,42,7),Jr(0,11,14,-7,0,23,36,3,0,9,44,8),Jr(0,11,15,-7,0,24,38,3,0,9,46,8)],LY=["duration","easing","delay"],kY={easeInOut:"cubic-bezier(0.4, 0, 0.2, 1)",easeOut:"cubic-bezier(0.0, 0, 0.2, 1)",easeIn:"cubic-bezier(0.4, 0, 1, 1)",sharp:"cubic-bezier(0.4, 0, 0.6, 1)"},k8={shortest:150,shorter:200,short:250,standard:300,complex:375,enteringScreen:225,leavingScreen:195};function mL(t){return`${Math.round(t)}ms`}function OY(t){if(!t)return 0;const e=t/36;return Math.round((4+15*e**.25+e/5)*10)}function NY(t){const e=X({},kY,t.easing),n=X({},k8,t.duration);return X({getAutoHeightDuration:OY,create:(i=["all"],s={})=>{const{duration:o=n.standard,easing:a=e.easeInOut,delay:l=0}=s;return Rt(s,LY),(Array.isArray(i)?i:[i]).map(c=>`${c} ${typeof o=="string"?o:mL(o)} ${a} ${typeof l=="string"?l:mL(l)}`).join(",")}},t,{easing:e,duration:n})}const DY={mobileStepper:1e3,fab:1050,speedDial:1050,appBar:1100,drawer:1200,modal:1300,snackbar:1400,tooltip:1500},FY=DY,UY=["breakpoints","mixins","spacing","palette","transitions","typography","shape"];function eR(t={},...e){const{mixins:n={},palette:r={},transitions:i={},typography:s={}}=t,o=Rt(t,UY);if(t.vars)throw new Error(op(18));const a=MY(r),l=qy(t);let c=vo(l,{mixins:XZ(l.breakpoints,n),palette:a,shadows:IY.slice(),typography:TY(a,s),transitions:NY(i),zIndex:X({},FY)});return c=vo(c,o),c=e.reduce((f,p)=>vo(f,p),c),c.unstable_sxConfig=X({},Xy,o==null?void 0:o.unstable_sxConfig),c.unstable_sx=function(p){return cg({sx:p,theme:this})},c}const zY=eR(),mw=zY,lp="$$material";function En({props:t,name:e}){return M8({props:t,name:e,defaultTheme:mw,themeId:lp})}function BY({styles:t,themeId:e,defaultTheme:n={}}){const r=pw(n),i=typeof t=="function"?t(e&&r[e]||r):t;return C.jsx(b8,{styles:i})}function O8(t){var e,n,r="";if(typeof t=="string"||typeof t=="number")r+=t;else if(typeof t=="object")if(Array.isArray(t)){var i=t.length;for(e=0;ea!=="theme"&&a!=="sx"&&a!=="as"})(cg);return D.forwardRef(function(l,c){const f=pw(n),p=Ky(l),{className:g,component:v="div"}=p,x=Rt(p,HY);return C.jsx(s,X({as:v,ref:c,className:N8(g,i?i(r):r),theme:e&&f[e]||f},x))})}function pn(t,e,n="Mui"){const r={};return e.forEach(i=>{r[i]=bn(t,i,n)}),r}var D8={exports:{}},Er={};/**
+ * @license React
+ * react-is.production.min.js
+ *
+ * Copyright (c) Facebook, Inc. and its affiliates.
+ *
+ * This source code is licensed under the MIT license found in the
+ * LICENSE file in the root directory of this source tree.
+ */var tR=Symbol.for("react.element"),nR=Symbol.for("react.portal"),gw=Symbol.for("react.fragment"),vw=Symbol.for("react.strict_mode"),yw=Symbol.for("react.profiler"),xw=Symbol.for("react.provider"),_w=Symbol.for("react.context"),VY=Symbol.for("react.server_context"),bw=Symbol.for("react.forward_ref"),Sw=Symbol.for("react.suspense"),ww=Symbol.for("react.suspense_list"),Mw=Symbol.for("react.memo"),Ew=Symbol.for("react.lazy"),WY=Symbol.for("react.offscreen"),F8;F8=Symbol.for("react.module.reference");function gl(t){if(typeof t=="object"&&t!==null){var e=t.$$typeof;switch(e){case tR:switch(t=t.type,t){case gw:case yw:case vw:case Sw:case ww:return t;default:switch(t=t&&t.$$typeof,t){case VY:case _w:case bw:case Ew:case Mw:case xw:return t;default:return e}}case nR:return e}}}Er.ContextConsumer=_w;Er.ContextProvider=xw;Er.Element=tR;Er.ForwardRef=bw;Er.Fragment=gw;Er.Lazy=Ew;Er.Memo=Mw;Er.Portal=nR;Er.Profiler=yw;Er.StrictMode=vw;Er.Suspense=Sw;Er.SuspenseList=ww;Er.isAsyncMode=function(){return!1};Er.isConcurrentMode=function(){return!1};Er.isContextConsumer=function(t){return gl(t)===_w};Er.isContextProvider=function(t){return gl(t)===xw};Er.isElement=function(t){return typeof t=="object"&&t!==null&&t.$$typeof===tR};Er.isForwardRef=function(t){return gl(t)===bw};Er.isFragment=function(t){return gl(t)===gw};Er.isLazy=function(t){return gl(t)===Ew};Er.isMemo=function(t){return gl(t)===Mw};Er.isPortal=function(t){return gl(t)===nR};Er.isProfiler=function(t){return gl(t)===yw};Er.isStrictMode=function(t){return gl(t)===vw};Er.isSuspense=function(t){return gl(t)===Sw};Er.isSuspenseList=function(t){return gl(t)===ww};Er.isValidElementType=function(t){return typeof t=="string"||typeof t=="function"||t===gw||t===yw||t===vw||t===Sw||t===ww||t===WY||typeof t=="object"&&t!==null&&(t.$$typeof===Ew||t.$$typeof===Mw||t.$$typeof===xw||t.$$typeof===_w||t.$$typeof===bw||t.$$typeof===F8||t.getModuleId!==void 0)};Er.typeOf=gl;D8.exports=Er;var gL=D8.exports;const jY=/^\s*function(?:\s|\s*\/\*.*\*\/\s*)+([^(\s/]*)\s*/;function U8(t){const e=`${t}`.match(jY);return e&&e[1]||""}function z8(t,e=""){return t.displayName||t.name||U8(t)||e}function vL(t,e,n){const r=z8(e);return t.displayName||(r!==""?`${n}(${r})`:n)}function GY(t){if(t!=null){if(typeof t=="string")return t;if(typeof t=="function")return z8(t,"Component");if(typeof t=="object")switch(t.$$typeof){case gL.ForwardRef:return vL(t,t.render,"ForwardRef");case gL.Memo:return vL(t,t.type,"memo");default:return}}}const XY=Object.freeze(Object.defineProperty({__proto__:null,default:GY,getFunctionName:U8},Symbol.toStringTag,{value:"Module"})),qY=["ownerState"],ZY=["variants"],YY=["name","slot","skipVariantsResolver","skipSx","overridesResolver"];function KY(t){return Object.keys(t).length===0}function QY(t){return typeof t=="string"&&t.charCodeAt(0)>96}function HE(t){return t!=="ownerState"&&t!=="theme"&&t!=="sx"&&t!=="as"}const JY=qy(),eK=t=>t&&t.charAt(0).toLowerCase()+t.slice(1);function $_({defaultTheme:t,theme:e,themeId:n}){return KY(e)?t:e[n]||e}function tK(t){return t?(e,n)=>n[t]:null}function bS(t,e){let{ownerState:n}=e,r=Rt(e,qY);const i=typeof t=="function"?t(X({ownerState:n},r)):t;if(Array.isArray(i))return i.flatMap(s=>bS(s,X({ownerState:n},r)));if(i&&typeof i=="object"&&Array.isArray(i.variants)){const{variants:s=[]}=i;let a=Rt(i,ZY);return s.forEach(l=>{let c=!0;typeof l.props=="function"?c=l.props(X({ownerState:n},r,n)):Object.keys(l.props).forEach(f=>{(n==null?void 0:n[f])!==l.props[f]&&r[f]!==l.props[f]&&(c=!1)}),c&&(Array.isArray(a)||(a=[a]),a.push(typeof l.style=="function"?l.style(X({ownerState:n},r,n)):l.style))}),a}return i}function nK(t={}){const{themeId:e,defaultTheme:n=JY,rootShouldForwardProp:r=HE,slotShouldForwardProp:i=HE}=t,s=o=>cg(X({},o,{theme:$_(X({},o,{defaultTheme:n,themeId:e}))}));return s.__mui_systemSx=!0,(o,a={})=>{S8(o,L=>L.filter(R=>!(R!=null&&R.__mui_systemSx)));const{name:l,slot:c,skipVariantsResolver:f,skipSx:p,overridesResolver:g=tK(eK(c))}=a,v=Rt(a,YY),x=f!==void 0?f:c&&c!=="Root"&&c!=="root"||!1,_=p||!1;let b,y=HE;c==="Root"||c==="root"?y=r:c?y=i:QY(o)&&(y=void 0);const S=Z3(o,X({shouldForwardProp:y,label:b},v)),w=L=>typeof L=="function"&&L.__emotion_real!==L||yu(L)?R=>bS(L,X({},R,{theme:$_({theme:R.theme,defaultTheme:n,themeId:e})})):L,T=(L,...R)=>{let P=w(L);const F=R?R.map(w):[];l&&g&&F.push(H=>{const Q=$_(X({},H,{defaultTheme:n,themeId:e}));if(!Q.components||!Q.components[l]||!Q.components[l].styleOverrides)return null;const q=Q.components[l].styleOverrides,le={};return Object.entries(q).forEach(([ie,ee])=>{le[ie]=bS(ee,X({},H,{theme:Q}))}),g(H,le)}),l&&!x&&F.push(H=>{var Q;const q=$_(X({},H,{defaultTheme:n,themeId:e})),le=q==null||(Q=q.components)==null||(Q=Q[l])==null?void 0:Q.variants;return bS({variants:le},X({},H,{theme:q}))}),_||F.push(s);const O=F.length-R.length;if(Array.isArray(L)&&O>0){const H=new Array(O).fill("");P=[...L,...H],P.raw=[...L.raw,...H]}const I=S(P,...F);return o.muiName&&(I.muiName=o.muiName),I};return S.withConfig&&(T.withConfig=S.withConfig),T}}const B8=nK(),Xo=typeof window<"u"?D.useLayoutEffect:D.useEffect;function fT(...t){return t.reduce((e,n)=>n==null?e:function(...i){e.apply(this,i),n.apply(this,i)},()=>{})}function Qy(t,e=166){let n;function r(...i){const s=()=>{t.apply(this,i)};clearTimeout(n),n=setTimeout(s,e)}return r.clear=()=>{clearTimeout(n)},r}function rK(t,e){return()=>null}function mv(t,e){var n,r;return D.isValidElement(t)&&e.indexOf((n=t.type.muiName)!=null?n:(r=t.type)==null||(r=r._payload)==null||(r=r.value)==null?void 0:r.muiName)!==-1}function Oi(t){return t&&t.ownerDocument||document}function Oc(t){return Oi(t).defaultView||window}function iK(t,e){return()=>null}function Yv(t,e){typeof t=="function"?t(e):t&&(t.current=e)}let yL=0;function sK(t){const[e,n]=D.useState(t),r=t||e;return D.useEffect(()=>{e==null&&(yL+=1,n(`mui-${yL}`))},[e]),r}const xL=pC.useId;function hg(t){if(xL!==void 0){const e=xL();return t??e}return sK(t)}function oK(t,e,n,r,i){return null}function Cu({controlled:t,default:e,name:n,state:r="value"}){const{current:i}=D.useRef(t!==void 0),[s,o]=D.useState(e),a=i?t:s,l=D.useCallback(c=>{i||o(c)},[]);return[a,l]}function ts(t){const e=D.useRef(t);return Xo(()=>{e.current=t}),D.useRef((...n)=>(0,e.current)(...n)).current}function Kr(...t){return D.useMemo(()=>t.every(e=>e==null)?null:e=>{t.forEach(n=>{Yv(n,e)})},t)}const _L={};function aK(t,e){const n=D.useRef(_L);return n.current===_L&&(n.current=t(e)),n}const lK=[];function cK(t){D.useEffect(t,lK)}class Jy{constructor(){this.currentId=null,this.clear=()=>{this.currentId!==null&&(clearTimeout(this.currentId),this.currentId=null)},this.disposeEffect=()=>this.clear}static create(){return new Jy}start(e,n){this.clear(),this.currentId=setTimeout(()=>{this.currentId=null,n()},e)}}function Ah(){const t=aK(Jy.create).current;return cK(t.disposeEffect),t}let Cw=!0,hT=!1;const uK=new Jy,dK={text:!0,search:!0,url:!0,tel:!0,email:!0,password:!0,number:!0,date:!0,month:!0,week:!0,time:!0,datetime:!0,"datetime-local":!0};function fK(t){const{type:e,tagName:n}=t;return!!(n==="INPUT"&&dK[e]&&!t.readOnly||n==="TEXTAREA"&&!t.readOnly||t.isContentEditable)}function hK(t){t.metaKey||t.altKey||t.ctrlKey||(Cw=!0)}function $E(){Cw=!1}function pK(){this.visibilityState==="hidden"&&hT&&(Cw=!0)}function mK(t){t.addEventListener("keydown",hK,!0),t.addEventListener("mousedown",$E,!0),t.addEventListener("pointerdown",$E,!0),t.addEventListener("touchstart",$E,!0),t.addEventListener("visibilitychange",pK,!0)}function gK(t){const{target:e}=t;try{return e.matches(":focus-visible")}catch{}return Cw||fK(e)}function Tw(){const t=D.useCallback(i=>{i!=null&&mK(i.ownerDocument)},[]),e=D.useRef(!1);function n(){return e.current?(hT=!0,uK.start(100,()=>{hT=!1}),e.current=!1,!0):!1}function r(i){return gK(i)?(e.current=!0,!0):!1}return{isFocusVisibleRef:e,onFocus:r,onBlur:n,ref:t}}function H8(t){const e=t.documentElement.clientWidth;return Math.abs(window.innerWidth-e)}let hm;function $8(){if(hm)return hm;const t=document.createElement("div"),e=document.createElement("div");return e.style.width="10px",e.style.height="1px",t.appendChild(e),t.dir="rtl",t.style.fontSize="14px",t.style.width="4px",t.style.height="1px",t.style.position="absolute",t.style.top="-1000px",t.style.overflow="scroll",document.body.appendChild(t),hm="reverse",t.scrollLeft>0?hm="default":(t.scrollLeft=1,t.scrollLeft===0&&(hm="negative")),document.body.removeChild(t),hm}function vK(t,e){const n=t.scrollLeft;if(e!=="rtl")return n;switch($8()){case"negative":return t.scrollWidth-t.clientWidth+n;case"reverse":return t.scrollWidth-t.clientWidth-n;default:return n}}const yK=t=>{const e=D.useRef({});return D.useEffect(()=>{e.current=t}),e.current},xK={border:0,clip:"rect(0 0 0 0)",height:"1px",margin:"-1px",overflow:"hidden",padding:0,position:"absolute",whiteSpace:"nowrap",width:"1px"},_K=xK;function Sn(t,e,n=void 0){const r={};return Object.keys(t).forEach(i=>{r[i]=t[i].reduce((s,o)=>{if(o){const a=e(o);a!==""&&s.push(a),n&&n[o]&&s.push(n[o])}return s},[]).join(" ")}),r}const bK=D.createContext(null),V8=bK;function W8(){return D.useContext(V8)}const SK=typeof Symbol=="function"&&Symbol.for,wK=SK?Symbol.for("mui.nested"):"__THEME_NESTED__";function MK(t,e){return typeof e=="function"?e(t):X({},t,e)}function EK(t){const{children:e,theme:n}=t,r=W8(),i=D.useMemo(()=>{const s=r===null?n:MK(r,n);return s!=null&&(s[wK]=r!==null),s},[n,r]);return C.jsx(V8.Provider,{value:i,children:e})}const CK=["value"],j8=D.createContext();function TK(t){let{value:e}=t,n=Rt(t,CK);return C.jsx(j8.Provider,X({value:e??!0},n))}const ex=()=>{const t=D.useContext(j8);return t??!1},bL={};function SL(t,e,n,r=!1){return D.useMemo(()=>{const i=t&&e[t]||e;if(typeof n=="function"){const s=n(i),o=t?X({},e,{[t]:s}):s;return r?()=>o:o}return t?X({},e,{[t]:n}):X({},e,n)},[t,e,n,r])}function AK(t){const{children:e,theme:n,themeId:r}=t,i=w8(bL),s=W8()||bL,o=SL(r,i,n),a=SL(r,s,n,!0),l=o.direction==="rtl";return C.jsx(EK,{theme:a,children:C.jsx(Yy.Provider,{value:o,children:C.jsx(TK,{value:l,children:e})})})}const RK=["component","direction","spacing","divider","children","className","useFlexGap"],PK=qy(),IK=B8("div",{name:"MuiStack",slot:"Root",overridesResolver:(t,e)=>e.root});function LK(t){return M8({props:t,name:"MuiStack",defaultTheme:PK})}function kK(t,e){const n=D.Children.toArray(t).filter(Boolean);return n.reduce((r,i,s)=>(r.push(i),s({row:"Left","row-reverse":"Right",column:"Top","column-reverse":"Bottom"})[t],NK=({ownerState:t,theme:e})=>{let n=X({display:"flex",flexDirection:"column"},jo({theme:e},Xh({values:t.direction,breakpoints:e.breakpoints.values}),r=>({flexDirection:r})));if(t.spacing){const r=B3(e),i=Object.keys(e.breakpoints.values).reduce((l,c)=>((typeof t.spacing=="object"&&t.spacing[c]!=null||typeof t.direction=="object"&&t.direction[c]!=null)&&(l[c]=!0),l),{}),s=Xh({values:t.direction,base:i}),o=Xh({values:t.spacing,base:i});typeof s=="object"&&Object.keys(s).forEach((l,c,f)=>{if(!s[l]){const g=c>0?s[f[c-1]]:"column";s[l]=g}}),n=vo(n,jo({theme:e},o,(l,c)=>t.useFlexGap?{gap:ap(r,l)}:{"& > :not(style):not(style)":{margin:0},"& > :not(style) ~ :not(style)":{[`margin${OK(c?s[c]:t.direction)}`]:ap(r,l)}}))}return n=jX(e.breakpoints,n),n};function DK(t={}){const{createStyledComponent:e=IK,useThemeProps:n=LK,componentName:r="MuiStack"}=t,i=()=>Sn({root:["root"]},l=>bn(r,l),{}),s=e(NK);return D.forwardRef(function(l,c){const f=n(l),p=Ky(f),{component:g="div",direction:v="column",spacing:x=0,divider:_,children:b,className:y,useFlexGap:S=!1}=p,w=Rt(p,RK),T={direction:v,spacing:x,useFlexGap:S},L=i();return C.jsx(s,X({as:g,ownerState:T,ref:c,className:N8(L.root,y)},w,{children:_?kK(b,_):b}))})}function G8(t){return C.jsx(BY,X({},t,{defaultTheme:mw,themeId:lp}))}const FK=(t,e)=>X({WebkitFontSmoothing:"antialiased",MozOsxFontSmoothing:"grayscale",boxSizing:"border-box",WebkitTextSizeAdjust:"100%"},e&&!t.vars&&{colorScheme:t.palette.mode}),UK=t=>X({color:(t.vars||t).palette.text.primary},t.typography.body1,{backgroundColor:(t.vars||t).palette.background.default,"@media print":{backgroundColor:(t.vars||t).palette.common.white}}),zK=(t,e=!1)=>{var n;const r={};e&&t.colorSchemes&&Object.entries(t.colorSchemes).forEach(([o,a])=>{var l;r[t.getColorSchemeSelector(o).replace(/\s*&/,"")]={colorScheme:(l=a.palette)==null?void 0:l.mode}});let i=X({html:FK(t,e),"*, *::before, *::after":{boxSizing:"inherit"},"strong, b":{fontWeight:t.typography.fontWeightBold},body:X({margin:0},UK(t),{"&::backdrop":{backgroundColor:(t.vars||t).palette.background.default}})},r);const s=(n=t.components)==null||(n=n.MuiCssBaseline)==null?void 0:n.styleOverrides;return s&&(i=[i,s]),i};function BK(t){const e=En({props:t,name:"MuiCssBaseline"}),{children:n,enableColorScheme:r=!1}=e;return C.jsxs(D.Fragment,{children:[C.jsx(G8,{styles:i=>zK(i,r)}),n]})}function Bu(){const t=pw(mw);return t[lp]||t}var tx={},VE={exports:{}},wL;function HK(){return wL||(wL=1,function(t){function e(n,r){if(n==null)return{};var i={},s=Object.keys(n),o,a;for(a=0;a=0)&&(i[o]=n[o]);return i}t.exports=e,t.exports.__esModule=!0,t.exports.default=t.exports}(VE)),VE.exports}const X8=Uu(zZ),$K=Uu(BX),VK=Uu(qX),WK=Uu(XY),jK=Uu(Dq),GK=Uu(WZ);var pg=pf;Object.defineProperty(tx,"__esModule",{value:!0});var XK=tx.default=oQ;tx.shouldForwardProp=SS;tx.systemDefaultTheme=void 0;var Za=pg(_8()),pT=pg(HK()),ML=eQ(X8),qK=$K;pg(VK);pg(WK);var ZK=pg(jK),YK=pg(GK);const KK=["ownerState"],QK=["variants"],JK=["name","slot","skipVariantsResolver","skipSx","overridesResolver"];function q8(t){if(typeof WeakMap!="function")return null;var e=new WeakMap,n=new WeakMap;return(q8=function(r){return r?n:e})(t)}function eQ(t,e){if(!e&&t&&t.__esModule)return t;if(t===null||typeof t!="object"&&typeof t!="function")return{default:t};var n=q8(e);if(n&&n.has(t))return n.get(t);var r={__proto__:null},i=Object.defineProperty&&Object.getOwnPropertyDescriptor;for(var s in t)if(s!=="default"&&Object.prototype.hasOwnProperty.call(t,s)){var o=i?Object.getOwnPropertyDescriptor(t,s):null;o&&(o.get||o.set)?Object.defineProperty(r,s,o):r[s]=t[s]}return r.default=t,n&&n.set(t,r),r}function tQ(t){return Object.keys(t).length===0}function nQ(t){return typeof t=="string"&&t.charCodeAt(0)>96}function SS(t){return t!=="ownerState"&&t!=="theme"&&t!=="sx"&&t!=="as"}const rQ=tx.systemDefaultTheme=(0,ZK.default)(),iQ=t=>t&&t.charAt(0).toLowerCase()+t.slice(1);function V_({defaultTheme:t,theme:e,themeId:n}){return tQ(e)?t:e[n]||e}function sQ(t){return t?(e,n)=>n[t]:null}function wS(t,e){let{ownerState:n}=e,r=(0,pT.default)(e,KK);const i=typeof t=="function"?t((0,Za.default)({ownerState:n},r)):t;if(Array.isArray(i))return i.flatMap(s=>wS(s,(0,Za.default)({ownerState:n},r)));if(i&&typeof i=="object"&&Array.isArray(i.variants)){const{variants:s=[]}=i;let a=(0,pT.default)(i,QK);return s.forEach(l=>{let c=!0;typeof l.props=="function"?c=l.props((0,Za.default)({ownerState:n},r,n)):Object.keys(l.props).forEach(f=>{(n==null?void 0:n[f])!==l.props[f]&&r[f]!==l.props[f]&&(c=!1)}),c&&(Array.isArray(a)||(a=[a]),a.push(typeof l.style=="function"?l.style((0,Za.default)({ownerState:n},r,n)):l.style))}),a}return i}function oQ(t={}){const{themeId:e,defaultTheme:n=rQ,rootShouldForwardProp:r=SS,slotShouldForwardProp:i=SS}=t,s=o=>(0,YK.default)((0,Za.default)({},o,{theme:V_((0,Za.default)({},o,{defaultTheme:n,themeId:e}))}));return s.__mui_systemSx=!0,(o,a={})=>{(0,ML.internal_processStyles)(o,L=>L.filter(R=>!(R!=null&&R.__mui_systemSx)));const{name:l,slot:c,skipVariantsResolver:f,skipSx:p,overridesResolver:g=sQ(iQ(c))}=a,v=(0,pT.default)(a,JK),x=f!==void 0?f:c&&c!=="Root"&&c!=="root"||!1,_=p||!1;let b,y=SS;c==="Root"||c==="root"?y=r:c?y=i:nQ(o)&&(y=void 0);const S=(0,ML.default)(o,(0,Za.default)({shouldForwardProp:y,label:b},v)),w=L=>typeof L=="function"&&L.__emotion_real!==L||(0,qK.isPlainObject)(L)?R=>wS(L,(0,Za.default)({},R,{theme:V_({theme:R.theme,defaultTheme:n,themeId:e})})):L,T=(L,...R)=>{let P=w(L);const F=R?R.map(w):[];l&&g&&F.push(H=>{const Q=V_((0,Za.default)({},H,{defaultTheme:n,themeId:e}));if(!Q.components||!Q.components[l]||!Q.components[l].styleOverrides)return null;const q=Q.components[l].styleOverrides,le={};return Object.entries(q).forEach(([ie,ee])=>{le[ie]=wS(ee,(0,Za.default)({},H,{theme:Q}))}),g(H,le)}),l&&!x&&F.push(H=>{var Q;const q=V_((0,Za.default)({},H,{defaultTheme:n,themeId:e})),le=q==null||(Q=q.components)==null||(Q=Q[l])==null?void 0:Q.variants;return wS({variants:le},(0,Za.default)({},H,{theme:q}))}),_||F.push(s);const O=F.length-R.length;if(Array.isArray(L)&&O>0){const H=new Array(O).fill("");P=[...L,...H],P.raw=[...L.raw,...H]}const I=S(P,...F);return o.muiName&&(I.muiName=o.muiName),I};return S.withConfig&&(T.withConfig=S.withConfig),T}}function Aw(t){return t!=="ownerState"&&t!=="theme"&&t!=="sx"&&t!=="as"}const aQ=t=>Aw(t)&&t!=="classes",La=aQ,lt=XK({themeId:lp,defaultTheme:mw,rootShouldForwardProp:La}),lQ=["theme"];function cQ(t){let{theme:e}=t,n=Rt(t,lQ);const r=e[lp];return C.jsx(AK,X({},n,{themeId:r?lp:void 0,theme:r||e}))}const EL=t=>{let e;return t<1?e=5.11916*t**2:e=4.5*Math.log(t+1)+2,(e/100).toFixed(2)},uQ={fontFamily:"'Roboto', sans-serif",fontSize:16,h1:{fontFamily:"'Exo 2', sans-serif",fontWeight:600,fontSize:"1.625rem"},h2:{fontFamily:"'Exo 2', sans-serif",fontWeight:600,fontSize:"1.325rem"},h3:{fontFamily:"'Exo 2', sans-serif",fontWeight:600,fontSize:"1.125rem"},h4:{fontFamily:"'Exo 2', sans-serif",fontWeight:500,fontSize:"1.125rem"},h5:{fontFamily:"'Exo 2', sans-serif",fontWeight:400,fontSize:"1.125rem"},h6:{fontFamily:"'Exo 2', sans-serif",fontWeight:600,fontSize:"1rem"}},W_={mode:"dark",accent:{main:"#4be09c"},primary:{light:"#4be09c",main:"#33c69d",dark:"#008675"},secondary:{light:"#cceae9",main:"#00b1b9",dark:"#212e3d"},error:{main:"#ff3e4e"},warning:{main:"#ffc63b"},success:{main:"#00d475"},info:{main:"#00b1b9"},background:{default:"#0c1c2c",paper:"#212e3d"},data:{100:"#008e8e",200:"#78b5b3",300:"#cceae9",400:"#0079af",500:"#86b7d1",600:"#d6837b",700:"#988fd8",800:"#dbdbab",900:"#abd1ad"},grey:{50:"#fafafa",100:"#f5f5f5",200:"#eeeeee",300:"#e0e0e0",400:"#bdbdbd",500:"#9e9e9e",600:"#757575",700:"#616161",800:"#424242",900:"#212121",A100:"#cccccc",A200:"#999999",A400:"#808080",A700:"#606060"},text:{primary:"#ffffff"}},dQ=eR({typography:uQ,palette:W_,components:{MuiTooltip:{styleOverrides:{tooltip:{backgroundColor:W_.grey[800],borderColor:W_.grey[700],borderStyle:"dotted"}}},MuiDialog:{styleOverrides:{paper:{background:W_.background.paper}}}}});var mg=class{constructor(){this.listeners=new Set,this.subscribe=this.subscribe.bind(this)}subscribe(t){return this.listeners.add(t),this.onSubscribe(),()=>{this.listeners.delete(t),this.onUnsubscribe()}}hasListeners(){return this.listeners.size>0}onSubscribe(){}onUnsubscribe(){}},W0=typeof window>"u"||"Deno"in globalThis;function Ya(){}function fQ(t,e){return typeof t=="function"?t(e):t}function mT(t){return typeof t=="number"&&t>=0&&t!==1/0}function Z8(t,e){return Math.max(t+(e||0)-Date.now(),0)}function CL(t,e){const{type:n="all",exact:r,fetchStatus:i,predicate:s,queryKey:o,stale:a}=t;if(o){if(r){if(e.queryHash!==rR(o,e.options))return!1}else if(!Kv(e.queryKey,o))return!1}if(n!=="all"){const l=e.isActive();if(n==="active"&&!l||n==="inactive"&&l)return!1}return!(typeof a=="boolean"&&e.isStale()!==a||i&&i!==e.state.fetchStatus||s&&!s(e))}function TL(t,e){const{exact:n,status:r,predicate:i,mutationKey:s}=t;if(s){if(!e.options.mutationKey)return!1;if(n){if(cp(e.options.mutationKey)!==cp(s))return!1}else if(!Kv(e.options.mutationKey,s))return!1}return!(r&&e.state.status!==r||i&&!i(e))}function rR(t,e){return((e==null?void 0:e.queryKeyHashFn)||cp)(t)}function cp(t){return JSON.stringify(t,(e,n)=>gT(n)?Object.keys(n).sort().reduce((r,i)=>(r[i]=n[i],r),{}):n)}function Kv(t,e){return t===e?!0:typeof t!=typeof e?!1:t&&e&&typeof t=="object"&&typeof e=="object"?!Object.keys(e).some(n=>!Kv(t[n],e[n])):!1}function Y8(t,e){if(t===e)return t;const n=AL(t)&&AL(e);if(n||gT(t)&&gT(e)){const r=n?t:Object.keys(t),i=r.length,s=n?e:Object.keys(e),o=s.length,a=n?[]:{};let l=0;for(let c=0;c{setTimeout(e,t)})}function vT(t,e,n){return typeof n.structuralSharing=="function"?n.structuralSharing(t,e):n.structuralSharing!==!1?Y8(t,e):e}function pQ(t,e,n=0){const r=[...t,e];return n&&r.length>n?r.slice(1):r}function mQ(t,e,n=0){const r=[e,...t];return n&&r.length>n?r.slice(0,-1):r}var iR=Symbol(),Fh,zd,S0,ED,gQ=(ED=class extends mg{constructor(){super();rn(this,Fh,void 0);rn(this,zd,void 0);rn(this,S0,void 0);jt(this,S0,e=>{if(!W0&&window.addEventListener){const n=()=>e();return window.addEventListener("visibilitychange",n,!1),()=>{window.removeEventListener("visibilitychange",n)}}})}onSubscribe(){Ae(this,zd)||this.setEventListener(Ae(this,S0))}onUnsubscribe(){var e;this.hasListeners()||((e=Ae(this,zd))==null||e.call(this),jt(this,zd,void 0))}setEventListener(e){var n;jt(this,S0,e),(n=Ae(this,zd))==null||n.call(this),jt(this,zd,e(r=>{typeof r=="boolean"?this.setFocused(r):this.onFocus()}))}setFocused(e){Ae(this,Fh)!==e&&(jt(this,Fh,e),this.onFocus())}onFocus(){const e=this.isFocused();this.listeners.forEach(n=>{n(e)})}isFocused(){var e;return typeof Ae(this,Fh)=="boolean"?Ae(this,Fh):((e=globalThis.document)==null?void 0:e.visibilityState)!=="hidden"}},Fh=new WeakMap,zd=new WeakMap,S0=new WeakMap,ED),sR=new gQ,w0,Bd,M0,CD,vQ=(CD=class extends mg{constructor(){super();rn(this,w0,!0);rn(this,Bd,void 0);rn(this,M0,void 0);jt(this,M0,e=>{if(!W0&&window.addEventListener){const n=()=>e(!0),r=()=>e(!1);return window.addEventListener("online",n,!1),window.addEventListener("offline",r,!1),()=>{window.removeEventListener("online",n),window.removeEventListener("offline",r)}}})}onSubscribe(){Ae(this,Bd)||this.setEventListener(Ae(this,M0))}onUnsubscribe(){var e;this.hasListeners()||((e=Ae(this,Bd))==null||e.call(this),jt(this,Bd,void 0))}setEventListener(e){var n;jt(this,M0,e),(n=Ae(this,Bd))==null||n.call(this),jt(this,Bd,e(this.setOnline.bind(this)))}setOnline(e){Ae(this,w0)!==e&&(jt(this,w0,e),this.listeners.forEach(r=>{r(e)}))}isOnline(){return Ae(this,w0)}},w0=new WeakMap,Bd=new WeakMap,M0=new WeakMap,CD),d2=new vQ;function yQ(t){return Math.min(1e3*2**t,3e4)}function K8(t){return(t??"online")==="online"?d2.isOnline():!0}var Q8=class{constructor(t){this.revert=t==null?void 0:t.revert,this.silent=t==null?void 0:t.silent}};function WE(t){return t instanceof Q8}function J8(t){let e=!1,n=0,r=!1,i,s,o;const a=new Promise((y,S)=>{s=y,o=S}),l=y=>{var S;r||(x(new Q8(y)),(S=t.abort)==null||S.call(t))},c=()=>{e=!0},f=()=>{e=!1},p=()=>sR.isFocused()&&(t.networkMode==="always"||d2.isOnline())&&t.canRun(),g=()=>K8(t.networkMode)&&t.canRun(),v=y=>{var S;r||(r=!0,(S=t.onSuccess)==null||S.call(t,y),i==null||i(),s(y))},x=y=>{var S;r||(r=!0,(S=t.onError)==null||S.call(t,y),i==null||i(),o(y))},_=()=>new Promise(y=>{var S;i=w=>{(r||p())&&y(w)},(S=t.onPause)==null||S.call(t)}).then(()=>{var y;i=void 0,r||(y=t.onContinue)==null||y.call(t)}),b=()=>{if(r)return;let y;try{y=t.fn()}catch(S){y=Promise.reject(S)}Promise.resolve(y).then(v).catch(S=>{var P;if(r)return;const w=t.retry??(W0?0:3),T=t.retryDelay??yQ,L=typeof T=="function"?T(n,S):T,R=w===!0||typeof w=="number"&&np()?void 0:_()).then(()=>{e?x(S):b()})})};return{promise:a,cancel:l,continue:()=>(i==null||i(),a),cancelRetry:c,continueRetry:f,canStart:g,start:()=>(g()?b():_().then(b),a)}}function xQ(){let t=[],e=0,n=g=>{g()},r=g=>{g()},i=g=>setTimeout(g,0);const s=g=>{i=g},o=g=>{let v;e++;try{v=g()}finally{e--,e||c()}return v},a=g=>{e?t.push(g):i(()=>{n(g)})},l=g=>(...v)=>{a(()=>{g(...v)})},c=()=>{const g=t;t=[],g.length&&i(()=>{r(()=>{g.forEach(v=>{n(v)})})})};return{batch:o,batchCalls:l,schedule:a,setNotifyFunction:g=>{n=g},setBatchNotifyFunction:g=>{r=g},setScheduler:s}}var Ji=xQ(),Uh,TD,e7=(TD=class{constructor(){rn(this,Uh,void 0)}destroy(){this.clearGcTimeout()}scheduleGc(){this.clearGcTimeout(),mT(this.gcTime)&&jt(this,Uh,setTimeout(()=>{this.optionalRemove()},this.gcTime))}updateGcTime(t){this.gcTime=Math.max(this.gcTime||0,t??(W0?1/0:5*60*1e3))}clearGcTimeout(){Ae(this,Uh)&&(clearTimeout(Ae(this,Uh)),jt(this,Uh,void 0))}},Uh=new WeakMap,TD),E0,C0,qa,lo,Ay,zh,Nl,hu,AD,_Q=(AD=class extends e7{constructor(e){super();rn(this,Nl);rn(this,E0,void 0);rn(this,C0,void 0);rn(this,qa,void 0);rn(this,lo,void 0);rn(this,Ay,void 0);rn(this,zh,void 0);jt(this,zh,!1),jt(this,Ay,e.defaultOptions),this.setOptions(e.options),this.observers=[],jt(this,qa,e.cache),this.queryKey=e.queryKey,this.queryHash=e.queryHash,jt(this,E0,e.state||bQ(this.options)),this.state=Ae(this,E0),this.scheduleGc()}get meta(){return this.options.meta}setOptions(e){this.options={...Ae(this,Ay),...e},this.updateGcTime(this.options.gcTime)}optionalRemove(){!this.observers.length&&this.state.fetchStatus==="idle"&&Ae(this,qa).remove(this)}setData(e,n){const r=vT(this.state.data,e,this.options);return jn(this,Nl,hu).call(this,{data:r,type:"success",dataUpdatedAt:n==null?void 0:n.updatedAt,manual:n==null?void 0:n.manual}),r}setState(e,n){jn(this,Nl,hu).call(this,{type:"setState",state:e,setStateOptions:n})}cancel(e){var r,i;const n=(r=Ae(this,lo))==null?void 0:r.promise;return(i=Ae(this,lo))==null||i.cancel(e),n?n.then(Ya).catch(Ya):Promise.resolve()}destroy(){super.destroy(),this.cancel({silent:!0})}reset(){this.destroy(),this.setState(Ae(this,E0))}isActive(){return this.observers.some(e=>e.options.enabled!==!1)}isDisabled(){return this.getObserversCount()>0&&!this.isActive()}isStale(){return this.state.isInvalidated?!0:this.getObserversCount()>0?this.observers.some(e=>e.getCurrentResult().isStale):this.state.data===void 0}isStaleByTime(e=0){return this.state.isInvalidated||this.state.data===void 0||!Z8(this.state.dataUpdatedAt,e)}onFocus(){var n;const e=this.observers.find(r=>r.shouldFetchOnWindowFocus());e==null||e.refetch({cancelRefetch:!1}),(n=Ae(this,lo))==null||n.continue()}onOnline(){var n;const e=this.observers.find(r=>r.shouldFetchOnReconnect());e==null||e.refetch({cancelRefetch:!1}),(n=Ae(this,lo))==null||n.continue()}addObserver(e){this.observers.includes(e)||(this.observers.push(e),this.clearGcTimeout(),Ae(this,qa).notify({type:"observerAdded",query:this,observer:e}))}removeObserver(e){this.observers.includes(e)&&(this.observers=this.observers.filter(n=>n!==e),this.observers.length||(Ae(this,lo)&&(Ae(this,zh)?Ae(this,lo).cancel({revert:!0}):Ae(this,lo).cancelRetry()),this.scheduleGc()),Ae(this,qa).notify({type:"observerRemoved",query:this,observer:e}))}getObserversCount(){return this.observers.length}invalidate(){this.state.isInvalidated||jn(this,Nl,hu).call(this,{type:"invalidate"})}fetch(e,n){var c,f,p;if(this.state.fetchStatus!=="idle"){if(this.state.data!==void 0&&(n!=null&&n.cancelRefetch))this.cancel({silent:!0});else if(Ae(this,lo))return Ae(this,lo).continueRetry(),Ae(this,lo).promise}if(e&&this.setOptions(e),!this.options.queryFn){const g=this.observers.find(v=>v.options.queryFn);g&&this.setOptions(g.options)}const r=new AbortController,i={queryKey:this.queryKey,meta:this.meta},s=g=>{Object.defineProperty(g,"signal",{enumerable:!0,get:()=>(jt(this,zh,!0),r.signal)})};s(i);const o=()=>!this.options.queryFn||this.options.queryFn===iR?Promise.reject(new Error(`Missing queryFn: '${this.options.queryHash}'`)):(jt(this,zh,!1),this.options.persister?this.options.persister(this.options.queryFn,i,this):this.options.queryFn(i)),a={fetchOptions:n,options:this.options,queryKey:this.queryKey,state:this.state,fetchFn:o};s(a),(c=this.options.behavior)==null||c.onFetch(a,this),jt(this,C0,this.state),(this.state.fetchStatus==="idle"||this.state.fetchMeta!==((f=a.fetchOptions)==null?void 0:f.meta))&&jn(this,Nl,hu).call(this,{type:"fetch",meta:(p=a.fetchOptions)==null?void 0:p.meta});const l=g=>{var v,x,_,b;WE(g)&&g.silent||jn(this,Nl,hu).call(this,{type:"error",error:g}),WE(g)||((x=(v=Ae(this,qa).config).onError)==null||x.call(v,g,this),(b=(_=Ae(this,qa).config).onSettled)==null||b.call(_,this.state.data,g,this)),this.isFetchingOptimistic||this.scheduleGc(),this.isFetchingOptimistic=!1};return jt(this,lo,J8({fn:a.fetchFn,abort:r.abort.bind(r),onSuccess:g=>{var v,x,_,b;if(g===void 0){l(new Error(`${this.queryHash} data is undefined`));return}this.setData(g),(x=(v=Ae(this,qa).config).onSuccess)==null||x.call(v,g,this),(b=(_=Ae(this,qa).config).onSettled)==null||b.call(_,g,this.state.error,this),this.isFetchingOptimistic||this.scheduleGc(),this.isFetchingOptimistic=!1},onError:l,onFail:(g,v)=>{jn(this,Nl,hu).call(this,{type:"failed",failureCount:g,error:v})},onPause:()=>{jn(this,Nl,hu).call(this,{type:"pause"})},onContinue:()=>{jn(this,Nl,hu).call(this,{type:"continue"})},retry:a.options.retry,retryDelay:a.options.retryDelay,networkMode:a.options.networkMode,canRun:()=>!0})),Ae(this,lo).start()}},E0=new WeakMap,C0=new WeakMap,qa=new WeakMap,lo=new WeakMap,Ay=new WeakMap,zh=new WeakMap,Nl=new WeakSet,hu=function(e){const n=r=>{switch(e.type){case"failed":return{...r,fetchFailureCount:e.failureCount,fetchFailureReason:e.error};case"pause":return{...r,fetchStatus:"paused"};case"continue":return{...r,fetchStatus:"fetching"};case"fetch":return{...r,...t7(r.data,this.options),fetchMeta:e.meta??null};case"success":return{...r,data:e.data,dataUpdateCount:r.dataUpdateCount+1,dataUpdatedAt:e.dataUpdatedAt??Date.now(),error:null,isInvalidated:!1,status:"success",...!e.manual&&{fetchStatus:"idle",fetchFailureCount:0,fetchFailureReason:null}};case"error":const i=e.error;return WE(i)&&i.revert&&Ae(this,C0)?{...Ae(this,C0),fetchStatus:"idle"}:{...r,error:i,errorUpdateCount:r.errorUpdateCount+1,errorUpdatedAt:Date.now(),fetchFailureCount:r.fetchFailureCount+1,fetchFailureReason:i,fetchStatus:"idle",status:"error"};case"invalidate":return{...r,isInvalidated:!0};case"setState":return{...r,...e.state}}};this.state=n(this.state),Ji.batch(()=>{this.observers.forEach(r=>{r.onQueryUpdate()}),Ae(this,qa).notify({query:this,type:"updated",action:e})})},AD);function t7(t,e){return{fetchFailureCount:0,fetchFailureReason:null,fetchStatus:K8(e.networkMode)?"fetching":"paused",...t===void 0&&{error:null,status:"pending"}}}function bQ(t){const e=typeof t.initialData=="function"?t.initialData():t.initialData,n=e!==void 0,r=n?typeof t.initialDataUpdatedAt=="function"?t.initialDataUpdatedAt():t.initialDataUpdatedAt:0;return{data:e,dataUpdateCount:0,dataUpdatedAt:n?r??Date.now():0,error:null,errorUpdateCount:0,errorUpdatedAt:0,fetchFailureCount:0,fetchFailureReason:null,fetchMeta:null,isInvalidated:!1,status:n?"success":"pending",fetchStatus:"idle"}}var vc,RD,SQ=(RD=class extends mg{constructor(e={}){super();rn(this,vc,void 0);this.config=e,jt(this,vc,new Map)}build(e,n,r){const i=n.queryKey,s=n.queryHash??rR(i,n);let o=this.get(s);return o||(o=new _Q({cache:this,queryKey:i,queryHash:s,options:e.defaultQueryOptions(n),state:r,defaultOptions:e.getQueryDefaults(i)}),this.add(o)),o}add(e){Ae(this,vc).has(e.queryHash)||(Ae(this,vc).set(e.queryHash,e),this.notify({type:"added",query:e}))}remove(e){const n=Ae(this,vc).get(e.queryHash);n&&(e.destroy(),n===e&&Ae(this,vc).delete(e.queryHash),this.notify({type:"removed",query:e}))}clear(){Ji.batch(()=>{this.getAll().forEach(e=>{this.remove(e)})})}get(e){return Ae(this,vc).get(e)}getAll(){return[...Ae(this,vc).values()]}find(e){const n={exact:!0,...e};return this.getAll().find(r=>CL(n,r))}findAll(e={}){const n=this.getAll();return Object.keys(e).length>0?n.filter(r=>CL(e,r)):n}notify(e){Ji.batch(()=>{this.listeners.forEach(n=>{n(e)})})}onFocus(){Ji.batch(()=>{this.getAll().forEach(e=>{e.onFocus()})})}onOnline(){Ji.batch(()=>{this.getAll().forEach(e=>{e.onOnline()})})}},vc=new WeakMap,RD),yc,co,Bh,xc,Ld,PD,wQ=(PD=class extends e7{constructor(e){super();rn(this,xc);rn(this,yc,void 0);rn(this,co,void 0);rn(this,Bh,void 0);this.mutationId=e.mutationId,jt(this,co,e.mutationCache),jt(this,yc,[]),this.state=e.state||n7(),this.setOptions(e.options),this.scheduleGc()}setOptions(e){this.options=e,this.updateGcTime(this.options.gcTime)}get meta(){return this.options.meta}addObserver(e){Ae(this,yc).includes(e)||(Ae(this,yc).push(e),this.clearGcTimeout(),Ae(this,co).notify({type:"observerAdded",mutation:this,observer:e}))}removeObserver(e){jt(this,yc,Ae(this,yc).filter(n=>n!==e)),this.scheduleGc(),Ae(this,co).notify({type:"observerRemoved",mutation:this,observer:e})}optionalRemove(){Ae(this,yc).length||(this.state.status==="pending"?this.scheduleGc():Ae(this,co).remove(this))}continue(){var e;return((e=Ae(this,Bh))==null?void 0:e.continue())??this.execute(this.state.variables)}async execute(e){var i,s,o,a,l,c,f,p,g,v,x,_,b,y,S,w,T,L,R,P;jt(this,Bh,J8({fn:()=>this.options.mutationFn?this.options.mutationFn(e):Promise.reject(new Error("No mutationFn found")),onFail:(F,O)=>{jn(this,xc,Ld).call(this,{type:"failed",failureCount:F,error:O})},onPause:()=>{jn(this,xc,Ld).call(this,{type:"pause"})},onContinue:()=>{jn(this,xc,Ld).call(this,{type:"continue"})},retry:this.options.retry??0,retryDelay:this.options.retryDelay,networkMode:this.options.networkMode,canRun:()=>Ae(this,co).canRun(this)}));const n=this.state.status==="pending",r=!Ae(this,Bh).canStart();try{if(!n){jn(this,xc,Ld).call(this,{type:"pending",variables:e,isPaused:r}),await((s=(i=Ae(this,co).config).onMutate)==null?void 0:s.call(i,e,this));const O=await((a=(o=this.options).onMutate)==null?void 0:a.call(o,e));O!==this.state.context&&jn(this,xc,Ld).call(this,{type:"pending",context:O,variables:e,isPaused:r})}const F=await Ae(this,Bh).start();return await((c=(l=Ae(this,co).config).onSuccess)==null?void 0:c.call(l,F,e,this.state.context,this)),await((p=(f=this.options).onSuccess)==null?void 0:p.call(f,F,e,this.state.context)),await((v=(g=Ae(this,co).config).onSettled)==null?void 0:v.call(g,F,null,this.state.variables,this.state.context,this)),await((_=(x=this.options).onSettled)==null?void 0:_.call(x,F,null,e,this.state.context)),jn(this,xc,Ld).call(this,{type:"success",data:F}),F}catch(F){try{throw await((y=(b=Ae(this,co).config).onError)==null?void 0:y.call(b,F,e,this.state.context,this)),await((w=(S=this.options).onError)==null?void 0:w.call(S,F,e,this.state.context)),await((L=(T=Ae(this,co).config).onSettled)==null?void 0:L.call(T,void 0,F,this.state.variables,this.state.context,this)),await((P=(R=this.options).onSettled)==null?void 0:P.call(R,void 0,F,e,this.state.context)),F}finally{jn(this,xc,Ld).call(this,{type:"error",error:F})}}finally{Ae(this,co).runNext(this)}}},yc=new WeakMap,co=new WeakMap,Bh=new WeakMap,xc=new WeakSet,Ld=function(e){const n=r=>{switch(e.type){case"failed":return{...r,failureCount:e.failureCount,failureReason:e.error};case"pause":return{...r,isPaused:!0};case"continue":return{...r,isPaused:!1};case"pending":return{...r,context:e.context,data:void 0,failureCount:0,failureReason:null,error:null,isPaused:e.isPaused,status:"pending",variables:e.variables,submittedAt:Date.now()};case"success":return{...r,data:e.data,failureCount:0,failureReason:null,error:null,status:"success",isPaused:!1};case"error":return{...r,data:void 0,error:e.error,failureCount:r.failureCount+1,failureReason:e.error,isPaused:!1,status:"error"}}};this.state=n(this.state),Ji.batch(()=>{Ae(this,yc).forEach(r=>{r.onMutationUpdate(e)}),Ae(this,co).notify({mutation:this,type:"updated",action:e})})},PD);function n7(){return{context:void 0,data:void 0,error:null,failureCount:0,failureReason:null,isPaused:!1,status:"idle",variables:void 0,submittedAt:0}}var ha,Ry,ID,MQ=(ID=class extends mg{constructor(e={}){super();rn(this,ha,void 0);rn(this,Ry,void 0);this.config=e,jt(this,ha,new Map),jt(this,Ry,Date.now())}build(e,n,r){const i=new wQ({mutationCache:this,mutationId:++S_(this,Ry)._,options:e.defaultMutationOptions(n),state:r});return this.add(i),i}add(e){const n=j_(e),r=Ae(this,ha).get(n)??[];r.push(e),Ae(this,ha).set(n,r),this.notify({type:"added",mutation:e})}remove(e){var r;const n=j_(e);if(Ae(this,ha).has(n)){const i=(r=Ae(this,ha).get(n))==null?void 0:r.filter(s=>s!==e);i&&(i.length===0?Ae(this,ha).delete(n):Ae(this,ha).set(n,i))}this.notify({type:"removed",mutation:e})}canRun(e){var r;const n=(r=Ae(this,ha).get(j_(e)))==null?void 0:r.find(i=>i.state.status==="pending");return!n||n===e}runNext(e){var r;const n=(r=Ae(this,ha).get(j_(e)))==null?void 0:r.find(i=>i!==e&&i.state.isPaused);return(n==null?void 0:n.continue())??Promise.resolve()}clear(){Ji.batch(()=>{this.getAll().forEach(e=>{this.remove(e)})})}getAll(){return[...Ae(this,ha).values()].flat()}find(e){const n={exact:!0,...e};return this.getAll().find(r=>TL(n,r))}findAll(e={}){return this.getAll().filter(n=>TL(e,n))}notify(e){Ji.batch(()=>{this.listeners.forEach(n=>{n(e)})})}resumePausedMutations(){const e=this.getAll().filter(n=>n.state.isPaused);return Ji.batch(()=>Promise.all(e.map(n=>n.continue().catch(Ya))))}},ha=new WeakMap,Ry=new WeakMap,ID);function j_(t){var e;return((e=t.options.scope)==null?void 0:e.id)??String(t.mutationId)}function EQ(t){return{onFetch:(e,n)=>{const r=async()=>{var x,_,b,y,S;const i=e.options,s=(b=(_=(x=e.fetchOptions)==null?void 0:x.meta)==null?void 0:_.fetchMore)==null?void 0:b.direction,o=((y=e.state.data)==null?void 0:y.pages)||[],a=((S=e.state.data)==null?void 0:S.pageParams)||[],l={pages:[],pageParams:[]};let c=!1;const f=w=>{Object.defineProperty(w,"signal",{enumerable:!0,get:()=>(e.signal.aborted?c=!0:e.signal.addEventListener("abort",()=>{c=!0}),e.signal)})},p=e.options.queryFn&&e.options.queryFn!==iR?e.options.queryFn:()=>Promise.reject(new Error(`Missing queryFn: '${e.options.queryHash}'`)),g=async(w,T,L)=>{if(c)return Promise.reject();if(T==null&&w.pages.length)return Promise.resolve(w);const R={queryKey:e.queryKey,pageParam:T,direction:L?"backward":"forward",meta:e.options.meta};f(R);const P=await p(R),{maxPages:F}=e.options,O=L?mQ:pQ;return{pages:O(w.pages,P,F),pageParams:O(w.pageParams,T,F)}};let v;if(s&&o.length){const w=s==="backward",T=w?CQ:PL,L={pages:o,pageParams:a},R=T(i,L);v=await g(L,R,w)}else{v=await g(l,a[0]??i.initialPageParam);const w=t??o.length;for(let T=1;T{var i,s;return(s=(i=e.options).persister)==null?void 0:s.call(i,r,{queryKey:e.queryKey,meta:e.options.meta,signal:e.signal},n)}:e.fetchFn=r}}}function PL(t,{pages:e,pageParams:n}){const r=e.length-1;return t.getNextPageParam(e[r],e,n[r],n)}function CQ(t,{pages:e,pageParams:n}){var r;return(r=t.getPreviousPageParam)==null?void 0:r.call(t,e[0],e,n[0],n)}var _i,Hd,$d,T0,A0,Vd,R0,P0,LD,TQ=(LD=class{constructor(t={}){rn(this,_i,void 0);rn(this,Hd,void 0);rn(this,$d,void 0);rn(this,T0,void 0);rn(this,A0,void 0);rn(this,Vd,void 0);rn(this,R0,void 0);rn(this,P0,void 0);jt(this,_i,t.queryCache||new SQ),jt(this,Hd,t.mutationCache||new MQ),jt(this,$d,t.defaultOptions||{}),jt(this,T0,new Map),jt(this,A0,new Map),jt(this,Vd,0)}mount(){S_(this,Vd)._++,Ae(this,Vd)===1&&(jt(this,R0,sR.subscribe(async t=>{t&&(await this.resumePausedMutations(),Ae(this,_i).onFocus())})),jt(this,P0,d2.subscribe(async t=>{t&&(await this.resumePausedMutations(),Ae(this,_i).onOnline())})))}unmount(){var t,e;S_(this,Vd)._--,Ae(this,Vd)===0&&((t=Ae(this,R0))==null||t.call(this),jt(this,R0,void 0),(e=Ae(this,P0))==null||e.call(this),jt(this,P0,void 0))}isFetching(t){return Ae(this,_i).findAll({...t,fetchStatus:"fetching"}).length}isMutating(t){return Ae(this,Hd).findAll({...t,status:"pending"}).length}getQueryData(t){var n;const e=this.defaultQueryOptions({queryKey:t});return(n=Ae(this,_i).get(e.queryHash))==null?void 0:n.state.data}ensureQueryData(t){const e=this.getQueryData(t.queryKey);if(e===void 0)return this.fetchQuery(t);{const n=this.defaultQueryOptions(t),r=Ae(this,_i).build(this,n);return t.revalidateIfStale&&r.isStaleByTime(n.staleTime)&&this.prefetchQuery(n),Promise.resolve(e)}}getQueriesData(t){return Ae(this,_i).findAll(t).map(({queryKey:e,state:n})=>{const r=n.data;return[e,r]})}setQueryData(t,e,n){const r=this.defaultQueryOptions({queryKey:t}),i=Ae(this,_i).get(r.queryHash),s=i==null?void 0:i.state.data,o=fQ(e,s);if(o!==void 0)return Ae(this,_i).build(this,r).setData(o,{...n,manual:!0})}setQueriesData(t,e,n){return Ji.batch(()=>Ae(this,_i).findAll(t).map(({queryKey:r})=>[r,this.setQueryData(r,e,n)]))}getQueryState(t){var n;const e=this.defaultQueryOptions({queryKey:t});return(n=Ae(this,_i).get(e.queryHash))==null?void 0:n.state}removeQueries(t){const e=Ae(this,_i);Ji.batch(()=>{e.findAll(t).forEach(n=>{e.remove(n)})})}resetQueries(t,e){const n=Ae(this,_i),r={type:"active",...t};return Ji.batch(()=>(n.findAll(t).forEach(i=>{i.reset()}),this.refetchQueries(r,e)))}cancelQueries(t={},e={}){const n={revert:!0,...e},r=Ji.batch(()=>Ae(this,_i).findAll(t).map(i=>i.cancel(n)));return Promise.all(r).then(Ya).catch(Ya)}invalidateQueries(t={},e={}){return Ji.batch(()=>{if(Ae(this,_i).findAll(t).forEach(r=>{r.invalidate()}),t.refetchType==="none")return Promise.resolve();const n={...t,type:t.refetchType??t.type??"active"};return this.refetchQueries(n,e)})}refetchQueries(t={},e){const n={...e,cancelRefetch:(e==null?void 0:e.cancelRefetch)??!0},r=Ji.batch(()=>Ae(this,_i).findAll(t).filter(i=>!i.isDisabled()).map(i=>{let s=i.fetch(void 0,n);return n.throwOnError||(s=s.catch(Ya)),i.state.fetchStatus==="paused"?Promise.resolve():s}));return Promise.all(r).then(Ya)}fetchQuery(t){const e=this.defaultQueryOptions(t);e.retry===void 0&&(e.retry=!1);const n=Ae(this,_i).build(this,e);return n.isStaleByTime(e.staleTime)?n.fetch(e):Promise.resolve(n.state.data)}prefetchQuery(t){return this.fetchQuery(t).then(Ya).catch(Ya)}fetchInfiniteQuery(t){return t.behavior=EQ(t.pages),this.fetchQuery(t)}prefetchInfiniteQuery(t){return this.fetchInfiniteQuery(t).then(Ya).catch(Ya)}resumePausedMutations(){return d2.isOnline()?Ae(this,Hd).resumePausedMutations():Promise.resolve()}getQueryCache(){return Ae(this,_i)}getMutationCache(){return Ae(this,Hd)}getDefaultOptions(){return Ae(this,$d)}setDefaultOptions(t){jt(this,$d,t)}setQueryDefaults(t,e){Ae(this,T0).set(cp(t),{queryKey:t,defaultOptions:e})}getQueryDefaults(t){const e=[...Ae(this,T0).values()];let n={};return e.forEach(r=>{Kv(t,r.queryKey)&&(n={...n,...r.defaultOptions})}),n}setMutationDefaults(t,e){Ae(this,A0).set(cp(t),{mutationKey:t,defaultOptions:e})}getMutationDefaults(t){const e=[...Ae(this,A0).values()];let n={};return e.forEach(r=>{Kv(t,r.mutationKey)&&(n={...n,...r.defaultOptions})}),n}defaultQueryOptions(t){if(t._defaulted)return t;const e={...Ae(this,$d).queries,...this.getQueryDefaults(t.queryKey),...t,_defaulted:!0};return e.queryHash||(e.queryHash=rR(e.queryKey,e)),e.refetchOnReconnect===void 0&&(e.refetchOnReconnect=e.networkMode!=="always"),e.throwOnError===void 0&&(e.throwOnError=!!e.suspense),!e.networkMode&&e.persister&&(e.networkMode="offlineFirst"),e.enabled!==!0&&e.queryFn===iR&&(e.enabled=!1),e}defaultMutationOptions(t){return t!=null&&t._defaulted?t:{...Ae(this,$d).mutations,...(t==null?void 0:t.mutationKey)&&this.getMutationDefaults(t.mutationKey),...t,_defaulted:!0}}clear(){Ae(this,_i).clear(),Ae(this,Hd).clear()}},_i=new WeakMap,Hd=new WeakMap,$d=new WeakMap,T0=new WeakMap,A0=new WeakMap,Vd=new WeakMap,R0=new WeakMap,P0=new WeakMap,LD),ko,Br,Py,uo,Hh,I0,_c,Iy,L0,k0,$h,Vh,Wd,O0,Wh,J1,Ly,yT,ky,xT,Oy,_T,Ny,bT,Dy,ST,Fy,wT,Uy,MT,P2,r7,kD,AQ=(kD=class extends mg{constructor(e,n){super();rn(this,Wh);rn(this,Ly);rn(this,ky);rn(this,Oy);rn(this,Ny);rn(this,Dy);rn(this,Fy);rn(this,Uy);rn(this,P2);rn(this,ko,void 0);rn(this,Br,void 0);rn(this,Py,void 0);rn(this,uo,void 0);rn(this,Hh,void 0);rn(this,I0,void 0);rn(this,_c,void 0);rn(this,Iy,void 0);rn(this,L0,void 0);rn(this,k0,void 0);rn(this,$h,void 0);rn(this,Vh,void 0);rn(this,Wd,void 0);rn(this,O0,new Set);this.options=n,jt(this,ko,e),jt(this,_c,null),this.bindMethods(),this.setOptions(n)}bindMethods(){this.refetch=this.refetch.bind(this)}onSubscribe(){this.listeners.size===1&&(Ae(this,Br).addObserver(this),IL(Ae(this,Br),this.options)?jn(this,Wh,J1).call(this):this.updateResult(),jn(this,Ny,bT).call(this))}onUnsubscribe(){this.hasListeners()||this.destroy()}shouldFetchOnReconnect(){return ET(Ae(this,Br),this.options,this.options.refetchOnReconnect)}shouldFetchOnWindowFocus(){return ET(Ae(this,Br),this.options,this.options.refetchOnWindowFocus)}destroy(){this.listeners=new Set,jn(this,Dy,ST).call(this),jn(this,Fy,wT).call(this),Ae(this,Br).removeObserver(this)}setOptions(e,n){const r=this.options,i=Ae(this,Br);if(this.options=Ae(this,ko).defaultQueryOptions(e),this.options.enabled!==void 0&&typeof this.options.enabled!="boolean")throw new Error("Expected enabled to be a boolean");jn(this,Uy,MT).call(this),Ae(this,Br).setOptions(this.options),r._defaulted&&!u2(this.options,r)&&Ae(this,ko).getQueryCache().notify({type:"observerOptionsUpdated",query:Ae(this,Br),observer:this});const s=this.hasListeners();s&&LL(Ae(this,Br),i,this.options,r)&&jn(this,Wh,J1).call(this),this.updateResult(n),s&&(Ae(this,Br)!==i||this.options.enabled!==r.enabled||this.options.staleTime!==r.staleTime)&&jn(this,Ly,yT).call(this);const o=jn(this,ky,xT).call(this);s&&(Ae(this,Br)!==i||this.options.enabled!==r.enabled||o!==Ae(this,Wd))&&jn(this,Oy,_T).call(this,o)}getOptimisticResult(e){const n=Ae(this,ko).getQueryCache().build(Ae(this,ko),e),r=this.createResult(n,e);return PQ(this,r)&&(jt(this,uo,r),jt(this,I0,this.options),jt(this,Hh,Ae(this,Br).state)),r}getCurrentResult(){return Ae(this,uo)}trackResult(e,n){const r={};return Object.keys(e).forEach(i=>{Object.defineProperty(r,i,{configurable:!1,enumerable:!0,get:()=>(this.trackProp(i),n==null||n(i),e[i])})}),r}trackProp(e){Ae(this,O0).add(e)}getCurrentQuery(){return Ae(this,Br)}refetch({...e}={}){return this.fetch({...e})}fetchOptimistic(e){const n=Ae(this,ko).defaultQueryOptions(e),r=Ae(this,ko).getQueryCache().build(Ae(this,ko),n);return r.isFetchingOptimistic=!0,r.fetch().then(()=>this.createResult(r,n))}fetch(e){return jn(this,Wh,J1).call(this,{...e,cancelRefetch:e.cancelRefetch??!0}).then(()=>(this.updateResult(),Ae(this,uo)))}createResult(e,n){var P;const r=Ae(this,Br),i=this.options,s=Ae(this,uo),o=Ae(this,Hh),a=Ae(this,I0),c=e!==r?e.state:Ae(this,Py),{state:f}=e;let p={...f},g=!1,v;if(n._optimisticResults){const F=this.hasListeners(),O=!F&&IL(e,n),I=F&&LL(e,r,n,i);(O||I)&&(p={...p,...t7(f.data,e.options)}),n._optimisticResults==="isRestoring"&&(p.fetchStatus="idle")}let{error:x,errorUpdatedAt:_,status:b}=p;if(n.select&&p.data!==void 0)if(s&&p.data===(o==null?void 0:o.data)&&n.select===Ae(this,Iy))v=Ae(this,L0);else try{jt(this,Iy,n.select),v=n.select(p.data),v=vT(s==null?void 0:s.data,v,n),jt(this,L0,v),jt(this,_c,null)}catch(F){jt(this,_c,F)}else v=p.data;if(n.placeholderData!==void 0&&v===void 0&&b==="pending"){let F;if(s!=null&&s.isPlaceholderData&&n.placeholderData===(a==null?void 0:a.placeholderData))F=s.data;else if(F=typeof n.placeholderData=="function"?n.placeholderData((P=Ae(this,k0))==null?void 0:P.state.data,Ae(this,k0)):n.placeholderData,n.select&&F!==void 0)try{F=n.select(F),jt(this,_c,null)}catch(O){jt(this,_c,O)}F!==void 0&&(b="success",v=vT(s==null?void 0:s.data,F,n),g=!0)}Ae(this,_c)&&(x=Ae(this,_c),v=Ae(this,L0),_=Date.now(),b="error");const y=p.fetchStatus==="fetching",S=b==="pending",w=b==="error",T=S&&y,L=v!==void 0;return{status:b,fetchStatus:p.fetchStatus,isPending:S,isSuccess:b==="success",isError:w,isInitialLoading:T,isLoading:T,data:v,dataUpdatedAt:p.dataUpdatedAt,error:x,errorUpdatedAt:_,failureCount:p.fetchFailureCount,failureReason:p.fetchFailureReason,errorUpdateCount:p.errorUpdateCount,isFetched:p.dataUpdateCount>0||p.errorUpdateCount>0,isFetchedAfterMount:p.dataUpdateCount>c.dataUpdateCount||p.errorUpdateCount>c.errorUpdateCount,isFetching:y,isRefetching:y&&!S,isLoadingError:w&&!L,isPaused:p.fetchStatus==="paused",isPlaceholderData:g,isRefetchError:w&&L,isStale:oR(e,n),refetch:this.refetch}}updateResult(e){const n=Ae(this,uo),r=this.createResult(Ae(this,Br),this.options);if(jt(this,Hh,Ae(this,Br).state),jt(this,I0,this.options),Ae(this,Hh).data!==void 0&&jt(this,k0,Ae(this,Br)),u2(r,n))return;jt(this,uo,r);const i={},s=()=>{if(!n)return!0;const{notifyOnChangeProps:o}=this.options,a=typeof o=="function"?o():o;if(a==="all"||!a&&!Ae(this,O0).size)return!0;const l=new Set(a??Ae(this,O0));return this.options.throwOnError&&l.add("error"),Object.keys(Ae(this,uo)).some(c=>{const f=c;return Ae(this,uo)[f]!==n[f]&&l.has(f)})};(e==null?void 0:e.listeners)!==!1&&s()&&(i.listeners=!0),jn(this,P2,r7).call(this,{...i,...e})}onQueryUpdate(){this.updateResult(),this.hasListeners()&&jn(this,Ny,bT).call(this)}},ko=new WeakMap,Br=new WeakMap,Py=new WeakMap,uo=new WeakMap,Hh=new WeakMap,I0=new WeakMap,_c=new WeakMap,Iy=new WeakMap,L0=new WeakMap,k0=new WeakMap,$h=new WeakMap,Vh=new WeakMap,Wd=new WeakMap,O0=new WeakMap,Wh=new WeakSet,J1=function(e){jn(this,Uy,MT).call(this);let n=Ae(this,Br).fetch(this.options,e);return e!=null&&e.throwOnError||(n=n.catch(Ya)),n},Ly=new WeakSet,yT=function(){if(jn(this,Dy,ST).call(this),W0||Ae(this,uo).isStale||!mT(this.options.staleTime))return;const n=Z8(Ae(this,uo).dataUpdatedAt,this.options.staleTime)+1;jt(this,$h,setTimeout(()=>{Ae(this,uo).isStale||this.updateResult()},n))},ky=new WeakSet,xT=function(){return(typeof this.options.refetchInterval=="function"?this.options.refetchInterval(Ae(this,Br)):this.options.refetchInterval)??!1},Oy=new WeakSet,_T=function(e){jn(this,Fy,wT).call(this),jt(this,Wd,e),!(W0||this.options.enabled===!1||!mT(Ae(this,Wd))||Ae(this,Wd)===0)&&jt(this,Vh,setInterval(()=>{(this.options.refetchIntervalInBackground||sR.isFocused())&&jn(this,Wh,J1).call(this)},Ae(this,Wd)))},Ny=new WeakSet,bT=function(){jn(this,Ly,yT).call(this),jn(this,Oy,_T).call(this,jn(this,ky,xT).call(this))},Dy=new WeakSet,ST=function(){Ae(this,$h)&&(clearTimeout(Ae(this,$h)),jt(this,$h,void 0))},Fy=new WeakSet,wT=function(){Ae(this,Vh)&&(clearInterval(Ae(this,Vh)),jt(this,Vh,void 0))},Uy=new WeakSet,MT=function(){const e=Ae(this,ko).getQueryCache().build(Ae(this,ko),this.options);if(e===Ae(this,Br))return;const n=Ae(this,Br);jt(this,Br,e),jt(this,Py,e.state),this.hasListeners()&&(n==null||n.removeObserver(this),e.addObserver(this))},P2=new WeakSet,r7=function(e){Ji.batch(()=>{e.listeners&&this.listeners.forEach(n=>{n(Ae(this,uo))}),Ae(this,ko).getQueryCache().notify({query:Ae(this,Br),type:"observerResultsUpdated"})})},kD);function RQ(t,e){return e.enabled!==!1&&t.state.data===void 0&&!(t.state.status==="error"&&e.retryOnMount===!1)}function IL(t,e){return RQ(t,e)||t.state.data!==void 0&&ET(t,e,e.refetchOnMount)}function ET(t,e,n){if(e.enabled!==!1){const r=typeof n=="function"?n(t):n;return r==="always"||r!==!1&&oR(t,e)}return!1}function LL(t,e,n,r){return(t!==e||r.enabled===!1)&&(!n.suspense||t.state.status!=="error")&&oR(t,n)}function oR(t,e){return e.enabled!==!1&&t.isStaleByTime(e.staleTime)}function PQ(t,e){return!u2(t.getCurrentResult(),e)}var jd,Gd,Oo,vu,N0,MS,zy,CT,OD,IQ=(OD=class extends mg{constructor(n,r){super();rn(this,N0);rn(this,zy);rn(this,jd,void 0);rn(this,Gd,void 0);rn(this,Oo,void 0);rn(this,vu,void 0);jt(this,jd,n),this.setOptions(r),this.bindMethods(),jn(this,N0,MS).call(this)}bindMethods(){this.mutate=this.mutate.bind(this),this.reset=this.reset.bind(this)}setOptions(n){var i;const r=this.options;this.options=Ae(this,jd).defaultMutationOptions(n),u2(this.options,r)||Ae(this,jd).getMutationCache().notify({type:"observerOptionsUpdated",mutation:Ae(this,Oo),observer:this}),r!=null&&r.mutationKey&&this.options.mutationKey&&cp(r.mutationKey)!==cp(this.options.mutationKey)?this.reset():((i=Ae(this,Oo))==null?void 0:i.state.status)==="pending"&&Ae(this,Oo).setOptions(this.options)}onUnsubscribe(){var n;this.hasListeners()||(n=Ae(this,Oo))==null||n.removeObserver(this)}onMutationUpdate(n){jn(this,N0,MS).call(this),jn(this,zy,CT).call(this,n)}getCurrentResult(){return Ae(this,Gd)}reset(){var n;(n=Ae(this,Oo))==null||n.removeObserver(this),jt(this,Oo,void 0),jn(this,N0,MS).call(this),jn(this,zy,CT).call(this)}mutate(n,r){var i;return jt(this,vu,r),(i=Ae(this,Oo))==null||i.removeObserver(this),jt(this,Oo,Ae(this,jd).getMutationCache().build(Ae(this,jd),this.options)),Ae(this,Oo).addObserver(this),Ae(this,Oo).execute(n)}},jd=new WeakMap,Gd=new WeakMap,Oo=new WeakMap,vu=new WeakMap,N0=new WeakSet,MS=function(){var r;const n=((r=Ae(this,Oo))==null?void 0:r.state)??n7();jt(this,Gd,{...n,isPending:n.status==="pending",isSuccess:n.status==="success",isError:n.status==="error",isIdle:n.status==="idle",mutate:this.mutate,reset:this.reset})},zy=new WeakSet,CT=function(n){Ji.batch(()=>{var r,i,s,o,a,l,c,f;if(Ae(this,vu)&&this.hasListeners()){const p=Ae(this,Gd).variables,g=Ae(this,Gd).context;(n==null?void 0:n.type)==="success"?((i=(r=Ae(this,vu)).onSuccess)==null||i.call(r,n.data,p,g),(o=(s=Ae(this,vu)).onSettled)==null||o.call(s,n.data,null,p,g)):(n==null?void 0:n.type)==="error"&&((l=(a=Ae(this,vu)).onError)==null||l.call(a,n.error,p,g),(f=(c=Ae(this,vu)).onSettled)==null||f.call(c,void 0,n.error,p,g))}this.listeners.forEach(p=>{p(Ae(this,Gd))})})},OD),i7=D.createContext(void 0),mf=t=>{const e=D.useContext(i7);if(t)return t;if(!e)throw new Error("No QueryClient set, use QueryClientProvider to set one");return e},LQ=({client:t,children:e})=>(D.useEffect(()=>(t.mount(),()=>{t.unmount()}),[t]),C.jsx(i7.Provider,{value:t,children:e})),s7=D.createContext(!1),kQ=()=>D.useContext(s7);s7.Provider;function OQ(){let t=!1;return{clearReset:()=>{t=!1},reset:()=>{t=!0},isReset:()=>t}}var NQ=D.createContext(OQ()),DQ=()=>D.useContext(NQ);function o7(t,e){return typeof t=="function"?t(...e):!!t}function FQ(){}var UQ=(t,e)=>{(t.suspense||t.throwOnError)&&(e.isReset()||(t.retryOnMount=!1))},zQ=t=>{D.useEffect(()=>{t.clearReset()},[t])},BQ=({result:t,errorResetBoundary:e,throwOnError:n,query:r})=>t.isError&&!e.isReset()&&!t.isFetching&&r&&o7(n,[t.error,r]),HQ=t=>{t.suspense&&typeof t.staleTime!="number"&&(t.staleTime=1e3)},$Q=(t,e)=>(t==null?void 0:t.suspense)&&e.isPending,VQ=(t,e,n)=>e.fetchOptimistic(t).catch(()=>{n.clearReset()});function WQ(t,e,n){const r=mf(n),i=kQ(),s=DQ(),o=r.defaultQueryOptions(t);o._optimisticResults=i?"isRestoring":"optimistic",HQ(o),UQ(o,s),zQ(s);const[a]=D.useState(()=>new e(r,o)),l=a.getOptimisticResult(o);if(D.useSyncExternalStore(D.useCallback(c=>{const f=i?()=>{}:a.subscribe(Ji.batchCalls(c));return a.updateResult(),f},[a,i]),()=>a.getCurrentResult(),()=>a.getCurrentResult()),D.useEffect(()=>{a.setOptions(o,{listeners:!1})},[o,a]),$Q(o,l))throw VQ(o,a,s);if(BQ({result:l,errorResetBoundary:s,throwOnError:o.throwOnError,query:r.getQueryCache().get(o.queryHash)}))throw l.error;return o.notifyOnChangeProps?l:a.trackResult(l)}function Hu(t,e){return WQ(t,AQ,e)}function gg(t,e){const n=mf(e),[r]=D.useState(()=>new IQ(n,t));D.useEffect(()=>{r.setOptions(t)},[r,t]);const i=D.useSyncExternalStore(D.useCallback(o=>r.subscribe(Ji.batchCalls(o)),[r]),()=>r.getCurrentResult(),()=>r.getCurrentResult()),s=D.useCallback((o,a)=>{r.mutate(o,a).catch(FQ)},[r]);if(i.error&&o7(r.options.throwOnError,[i.error]))throw i.error;return{...i,mutate:s,mutateAsync:i.mutate}}function a7(t){var e,n,r="";if(typeof t=="string"||typeof t=="number")r+=t;else if(typeof t=="object")if(Array.isArray(t)){var i=t.length;for(e=0;e{const{color:e,fontSize:n,classes:r}=t,i={root:["root",e!=="inherit"&&`color${gt(e)}`,`fontSize${gt(n)}`]};return Sn(i,jQ,r)},qQ=lt("svg",{name:"MuiSvgIcon",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.color!=="inherit"&&e[`color${gt(n.color)}`],e[`fontSize${gt(n.fontSize)}`]]}})(({theme:t,ownerState:e})=>{var n,r,i,s,o,a,l,c,f,p,g,v,x;return{userSelect:"none",width:"1em",height:"1em",display:"inline-block",fill:e.hasSvgAsChild?void 0:"currentColor",flexShrink:0,transition:(n=t.transitions)==null||(r=n.create)==null?void 0:r.call(n,"fill",{duration:(i=t.transitions)==null||(i=i.duration)==null?void 0:i.shorter}),fontSize:{inherit:"inherit",small:((s=t.typography)==null||(o=s.pxToRem)==null?void 0:o.call(s,20))||"1.25rem",medium:((a=t.typography)==null||(l=a.pxToRem)==null?void 0:l.call(a,24))||"1.5rem",large:((c=t.typography)==null||(f=c.pxToRem)==null?void 0:f.call(c,35))||"2.1875rem"}[e.fontSize],color:(p=(g=(t.vars||t).palette)==null||(g=g[e.color])==null?void 0:g.main)!=null?p:{action:(v=(t.vars||t).palette)==null||(v=v.action)==null?void 0:v.active,disabled:(x=(t.vars||t).palette)==null||(x=x.action)==null?void 0:x.disabled,inherit:void 0}[e.color]}}),TT=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiSvgIcon"}),{children:i,className:s,color:o="inherit",component:a="svg",fontSize:l="medium",htmlColor:c,inheritViewBox:f=!1,titleAccess:p,viewBox:g="0 0 24 24"}=r,v=Rt(r,GQ),x=D.isValidElement(i)&&i.type==="svg",_=X({},r,{color:o,component:a,fontSize:l,instanceFontSize:e.fontSize,inheritViewBox:f,viewBox:g,hasSvgAsChild:x}),b={};f||(b.viewBox=g);const y=XQ(_);return C.jsxs(qQ,X({as:a,className:At(y.root,s),focusable:"false",color:c,"aria-hidden":p?void 0:!0,role:p?"img":void 0,ref:n},b,v,x&&i.props,{ownerState:_,children:[x?i.props.children:i,p?C.jsx("title",{children:p}):null]}))});TT.muiName="SvgIcon";function bt(t,e){function n(r,i){return C.jsx(TT,X({"data-testid":`${e}Icon`,ref:i},r,{children:t}))}return n.muiName=TT.muiName,D.memo(D.forwardRef(n))}const ZQ={configure:t=>{Y3.configure(t)}},YQ=Object.freeze(Object.defineProperty({__proto__:null,capitalize:gt,createChainedFunction:fT,createSvgIcon:bt,debounce:Qy,deprecatedPropType:rK,isMuiElement:mv,ownerDocument:Oi,ownerWindow:Oc,requirePropFactory:iK,setRef:Yv,unstable_ClassNameGenerator:ZQ,unstable_useEnhancedEffect:Xo,unstable_useId:hg,unsupportedProp:oK,useControlled:Cu,useEventCallback:ts,useForkRef:Kr,useIsFocusVisible:Tw},Symbol.toStringTag,{value:"Module"}));var Ar={};/**
+ * @license React
+ * react-is.production.min.js
+ *
+ * Copyright (c) Facebook, Inc. and its affiliates.
+ *
+ * This source code is licensed under the MIT license found in the
+ * LICENSE file in the root directory of this source tree.
+ */var aR=Symbol.for("react.element"),lR=Symbol.for("react.portal"),Rw=Symbol.for("react.fragment"),Pw=Symbol.for("react.strict_mode"),Iw=Symbol.for("react.profiler"),Lw=Symbol.for("react.provider"),kw=Symbol.for("react.context"),KQ=Symbol.for("react.server_context"),Ow=Symbol.for("react.forward_ref"),Nw=Symbol.for("react.suspense"),Dw=Symbol.for("react.suspense_list"),Fw=Symbol.for("react.memo"),Uw=Symbol.for("react.lazy"),QQ=Symbol.for("react.offscreen"),l7;l7=Symbol.for("react.module.reference");function vl(t){if(typeof t=="object"&&t!==null){var e=t.$$typeof;switch(e){case aR:switch(t=t.type,t){case Rw:case Iw:case Pw:case Nw:case Dw:return t;default:switch(t=t&&t.$$typeof,t){case KQ:case kw:case Ow:case Uw:case Fw:case Lw:return t;default:return e}}case lR:return e}}}Ar.ContextConsumer=kw;Ar.ContextProvider=Lw;Ar.Element=aR;Ar.ForwardRef=Ow;Ar.Fragment=Rw;Ar.Lazy=Uw;Ar.Memo=Fw;Ar.Portal=lR;Ar.Profiler=Iw;Ar.StrictMode=Pw;Ar.Suspense=Nw;Ar.SuspenseList=Dw;Ar.isAsyncMode=function(){return!1};Ar.isConcurrentMode=function(){return!1};Ar.isContextConsumer=function(t){return vl(t)===kw};Ar.isContextProvider=function(t){return vl(t)===Lw};Ar.isElement=function(t){return typeof t=="object"&&t!==null&&t.$$typeof===aR};Ar.isForwardRef=function(t){return vl(t)===Ow};Ar.isFragment=function(t){return vl(t)===Rw};Ar.isLazy=function(t){return vl(t)===Uw};Ar.isMemo=function(t){return vl(t)===Fw};Ar.isPortal=function(t){return vl(t)===lR};Ar.isProfiler=function(t){return vl(t)===Iw};Ar.isStrictMode=function(t){return vl(t)===Pw};Ar.isSuspense=function(t){return vl(t)===Nw};Ar.isSuspenseList=function(t){return vl(t)===Dw};Ar.isValidElementType=function(t){return typeof t=="string"||typeof t=="function"||t===Rw||t===Iw||t===Pw||t===Nw||t===Dw||t===QQ||typeof t=="object"&&t!==null&&(t.$$typeof===Uw||t.$$typeof===Fw||t.$$typeof===Lw||t.$$typeof===kw||t.$$typeof===Ow||t.$$typeof===l7||t.getModuleId!==void 0)};Ar.typeOf=vl;function cR(t){return En}function AT(t,e){return AT=Object.setPrototypeOf?Object.setPrototypeOf.bind():function(r,i){return r.__proto__=i,r},AT(t,e)}function c7(t,e){t.prototype=Object.create(e.prototype),t.prototype.constructor=t,AT(t,e)}const kL={disabled:!1},f2=Zt.createContext(null);var JQ=function(e){return e.scrollTop},ev="unmounted",mh="exited",gh="entering",Vm="entered",RT="exiting",$u=function(t){c7(e,t);function e(r,i){var s;s=t.call(this,r,i)||this;var o=i,a=o&&!o.isMounting?r.enter:r.appear,l;return s.appearStatus=null,r.in?a?(l=mh,s.appearStatus=gh):l=Vm:r.unmountOnExit||r.mountOnEnter?l=ev:l=mh,s.state={status:l},s.nextCallback=null,s}e.getDerivedStateFromProps=function(i,s){var o=i.in;return o&&s.status===ev?{status:mh}:null};var n=e.prototype;return n.componentDidMount=function(){this.updateStatus(!0,this.appearStatus)},n.componentDidUpdate=function(i){var s=null;if(i!==this.props){var o=this.state.status;this.props.in?o!==gh&&o!==Vm&&(s=gh):(o===gh||o===Vm)&&(s=RT)}this.updateStatus(!1,s)},n.componentWillUnmount=function(){this.cancelNextCallback()},n.getTimeouts=function(){var i=this.props.timeout,s,o,a;return s=o=a=i,i!=null&&typeof i!="number"&&(s=i.exit,o=i.enter,a=i.appear!==void 0?i.appear:o),{exit:s,enter:o,appear:a}},n.updateStatus=function(i,s){if(i===void 0&&(i=!1),s!==null)if(this.cancelNextCallback(),s===gh){if(this.props.unmountOnExit||this.props.mountOnEnter){var o=this.props.nodeRef?this.props.nodeRef.current:B_.findDOMNode(this);o&&JQ(o)}this.performEnter(i)}else this.performExit();else this.props.unmountOnExit&&this.state.status===mh&&this.setState({status:ev})},n.performEnter=function(i){var s=this,o=this.props.enter,a=this.context?this.context.isMounting:i,l=this.props.nodeRef?[a]:[B_.findDOMNode(this),a],c=l[0],f=l[1],p=this.getTimeouts(),g=a?p.appear:p.enter;if(!i&&!o||kL.disabled){this.safeSetState({status:Vm},function(){s.props.onEntered(c)});return}this.props.onEnter(c,f),this.safeSetState({status:gh},function(){s.props.onEntering(c,f),s.onTransitionEnd(g,function(){s.safeSetState({status:Vm},function(){s.props.onEntered(c,f)})})})},n.performExit=function(){var i=this,s=this.props.exit,o=this.getTimeouts(),a=this.props.nodeRef?void 0:B_.findDOMNode(this);if(!s||kL.disabled){this.safeSetState({status:mh},function(){i.props.onExited(a)});return}this.props.onExit(a),this.safeSetState({status:RT},function(){i.props.onExiting(a),i.onTransitionEnd(o.exit,function(){i.safeSetState({status:mh},function(){i.props.onExited(a)})})})},n.cancelNextCallback=function(){this.nextCallback!==null&&(this.nextCallback.cancel(),this.nextCallback=null)},n.safeSetState=function(i,s){s=this.setNextCallback(s),this.setState(i,s)},n.setNextCallback=function(i){var s=this,o=!0;return this.nextCallback=function(a){o&&(o=!1,s.nextCallback=null,i(a))},this.nextCallback.cancel=function(){o=!1},this.nextCallback},n.onTransitionEnd=function(i,s){this.setNextCallback(s);var o=this.props.nodeRef?this.props.nodeRef.current:B_.findDOMNode(this),a=i==null&&!this.props.addEndListener;if(!o||a){setTimeout(this.nextCallback,0);return}if(this.props.addEndListener){var l=this.props.nodeRef?[this.nextCallback]:[o,this.nextCallback],c=l[0],f=l[1];this.props.addEndListener(c,f)}i!=null&&setTimeout(this.nextCallback,i)},n.render=function(){var i=this.state.status;if(i===ev)return null;var s=this.props,o=s.children;s.in,s.mountOnEnter,s.unmountOnExit,s.appear,s.enter,s.exit,s.timeout,s.addEndListener,s.onEnter,s.onEntering,s.onEntered,s.onExit,s.onExiting,s.onExited,s.nodeRef;var a=Rt(s,["children","in","mountOnEnter","unmountOnExit","appear","enter","exit","timeout","addEndListener","onEnter","onEntering","onEntered","onExit","onExiting","onExited","nodeRef"]);return Zt.createElement(f2.Provider,{value:null},typeof o=="function"?o(i,a):Zt.cloneElement(Zt.Children.only(o),a))},e}(Zt.Component);$u.contextType=f2;$u.propTypes={};function pm(){}$u.defaultProps={in:!1,mountOnEnter:!1,unmountOnExit:!1,appear:!1,enter:!0,exit:!0,onEnter:pm,onEntering:pm,onEntered:pm,onExit:pm,onExiting:pm,onExited:pm};$u.UNMOUNTED=ev;$u.EXITED=mh;$u.ENTERING=gh;$u.ENTERED=Vm;$u.EXITING=RT;const uR=$u;function eJ(t){if(t===void 0)throw new ReferenceError("this hasn't been initialised - super() hasn't been called");return t}function dR(t,e){var n=function(s){return e&&D.isValidElement(s)?e(s):s},r=Object.create(null);return t&&D.Children.map(t,function(i){return i}).forEach(function(i){r[i.key]=n(i)}),r}function tJ(t,e){t=t||{},e=e||{};function n(f){return f in e?e[f]:t[f]}var r=Object.create(null),i=[];for(var s in t)s in e?i.length&&(r[s]=i,i=[]):i.push(s);var o,a={};for(var l in e){if(r[l])for(o=0;ot.scrollTop;function j0(t,e){var n,r;const{timeout:i,easing:s,style:o={}}=t;return{duration:(n=o.transitionDuration)!=null?n:typeof i=="number"?i:i[e.mode]||0,easing:(r=o.transitionTimingFunction)!=null?r:typeof s=="object"?s[e.mode]:s,delay:o.transitionDelay}}function aJ(t){return bn("MuiCollapse",t)}pn("MuiCollapse",["root","horizontal","vertical","entered","hidden","wrapper","wrapperInner"]);const lJ=["addEndListener","children","className","collapsedSize","component","easing","in","onEnter","onEntered","onEntering","onExit","onExited","onExiting","orientation","style","timeout","TransitionComponent"],cJ=t=>{const{orientation:e,classes:n}=t,r={root:["root",`${e}`],entered:["entered"],hidden:["hidden"],wrapper:["wrapper",`${e}`],wrapperInner:["wrapperInner",`${e}`]};return Sn(r,aJ,n)},uJ=lt("div",{name:"MuiCollapse",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,e[n.orientation],n.state==="entered"&&e.entered,n.state==="exited"&&!n.in&&n.collapsedSize==="0px"&&e.hidden]}})(({theme:t,ownerState:e})=>X({height:0,overflow:"hidden",transition:t.transitions.create("height")},e.orientation==="horizontal"&&{height:"auto",width:0,transition:t.transitions.create("width")},e.state==="entered"&&X({height:"auto",overflow:"visible"},e.orientation==="horizontal"&&{width:"auto"}),e.state==="exited"&&!e.in&&e.collapsedSize==="0px"&&{visibility:"hidden"})),dJ=lt("div",{name:"MuiCollapse",slot:"Wrapper",overridesResolver:(t,e)=>e.wrapper})(({ownerState:t})=>X({display:"flex",width:"100%"},t.orientation==="horizontal"&&{width:"auto",height:"100%"})),fJ=lt("div",{name:"MuiCollapse",slot:"WrapperInner",overridesResolver:(t,e)=>e.wrapperInner})(({ownerState:t})=>X({width:"100%"},t.orientation==="horizontal"&&{width:"auto",height:"100%"})),d7=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiCollapse"}),{addEndListener:i,children:s,className:o,collapsedSize:a="0px",component:l,easing:c,in:f,onEnter:p,onEntered:g,onEntering:v,onExit:x,onExited:_,onExiting:b,orientation:y="vertical",style:S,timeout:w=k8.standard,TransitionComponent:T=uR}=r,L=Rt(r,lJ),R=X({},r,{orientation:y,collapsedSize:a}),P=cJ(R),F=Bu(),O=Ah(),I=D.useRef(null),H=D.useRef(),Q=typeof a=="number"?`${a}px`:a,q=y==="horizontal",le=q?"width":"height",ie=D.useRef(null),ee=Kr(n,ie),ue=pe=>Se=>{if(pe){const je=ie.current;Se===void 0?pe(je):pe(je,Se)}},z=()=>I.current?I.current[q?"clientWidth":"clientHeight"]:0,te=ue((pe,Se)=>{I.current&&q&&(I.current.style.position="absolute"),pe.style[le]=Q,p&&p(pe,Se)}),oe=ue((pe,Se)=>{const je=z();I.current&&q&&(I.current.style.position="");const{duration:it,easing:xe}=j0({style:S,timeout:w,easing:c},{mode:"enter"});if(w==="auto"){const et=F.transitions.getAutoHeightDuration(je);pe.style.transitionDuration=`${et}ms`,H.current=et}else pe.style.transitionDuration=typeof it=="string"?it:`${it}ms`;pe.style[le]=`${je}px`,pe.style.transitionTimingFunction=xe,v&&v(pe,Se)}),de=ue((pe,Se)=>{pe.style[le]="auto",g&&g(pe,Se)}),Ce=ue(pe=>{pe.style[le]=`${z()}px`,x&&x(pe)}),Le=ue(_),V=ue(pe=>{const Se=z(),{duration:je,easing:it}=j0({style:S,timeout:w,easing:c},{mode:"exit"});if(w==="auto"){const xe=F.transitions.getAutoHeightDuration(Se);pe.style.transitionDuration=`${xe}ms`,H.current=xe}else pe.style.transitionDuration=typeof je=="string"?je:`${je}ms`;pe.style[le]=Q,pe.style.transitionTimingFunction=it,b&&b(pe)}),me=pe=>{w==="auto"&&O.start(H.current||0,pe),i&&i(ie.current,pe)};return C.jsx(T,X({in:f,onEnter:te,onEntered:de,onEntering:oe,onExit:Ce,onExited:Le,onExiting:V,addEndListener:me,nodeRef:ie,timeout:w==="auto"?null:w},L,{children:(pe,Se)=>C.jsx(uJ,X({as:l,className:At(P.root,o,{entered:P.entered,exited:!f&&Q==="0px"&&P.hidden}[pe]),style:X({[q?"minWidth":"minHeight"]:Q},S),ref:ee},Se,{ownerState:X({},R,{state:pe}),children:C.jsx(dJ,{ownerState:X({},R,{state:pe}),className:P.wrapper,ref:I,children:C.jsx(fJ,{ownerState:X({},R,{state:pe}),className:P.wrapperInner,children:s})})}))}))});d7.muiSupportAuto=!0;const hJ=d7;function pJ(t){return bn("MuiPaper",t)}pn("MuiPaper",["root","rounded","outlined","elevation","elevation0","elevation1","elevation2","elevation3","elevation4","elevation5","elevation6","elevation7","elevation8","elevation9","elevation10","elevation11","elevation12","elevation13","elevation14","elevation15","elevation16","elevation17","elevation18","elevation19","elevation20","elevation21","elevation22","elevation23","elevation24"]);const mJ=["className","component","elevation","square","variant"],gJ=t=>{const{square:e,elevation:n,variant:r,classes:i}=t,s={root:["root",r,!e&&"rounded",r==="elevation"&&`elevation${n}`]};return Sn(s,pJ,i)},vJ=lt("div",{name:"MuiPaper",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,e[n.variant],!n.square&&e.rounded,n.variant==="elevation"&&e[`elevation${n.elevation}`]]}})(({theme:t,ownerState:e})=>{var n;return X({backgroundColor:(t.vars||t).palette.background.paper,color:(t.vars||t).palette.text.primary,transition:t.transitions.create("box-shadow")},!e.square&&{borderRadius:t.shape.borderRadius},e.variant==="outlined"&&{border:`1px solid ${(t.vars||t).palette.divider}`},e.variant==="elevation"&&X({boxShadow:(t.vars||t).shadows[e.elevation]},!t.vars&&t.palette.mode==="dark"&&{backgroundImage:`linear-gradient(${qn("#fff",EL(e.elevation))}, ${qn("#fff",EL(e.elevation))})`},t.vars&&{backgroundImage:(n=t.vars.overlays)==null?void 0:n[e.elevation]}))}),yJ=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiPaper"}),{className:i,component:s="div",elevation:o=1,square:a=!1,variant:l="elevation"}=r,c=Rt(r,mJ),f=X({},r,{component:s,elevation:o,square:a,variant:l}),p=gJ(f);return C.jsx(vJ,X({as:s,ownerState:f,className:At(p.root,i),ref:n},c))}),nx=yJ;function Rc(t){return typeof t=="string"}function tv(t,e,n){return t===void 0||Rc(t)?e:X({},e,{ownerState:X({},e.ownerState,n)})}function xJ(t,e,n=(r,i)=>r===i){return t.length===e.length&&t.every((r,i)=>n(r,e[i]))}const _J={disableDefaultClasses:!1},bJ=D.createContext(_J);function SJ(t){const{disableDefaultClasses:e}=D.useContext(bJ);return n=>e?"":t(n)}function gv(t,e=[]){if(t===void 0)return{};const n={};return Object.keys(t).filter(r=>r.match(/^on[A-Z]/)&&typeof t[r]=="function"&&!e.includes(r)).forEach(r=>{n[r]=t[r]}),n}function wJ(t,e,n){return typeof t=="function"?t(e,n):t}function f7(t){var e,n,r="";if(typeof t=="string"||typeof t=="number")r+=t;else if(typeof t=="object")if(Array.isArray(t)){var i=t.length;for(e=0;e!(n.match(/^on[A-Z]/)&&typeof t[n]=="function")).forEach(n=>{e[n]=t[n]}),e}function MJ(t){const{getSlotProps:e,additionalProps:n,externalSlotProps:r,externalForwardedProps:i,className:s}=t;if(!e){const v=OL(n==null?void 0:n.className,s,i==null?void 0:i.className,r==null?void 0:r.className),x=X({},n==null?void 0:n.style,i==null?void 0:i.style,r==null?void 0:r.style),_=X({},n,i,r);return v.length>0&&(_.className=v),Object.keys(x).length>0&&(_.style=x),{props:_,internalRef:void 0}}const o=gv(X({},i,r)),a=NL(r),l=NL(i),c=e(o),f=OL(c==null?void 0:c.className,n==null?void 0:n.className,s,i==null?void 0:i.className,r==null?void 0:r.className),p=X({},c==null?void 0:c.style,n==null?void 0:n.style,i==null?void 0:i.style,r==null?void 0:r.style),g=X({},c,n,l,a);return f.length>0&&(g.className=f),Object.keys(p).length>0&&(g.style=p),{props:g,internalRef:c.ref}}const EJ=["elementType","externalSlotProps","ownerState","skipResolvingSlotProps"];function Qi(t){var e;const{elementType:n,externalSlotProps:r,ownerState:i,skipResolvingSlotProps:s=!1}=t,o=Rt(t,EJ),a=s?{}:wJ(r,i),{props:l,internalRef:c}=MJ(X({},o,{externalSlotProps:a})),f=Kr(c,a==null?void 0:a.ref,(e=t.additionalProps)==null?void 0:e.ref);return tv(n,X({},l,{ref:f}),i)}function CJ(t){const{className:e,classes:n,pulsate:r=!1,rippleX:i,rippleY:s,rippleSize:o,in:a,onExited:l,timeout:c}=t,[f,p]=D.useState(!1),g=At(e,n.ripple,n.rippleVisible,r&&n.ripplePulsate),v={width:o,height:o,top:-(o/2)+s,left:-(o/2)+i},x=At(n.child,f&&n.childLeaving,r&&n.childPulsate);return!a&&!f&&p(!0),D.useEffect(()=>{if(!a&&l!=null){const _=setTimeout(l,c);return()=>{clearTimeout(_)}}},[l,a,c]),C.jsx("span",{className:g,style:v,children:C.jsx("span",{className:x})})}const Ka=pn("MuiTouchRipple",["root","ripple","rippleVisible","ripplePulsate","child","childLeaving","childPulsate"]),TJ=["center","classes","className"];let zw=t=>t,DL,FL,UL,zL;const PT=550,AJ=80,RJ=dg(DL||(DL=zw`
+ 0% {
+ transform: scale(0);
+ opacity: 0.1;
+ }
+
+ 100% {
+ transform: scale(1);
+ opacity: 0.3;
+ }
+`)),PJ=dg(FL||(FL=zw`
+ 0% {
+ opacity: 1;
+ }
+
+ 100% {
+ opacity: 0;
+ }
+`)),IJ=dg(UL||(UL=zw`
+ 0% {
+ transform: scale(1);
+ }
+
+ 50% {
+ transform: scale(0.92);
+ }
+
+ 100% {
+ transform: scale(1);
+ }
+`)),LJ=lt("span",{name:"MuiTouchRipple",slot:"Root"})({overflow:"hidden",pointerEvents:"none",position:"absolute",zIndex:0,top:0,right:0,bottom:0,left:0,borderRadius:"inherit"}),kJ=lt(CJ,{name:"MuiTouchRipple",slot:"Ripple"})(zL||(zL=zw`
+ opacity: 0;
+ position: absolute;
+
+ &.${0} {
+ opacity: 0.3;
+ transform: scale(1);
+ animation-name: ${0};
+ animation-duration: ${0}ms;
+ animation-timing-function: ${0};
+ }
+
+ &.${0} {
+ animation-duration: ${0}ms;
+ }
+
+ & .${0} {
+ opacity: 1;
+ display: block;
+ width: 100%;
+ height: 100%;
+ border-radius: 50%;
+ background-color: currentColor;
+ }
+
+ & .${0} {
+ opacity: 0;
+ animation-name: ${0};
+ animation-duration: ${0}ms;
+ animation-timing-function: ${0};
+ }
+
+ & .${0} {
+ position: absolute;
+ /* @noflip */
+ left: 0px;
+ top: 0;
+ animation-name: ${0};
+ animation-duration: 2500ms;
+ animation-timing-function: ${0};
+ animation-iteration-count: infinite;
+ animation-delay: 200ms;
+ }
+`),Ka.rippleVisible,RJ,PT,({theme:t})=>t.transitions.easing.easeInOut,Ka.ripplePulsate,({theme:t})=>t.transitions.duration.shorter,Ka.child,Ka.childLeaving,PJ,PT,({theme:t})=>t.transitions.easing.easeInOut,Ka.childPulsate,IJ,({theme:t})=>t.transitions.easing.easeInOut),OJ=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiTouchRipple"}),{center:i=!1,classes:s={},className:o}=r,a=Rt(r,TJ),[l,c]=D.useState([]),f=D.useRef(0),p=D.useRef(null);D.useEffect(()=>{p.current&&(p.current(),p.current=null)},[l]);const g=D.useRef(!1),v=Ah(),x=D.useRef(null),_=D.useRef(null),b=D.useCallback(T=>{const{pulsate:L,rippleX:R,rippleY:P,rippleSize:F,cb:O}=T;c(I=>[...I,C.jsx(kJ,{classes:{ripple:At(s.ripple,Ka.ripple),rippleVisible:At(s.rippleVisible,Ka.rippleVisible),ripplePulsate:At(s.ripplePulsate,Ka.ripplePulsate),child:At(s.child,Ka.child),childLeaving:At(s.childLeaving,Ka.childLeaving),childPulsate:At(s.childPulsate,Ka.childPulsate)},timeout:PT,pulsate:L,rippleX:R,rippleY:P,rippleSize:F},f.current)]),f.current+=1,p.current=O},[s]),y=D.useCallback((T={},L={},R=()=>{})=>{const{pulsate:P=!1,center:F=i||L.pulsate,fakeElement:O=!1}=L;if((T==null?void 0:T.type)==="mousedown"&&g.current){g.current=!1;return}(T==null?void 0:T.type)==="touchstart"&&(g.current=!0);const I=O?null:_.current,H=I?I.getBoundingClientRect():{width:0,height:0,left:0,top:0};let Q,q,le;if(F||T===void 0||T.clientX===0&&T.clientY===0||!T.clientX&&!T.touches)Q=Math.round(H.width/2),q=Math.round(H.height/2);else{const{clientX:ie,clientY:ee}=T.touches&&T.touches.length>0?T.touches[0]:T;Q=Math.round(ie-H.left),q=Math.round(ee-H.top)}if(F)le=Math.sqrt((2*H.width**2+H.height**2)/3),le%2===0&&(le+=1);else{const ie=Math.max(Math.abs((I?I.clientWidth:0)-Q),Q)*2+2,ee=Math.max(Math.abs((I?I.clientHeight:0)-q),q)*2+2;le=Math.sqrt(ie**2+ee**2)}T!=null&&T.touches?x.current===null&&(x.current=()=>{b({pulsate:P,rippleX:Q,rippleY:q,rippleSize:le,cb:R})},v.start(AJ,()=>{x.current&&(x.current(),x.current=null)})):b({pulsate:P,rippleX:Q,rippleY:q,rippleSize:le,cb:R})},[i,b,v]),S=D.useCallback(()=>{y({},{pulsate:!0})},[y]),w=D.useCallback((T,L)=>{if(v.clear(),(T==null?void 0:T.type)==="touchend"&&x.current){x.current(),x.current=null,v.start(0,()=>{w(T,L)});return}x.current=null,c(R=>R.length>0?R.slice(1):R),p.current=L},[v]);return D.useImperativeHandle(n,()=>({pulsate:S,start:y,stop:w}),[S,y,w]),C.jsx(LJ,X({className:At(Ka.root,s.root,o),ref:_},a,{children:C.jsx(oJ,{component:null,exit:!0,children:l})}))}),NJ=OJ;function DJ(t){return bn("MuiButtonBase",t)}const FJ=pn("MuiButtonBase",["root","disabled","focusVisible"]),UJ=["action","centerRipple","children","className","component","disabled","disableRipple","disableTouchRipple","focusRipple","focusVisibleClassName","LinkComponent","onBlur","onClick","onContextMenu","onDragLeave","onFocus","onFocusVisible","onKeyDown","onKeyUp","onMouseDown","onMouseLeave","onMouseUp","onTouchEnd","onTouchMove","onTouchStart","tabIndex","TouchRippleProps","touchRippleRef","type"],zJ=t=>{const{disabled:e,focusVisible:n,focusVisibleClassName:r,classes:i}=t,o=Sn({root:["root",e&&"disabled",n&&"focusVisible"]},DJ,i);return n&&r&&(o.root+=` ${r}`),o},BJ=lt("button",{name:"MuiButtonBase",slot:"Root",overridesResolver:(t,e)=>e.root})({display:"inline-flex",alignItems:"center",justifyContent:"center",position:"relative",boxSizing:"border-box",WebkitTapHighlightColor:"transparent",backgroundColor:"transparent",outline:0,border:0,margin:0,borderRadius:0,padding:0,cursor:"pointer",userSelect:"none",verticalAlign:"middle",MozAppearance:"none",WebkitAppearance:"none",textDecoration:"none",color:"inherit","&::-moz-focus-inner":{borderStyle:"none"},[`&.${FJ.disabled}`]:{pointerEvents:"none",cursor:"default"},"@media print":{colorAdjust:"exact"}}),HJ=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiButtonBase"}),{action:i,centerRipple:s=!1,children:o,className:a,component:l="button",disabled:c=!1,disableRipple:f=!1,disableTouchRipple:p=!1,focusRipple:g=!1,LinkComponent:v="a",onBlur:x,onClick:_,onContextMenu:b,onDragLeave:y,onFocus:S,onFocusVisible:w,onKeyDown:T,onKeyUp:L,onMouseDown:R,onMouseLeave:P,onMouseUp:F,onTouchEnd:O,onTouchMove:I,onTouchStart:H,tabIndex:Q=0,TouchRippleProps:q,touchRippleRef:le,type:ie}=r,ee=Rt(r,UJ),ue=D.useRef(null),z=D.useRef(null),te=Kr(z,le),{isFocusVisibleRef:oe,onFocus:de,onBlur:Ce,ref:Le}=Tw(),[V,me]=D.useState(!1);c&&V&&me(!1),D.useImperativeHandle(i,()=>({focusVisible:()=>{me(!0),ue.current.focus()}}),[]);const[pe,Se]=D.useState(!1);D.useEffect(()=>{Se(!0)},[]);const je=pe&&!f&&!c;D.useEffect(()=>{V&&g&&!f&&pe&&z.current.pulsate()},[f,g,V,pe]);function it(ge,Xe,St=p){return ts(mt=>(Xe&&Xe(mt),!St&&z.current&&z.current[ge](mt),!0))}const xe=it("start",R),et=it("stop",b),Re=it("stop",y),Oe=it("stop",F),Te=it("stop",ge=>{V&&ge.preventDefault(),P&&P(ge)}),ze=it("start",H),ke=it("stop",O),rt=it("stop",I),tt=it("stop",ge=>{Ce(ge),oe.current===!1&&me(!1),x&&x(ge)},!1),ae=ts(ge=>{ue.current||(ue.current=ge.currentTarget),de(ge),oe.current===!0&&(me(!0),w&&w(ge)),S&&S(ge)}),G=()=>{const ge=ue.current;return l&&l!=="button"&&!(ge.tagName==="A"&&ge.href)},be=D.useRef(!1),$e=ts(ge=>{g&&!be.current&&V&&z.current&&ge.key===" "&&(be.current=!0,z.current.stop(ge,()=>{z.current.start(ge)})),ge.target===ge.currentTarget&&G()&&ge.key===" "&&ge.preventDefault(),T&&T(ge),ge.target===ge.currentTarget&&G()&&ge.key==="Enter"&&!c&&(ge.preventDefault(),_&&_(ge))}),Ze=ts(ge=>{g&&ge.key===" "&&z.current&&V&&!ge.defaultPrevented&&(be.current=!1,z.current.stop(ge,()=>{z.current.pulsate(ge)})),L&&L(ge),_&&ge.target===ge.currentTarget&&G()&&ge.key===" "&&!ge.defaultPrevented&&_(ge)});let We=l;We==="button"&&(ee.href||ee.to)&&(We=v);const Mt={};We==="button"?(Mt.type=ie===void 0?"button":ie,Mt.disabled=c):(!ee.href&&!ee.to&&(Mt.role="button"),c&&(Mt["aria-disabled"]=c));const pt=Kr(n,Le,ue),at=X({},r,{centerRipple:s,component:l,disabled:c,disableRipple:f,disableTouchRipple:p,focusRipple:g,tabIndex:Q,focusVisible:V}),Ie=zJ(at);return C.jsxs(BJ,X({as:We,className:At(Ie.root,a),ownerState:at,onBlur:tt,onClick:_,onContextMenu:et,onFocus:ae,onKeyDown:$e,onKeyUp:Ze,onMouseDown:xe,onMouseLeave:Te,onMouseUp:Oe,onDragLeave:Re,onTouchEnd:ke,onTouchMove:rt,onTouchStart:ze,ref:pt,tabIndex:c?-1:Q,type:ie},Mt,ee,{children:[o,je?C.jsx(NJ,X({ref:te,center:s},q)):null]}))}),Nu=HJ;function $J(t){return bn("MuiIconButton",t)}const VJ=pn("MuiIconButton",["root","disabled","colorInherit","colorPrimary","colorSecondary","colorError","colorInfo","colorSuccess","colorWarning","edgeStart","edgeEnd","sizeSmall","sizeMedium","sizeLarge"]),WJ=["edge","children","className","color","disabled","disableFocusRipple","size"],jJ=t=>{const{classes:e,disabled:n,color:r,edge:i,size:s}=t,o={root:["root",n&&"disabled",r!=="default"&&`color${gt(r)}`,i&&`edge${gt(i)}`,`size${gt(s)}`]};return Sn(o,$J,e)},GJ=lt(Nu,{name:"MuiIconButton",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.color!=="default"&&e[`color${gt(n.color)}`],n.edge&&e[`edge${gt(n.edge)}`],e[`size${gt(n.size)}`]]}})(({theme:t,ownerState:e})=>X({textAlign:"center",flex:"0 0 auto",fontSize:t.typography.pxToRem(24),padding:8,borderRadius:"50%",overflow:"visible",color:(t.vars||t).palette.action.active,transition:t.transitions.create("background-color",{duration:t.transitions.duration.shortest})},!e.disableRipple&&{"&:hover":{backgroundColor:t.vars?`rgba(${t.vars.palette.action.activeChannel} / ${t.vars.palette.action.hoverOpacity})`:qn(t.palette.action.active,t.palette.action.hoverOpacity),"@media (hover: none)":{backgroundColor:"transparent"}}},e.edge==="start"&&{marginLeft:e.size==="small"?-3:-12},e.edge==="end"&&{marginRight:e.size==="small"?-3:-12}),({theme:t,ownerState:e})=>{var n;const r=(n=(t.vars||t).palette)==null?void 0:n[e.color];return X({},e.color==="inherit"&&{color:"inherit"},e.color!=="inherit"&&e.color!=="default"&&X({color:r==null?void 0:r.main},!e.disableRipple&&{"&:hover":X({},r&&{backgroundColor:t.vars?`rgba(${r.mainChannel} / ${t.vars.palette.action.hoverOpacity})`:qn(r.main,t.palette.action.hoverOpacity)},{"@media (hover: none)":{backgroundColor:"transparent"}})}),e.size==="small"&&{padding:5,fontSize:t.typography.pxToRem(18)},e.size==="large"&&{padding:12,fontSize:t.typography.pxToRem(28)},{[`&.${VJ.disabled}`]:{backgroundColor:"transparent",color:(t.vars||t).palette.action.disabled}})}),XJ=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiIconButton"}),{edge:i=!1,children:s,className:o,color:a="default",disabled:l=!1,disableFocusRipple:c=!1,size:f="medium"}=r,p=Rt(r,WJ),g=X({},r,{edge:i,color:a,disabled:l,disableFocusRipple:c,size:f}),v=jJ(g);return C.jsx(GJ,X({className:At(v.root,o),centerRipple:!0,focusRipple:!c,disabled:l,ref:n},p,{ownerState:g,children:s}))}),Vu=XJ,qJ=bt(C.jsx("path",{d:"M19 6.41L17.59 5 12 10.59 6.41 5 5 6.41 10.59 12 5 17.59 6.41 19 12 13.41 17.59 19 19 17.59 13.41 12z"}),"Close");function ZJ(t){return bn("MuiTypography",t)}pn("MuiTypography",["root","h1","h2","h3","h4","h5","h6","subtitle1","subtitle2","body1","body2","inherit","button","caption","overline","alignLeft","alignRight","alignCenter","alignJustify","noWrap","gutterBottom","paragraph"]);const YJ=["align","className","component","gutterBottom","noWrap","paragraph","variant","variantMapping"],KJ=t=>{const{align:e,gutterBottom:n,noWrap:r,paragraph:i,variant:s,classes:o}=t,a={root:["root",s,t.align!=="inherit"&&`align${gt(e)}`,n&&"gutterBottom",r&&"noWrap",i&&"paragraph"]};return Sn(a,ZJ,o)},QJ=lt("span",{name:"MuiTypography",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.variant&&e[n.variant],n.align!=="inherit"&&e[`align${gt(n.align)}`],n.noWrap&&e.noWrap,n.gutterBottom&&e.gutterBottom,n.paragraph&&e.paragraph]}})(({theme:t,ownerState:e})=>X({margin:0},e.variant==="inherit"&&{font:"inherit"},e.variant!=="inherit"&&t.typography[e.variant],e.align!=="inherit"&&{textAlign:e.align},e.noWrap&&{overflow:"hidden",textOverflow:"ellipsis",whiteSpace:"nowrap"},e.gutterBottom&&{marginBottom:"0.35em"},e.paragraph&&{marginBottom:16})),BL={h1:"h1",h2:"h2",h3:"h3",h4:"h4",h5:"h5",h6:"h6",subtitle1:"h6",subtitle2:"h6",body1:"p",body2:"p",inherit:"p"},JJ={primary:"primary.main",textPrimary:"text.primary",secondary:"secondary.main",textSecondary:"text.secondary",error:"error.main"},eee=t=>JJ[t]||t,tee=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiTypography"}),i=eee(r.color),s=Ky(X({},r,{color:i})),{align:o="inherit",className:a,component:l,gutterBottom:c=!1,noWrap:f=!1,paragraph:p=!1,variant:g="body1",variantMapping:v=BL}=s,x=Rt(s,YJ),_=X({},s,{align:o,color:i,className:a,component:l,gutterBottom:c,noWrap:f,paragraph:p,variant:g,variantMapping:v}),b=l||(p?"p":v[g]||BL[g])||"span",y=KJ(_);return C.jsx(QJ,X({as:b,ref:n,ownerState:_,className:At(y.root,a)},x))}),mr=tee,h7="base";function nee(t){return`${h7}--${t}`}function ree(t,e){return`${h7}-${t}-${e}`}function p7(t,e){const n=E8[e];return n?nee(n):ree(t,e)}function iee(t,e){const n={};return e.forEach(r=>{n[r]=p7(t,r)}),n}const see=["input","select","textarea","a[href]","button","[tabindex]","audio[controls]","video[controls]",'[contenteditable]:not([contenteditable="false"])'].join(",");function oee(t){const e=parseInt(t.getAttribute("tabindex")||"",10);return Number.isNaN(e)?t.contentEditable==="true"||(t.nodeName==="AUDIO"||t.nodeName==="VIDEO"||t.nodeName==="DETAILS")&&t.getAttribute("tabindex")===null?0:t.tabIndex:e}function aee(t){if(t.tagName!=="INPUT"||t.type!=="radio"||!t.name)return!1;const e=r=>t.ownerDocument.querySelector(`input[type="radio"]${r}`);let n=e(`[name="${t.name}"]:checked`);return n||(n=e(`[name="${t.name}"]`)),n!==t}function lee(t){return!(t.disabled||t.tagName==="INPUT"&&t.type==="hidden"||aee(t))}function cee(t){const e=[],n=[];return Array.from(t.querySelectorAll(see)).forEach((r,i)=>{const s=oee(r);s===-1||!lee(r)||(s===0?e.push(r):n.push({documentOrder:i,tabIndex:s,node:r}))}),n.sort((r,i)=>r.tabIndex===i.tabIndex?r.documentOrder-i.documentOrder:r.tabIndex-i.tabIndex).map(r=>r.node).concat(e)}function uee(){return!0}function dee(t){const{children:e,disableAutoFocus:n=!1,disableEnforceFocus:r=!1,disableRestoreFocus:i=!1,getTabbable:s=cee,isEnabled:o=uee,open:a}=t,l=D.useRef(!1),c=D.useRef(null),f=D.useRef(null),p=D.useRef(null),g=D.useRef(null),v=D.useRef(!1),x=D.useRef(null),_=Kr(e.ref,x),b=D.useRef(null);D.useEffect(()=>{!a||!x.current||(v.current=!n)},[n,a]),D.useEffect(()=>{if(!a||!x.current)return;const w=Oi(x.current);return x.current.contains(w.activeElement)||(x.current.hasAttribute("tabIndex")||x.current.setAttribute("tabIndex","-1"),v.current&&x.current.focus()),()=>{i||(p.current&&p.current.focus&&(l.current=!0,p.current.focus()),p.current=null)}},[a]),D.useEffect(()=>{if(!a||!x.current)return;const w=Oi(x.current),T=P=>{b.current=P,!(r||!o()||P.key!=="Tab")&&w.activeElement===x.current&&P.shiftKey&&(l.current=!0,f.current&&f.current.focus())},L=()=>{const P=x.current;if(P===null)return;if(!w.hasFocus()||!o()||l.current){l.current=!1;return}if(P.contains(w.activeElement)||r&&w.activeElement!==c.current&&w.activeElement!==f.current)return;if(w.activeElement!==g.current)g.current=null;else if(g.current!==null)return;if(!v.current)return;let F=[];if((w.activeElement===c.current||w.activeElement===f.current)&&(F=s(x.current)),F.length>0){var O,I;const H=!!((O=b.current)!=null&&O.shiftKey&&((I=b.current)==null?void 0:I.key)==="Tab"),Q=F[0],q=F[F.length-1];typeof Q!="string"&&typeof q!="string"&&(H?q.focus():Q.focus())}else P.focus()};w.addEventListener("focusin",L),w.addEventListener("keydown",T,!0);const R=setInterval(()=>{w.activeElement&&w.activeElement.tagName==="BODY"&&L()},50);return()=>{clearInterval(R),w.removeEventListener("focusin",L),w.removeEventListener("keydown",T,!0)}},[n,r,i,o,a,s]);const y=w=>{p.current===null&&(p.current=w.relatedTarget),v.current=!0,g.current=w.target;const T=e.props.onFocus;T&&T(w)},S=w=>{p.current===null&&(p.current=w.relatedTarget),v.current=!0};return C.jsxs(D.Fragment,{children:[C.jsx("div",{tabIndex:a?0:-1,onFocus:S,ref:c,"data-testid":"sentinelStart"}),D.cloneElement(e,{ref:_,onFocus:y}),C.jsx("div",{tabIndex:a?0:-1,onFocus:S,ref:f,"data-testid":"sentinelEnd"})]})}function fee(t){return typeof t=="function"?t():t}const m7=D.forwardRef(function(e,n){const{children:r,container:i,disablePortal:s=!1}=e,[o,a]=D.useState(null),l=Kr(D.isValidElement(r)?r.ref:null,n);if(Xo(()=>{s||a(fee(i)||document.body)},[i,s]),Xo(()=>{if(o&&!s)return Yv(n,o),()=>{Yv(n,null)}},[n,o,s]),s){if(D.isValidElement(r)){const c={ref:l};return D.cloneElement(r,c)}return C.jsx(D.Fragment,{children:r})}return C.jsx(D.Fragment,{children:o&&X2.createPortal(r,o)})});function hee(t){const e=Oi(t);return e.body===t?Oc(t).innerWidth>e.documentElement.clientWidth:t.scrollHeight>t.clientHeight}function vv(t,e){e?t.setAttribute("aria-hidden","true"):t.removeAttribute("aria-hidden")}function HL(t){return parseInt(Oc(t).getComputedStyle(t).paddingRight,10)||0}function pee(t){const n=["TEMPLATE","SCRIPT","STYLE","LINK","MAP","META","NOSCRIPT","PICTURE","COL","COLGROUP","PARAM","SLOT","SOURCE","TRACK"].indexOf(t.tagName)!==-1,r=t.tagName==="INPUT"&&t.getAttribute("type")==="hidden";return n||r}function $L(t,e,n,r,i){const s=[e,n,...r];[].forEach.call(t.children,o=>{const a=s.indexOf(o)===-1,l=!pee(o);a&&l&&vv(o,i)})}function jE(t,e){let n=-1;return t.some((r,i)=>e(r)?(n=i,!0):!1),n}function mee(t,e){const n=[],r=t.container;if(!e.disableScrollLock){if(hee(r)){const o=H8(Oi(r));n.push({value:r.style.paddingRight,property:"padding-right",el:r}),r.style.paddingRight=`${HL(r)+o}px`;const a=Oi(r).querySelectorAll(".mui-fixed");[].forEach.call(a,l=>{n.push({value:l.style.paddingRight,property:"padding-right",el:l}),l.style.paddingRight=`${HL(l)+o}px`})}let s;if(r.parentNode instanceof DocumentFragment)s=Oi(r).body;else{const o=r.parentElement,a=Oc(r);s=(o==null?void 0:o.nodeName)==="HTML"&&a.getComputedStyle(o).overflowY==="scroll"?o:r}n.push({value:s.style.overflow,property:"overflow",el:s},{value:s.style.overflowX,property:"overflow-x",el:s},{value:s.style.overflowY,property:"overflow-y",el:s}),s.style.overflow="hidden"}return()=>{n.forEach(({value:s,el:o,property:a})=>{s?o.style.setProperty(a,s):o.style.removeProperty(a)})}}function gee(t){const e=[];return[].forEach.call(t.children,n=>{n.getAttribute("aria-hidden")==="true"&&e.push(n)}),e}class vee{constructor(){this.containers=void 0,this.modals=void 0,this.modals=[],this.containers=[]}add(e,n){let r=this.modals.indexOf(e);if(r!==-1)return r;r=this.modals.length,this.modals.push(e),e.modalRef&&vv(e.modalRef,!1);const i=gee(n);$L(n,e.mount,e.modalRef,i,!0);const s=jE(this.containers,o=>o.container===n);return s!==-1?(this.containers[s].modals.push(e),r):(this.containers.push({modals:[e],container:n,restore:null,hiddenSiblings:i}),r)}mount(e,n){const r=jE(this.containers,s=>s.modals.indexOf(e)!==-1),i=this.containers[r];i.restore||(i.restore=mee(i,n))}remove(e,n=!0){const r=this.modals.indexOf(e);if(r===-1)return r;const i=jE(this.containers,o=>o.modals.indexOf(e)!==-1),s=this.containers[i];if(s.modals.splice(s.modals.indexOf(e),1),this.modals.splice(r,1),s.modals.length===0)s.restore&&s.restore(),e.modalRef&&vv(e.modalRef,n),$L(s.container,e.mount,e.modalRef,s.hiddenSiblings,!1),this.containers.splice(i,1);else{const o=s.modals[s.modals.length-1];o.modalRef&&vv(o.modalRef,!1)}return r}isTopModal(e){return this.modals.length>0&&this.modals[this.modals.length-1]===e}}function yee(t){return typeof t=="function"?t():t}function xee(t){return t?t.props.hasOwnProperty("in"):!1}const _ee=new vee;function bee(t){const{container:e,disableEscapeKeyDown:n=!1,disableScrollLock:r=!1,manager:i=_ee,closeAfterTransition:s=!1,onTransitionEnter:o,onTransitionExited:a,children:l,onClose:c,open:f,rootRef:p}=t,g=D.useRef({}),v=D.useRef(null),x=D.useRef(null),_=Kr(x,p),[b,y]=D.useState(!f),S=xee(l);let w=!0;(t["aria-hidden"]==="false"||t["aria-hidden"]===!1)&&(w=!1);const T=()=>Oi(v.current),L=()=>(g.current.modalRef=x.current,g.current.mount=v.current,g.current),R=()=>{i.mount(L(),{disableScrollLock:r}),x.current&&(x.current.scrollTop=0)},P=ts(()=>{const ee=yee(e)||T().body;i.add(L(),ee),x.current&&R()}),F=D.useCallback(()=>i.isTopModal(L()),[i]),O=ts(ee=>{v.current=ee,ee&&(f&&F()?R():x.current&&vv(x.current,w))}),I=D.useCallback(()=>{i.remove(L(),w)},[w,i]);D.useEffect(()=>()=>{I()},[I]),D.useEffect(()=>{f?P():(!S||!s)&&I()},[f,I,S,s,P]);const H=ee=>ue=>{var z;(z=ee.onKeyDown)==null||z.call(ee,ue),!(ue.key!=="Escape"||ue.which===229||!F())&&(n||(ue.stopPropagation(),c&&c(ue,"escapeKeyDown")))},Q=ee=>ue=>{var z;(z=ee.onClick)==null||z.call(ee,ue),ue.target===ue.currentTarget&&c&&c(ue,"backdropClick")};return{getRootProps:(ee={})=>{const ue=gv(t);delete ue.onTransitionEnter,delete ue.onTransitionExited;const z=X({},ue,ee);return X({role:"presentation"},z,{onKeyDown:H(z),ref:_})},getBackdropProps:(ee={})=>{const ue=ee;return X({"aria-hidden":!0},ue,{onClick:Q(ue),open:f})},getTransitionProps:()=>{const ee=()=>{y(!1),o&&o()},ue=()=>{y(!0),a&&a(),s&&I()};return{onEnter:fT(ee,l==null?void 0:l.props.onEnter),onExited:fT(ue,l==null?void 0:l.props.onExited)}},rootRef:_,portalRef:O,isTopModal:F,exited:b,hasTransition:S}}var Vo="top",dl="bottom",fl="right",Wo="left",hR="auto",rx=[Vo,dl,fl,Wo],G0="start",Qv="end",See="clippingParents",g7="viewport",M1="popper",wee="reference",VL=rx.reduce(function(t,e){return t.concat([e+"-"+G0,e+"-"+Qv])},[]),v7=[].concat(rx,[hR]).reduce(function(t,e){return t.concat([e,e+"-"+G0,e+"-"+Qv])},[]),Mee="beforeRead",Eee="read",Cee="afterRead",Tee="beforeMain",Aee="main",Ree="afterMain",Pee="beforeWrite",Iee="write",Lee="afterWrite",kee=[Mee,Eee,Cee,Tee,Aee,Ree,Pee,Iee,Lee];function Nc(t){return t?(t.nodeName||"").toLowerCase():null}function Ca(t){if(t==null)return window;if(t.toString()!=="[object Window]"){var e=t.ownerDocument;return e&&e.defaultView||window}return t}function up(t){var e=Ca(t).Element;return t instanceof e||t instanceof Element}function ol(t){var e=Ca(t).HTMLElement;return t instanceof e||t instanceof HTMLElement}function pR(t){if(typeof ShadowRoot>"u")return!1;var e=Ca(t).ShadowRoot;return t instanceof e||t instanceof ShadowRoot}function Oee(t){var e=t.state;Object.keys(e.elements).forEach(function(n){var r=e.styles[n]||{},i=e.attributes[n]||{},s=e.elements[n];!ol(s)||!Nc(s)||(Object.assign(s.style,r),Object.keys(i).forEach(function(o){var a=i[o];a===!1?s.removeAttribute(o):s.setAttribute(o,a===!0?"":a)}))})}function Nee(t){var e=t.state,n={popper:{position:e.options.strategy,left:"0",top:"0",margin:"0"},arrow:{position:"absolute"},reference:{}};return Object.assign(e.elements.popper.style,n.popper),e.styles=n,e.elements.arrow&&Object.assign(e.elements.arrow.style,n.arrow),function(){Object.keys(e.elements).forEach(function(r){var i=e.elements[r],s=e.attributes[r]||{},o=Object.keys(e.styles.hasOwnProperty(r)?e.styles[r]:n[r]),a=o.reduce(function(l,c){return l[c]="",l},{});!ol(i)||!Nc(i)||(Object.assign(i.style,a),Object.keys(s).forEach(function(l){i.removeAttribute(l)}))})}}const Dee={name:"applyStyles",enabled:!0,phase:"write",fn:Oee,effect:Nee,requires:["computeStyles"]};function Pc(t){return t.split("-")[0]}var qh=Math.max,h2=Math.min,X0=Math.round;function IT(){var t=navigator.userAgentData;return t!=null&&t.brands&&Array.isArray(t.brands)?t.brands.map(function(e){return e.brand+"/"+e.version}).join(" "):navigator.userAgent}function y7(){return!/^((?!chrome|android).)*safari/i.test(IT())}function q0(t,e,n){e===void 0&&(e=!1),n===void 0&&(n=!1);var r=t.getBoundingClientRect(),i=1,s=1;e&&ol(t)&&(i=t.offsetWidth>0&&X0(r.width)/t.offsetWidth||1,s=t.offsetHeight>0&&X0(r.height)/t.offsetHeight||1);var o=up(t)?Ca(t):window,a=o.visualViewport,l=!y7()&&n,c=(r.left+(l&&a?a.offsetLeft:0))/i,f=(r.top+(l&&a?a.offsetTop:0))/s,p=r.width/i,g=r.height/s;return{width:p,height:g,top:f,right:c+p,bottom:f+g,left:c,x:c,y:f}}function mR(t){var e=q0(t),n=t.offsetWidth,r=t.offsetHeight;return Math.abs(e.width-n)<=1&&(n=e.width),Math.abs(e.height-r)<=1&&(r=e.height),{x:t.offsetLeft,y:t.offsetTop,width:n,height:r}}function x7(t,e){var n=e.getRootNode&&e.getRootNode();if(t.contains(e))return!0;if(n&&pR(n)){var r=e;do{if(r&&t.isSameNode(r))return!0;r=r.parentNode||r.host}while(r)}return!1}function Du(t){return Ca(t).getComputedStyle(t)}function Fee(t){return["table","td","th"].indexOf(Nc(t))>=0}function gf(t){return((up(t)?t.ownerDocument:t.document)||window.document).documentElement}function Bw(t){return Nc(t)==="html"?t:t.assignedSlot||t.parentNode||(pR(t)?t.host:null)||gf(t)}function WL(t){return!ol(t)||Du(t).position==="fixed"?null:t.offsetParent}function Uee(t){var e=/firefox/i.test(IT()),n=/Trident/i.test(IT());if(n&&ol(t)){var r=Du(t);if(r.position==="fixed")return null}var i=Bw(t);for(pR(i)&&(i=i.host);ol(i)&&["html","body"].indexOf(Nc(i))<0;){var s=Du(i);if(s.transform!=="none"||s.perspective!=="none"||s.contain==="paint"||["transform","perspective"].indexOf(s.willChange)!==-1||e&&s.willChange==="filter"||e&&s.filter&&s.filter!=="none")return i;i=i.parentNode}return null}function ix(t){for(var e=Ca(t),n=WL(t);n&&Fee(n)&&Du(n).position==="static";)n=WL(n);return n&&(Nc(n)==="html"||Nc(n)==="body"&&Du(n).position==="static")?e:n||Uee(t)||e}function gR(t){return["top","bottom"].indexOf(t)>=0?"x":"y"}function yv(t,e,n){return qh(t,h2(e,n))}function zee(t,e,n){var r=yv(t,e,n);return r>n?n:r}function _7(){return{top:0,right:0,bottom:0,left:0}}function b7(t){return Object.assign({},_7(),t)}function S7(t,e){return e.reduce(function(n,r){return n[r]=t,n},{})}var Bee=function(e,n){return e=typeof e=="function"?e(Object.assign({},n.rects,{placement:n.placement})):e,b7(typeof e!="number"?e:S7(e,rx))};function Hee(t){var e,n=t.state,r=t.name,i=t.options,s=n.elements.arrow,o=n.modifiersData.popperOffsets,a=Pc(n.placement),l=gR(a),c=[Wo,fl].indexOf(a)>=0,f=c?"height":"width";if(!(!s||!o)){var p=Bee(i.padding,n),g=mR(s),v=l==="y"?Vo:Wo,x=l==="y"?dl:fl,_=n.rects.reference[f]+n.rects.reference[l]-o[l]-n.rects.popper[f],b=o[l]-n.rects.reference[l],y=ix(s),S=y?l==="y"?y.clientHeight||0:y.clientWidth||0:0,w=_/2-b/2,T=p[v],L=S-g[f]-p[x],R=S/2-g[f]/2+w,P=yv(T,R,L),F=l;n.modifiersData[r]=(e={},e[F]=P,e.centerOffset=P-R,e)}}function $ee(t){var e=t.state,n=t.options,r=n.element,i=r===void 0?"[data-popper-arrow]":r;i!=null&&(typeof i=="string"&&(i=e.elements.popper.querySelector(i),!i)||x7(e.elements.popper,i)&&(e.elements.arrow=i))}const Vee={name:"arrow",enabled:!0,phase:"main",fn:Hee,effect:$ee,requires:["popperOffsets"],requiresIfExists:["preventOverflow"]};function Z0(t){return t.split("-")[1]}var Wee={top:"auto",right:"auto",bottom:"auto",left:"auto"};function jee(t,e){var n=t.x,r=t.y,i=e.devicePixelRatio||1;return{x:X0(n*i)/i||0,y:X0(r*i)/i||0}}function jL(t){var e,n=t.popper,r=t.popperRect,i=t.placement,s=t.variation,o=t.offsets,a=t.position,l=t.gpuAcceleration,c=t.adaptive,f=t.roundOffsets,p=t.isFixed,g=o.x,v=g===void 0?0:g,x=o.y,_=x===void 0?0:x,b=typeof f=="function"?f({x:v,y:_}):{x:v,y:_};v=b.x,_=b.y;var y=o.hasOwnProperty("x"),S=o.hasOwnProperty("y"),w=Wo,T=Vo,L=window;if(c){var R=ix(n),P="clientHeight",F="clientWidth";if(R===Ca(n)&&(R=gf(n),Du(R).position!=="static"&&a==="absolute"&&(P="scrollHeight",F="scrollWidth")),R=R,i===Vo||(i===Wo||i===fl)&&s===Qv){T=dl;var O=p&&R===L&&L.visualViewport?L.visualViewport.height:R[P];_-=O-r.height,_*=l?1:-1}if(i===Wo||(i===Vo||i===dl)&&s===Qv){w=fl;var I=p&&R===L&&L.visualViewport?L.visualViewport.width:R[F];v-=I-r.width,v*=l?1:-1}}var H=Object.assign({position:a},c&&Wee),Q=f===!0?jee({x:v,y:_},Ca(n)):{x:v,y:_};if(v=Q.x,_=Q.y,l){var q;return Object.assign({},H,(q={},q[T]=S?"0":"",q[w]=y?"0":"",q.transform=(L.devicePixelRatio||1)<=1?"translate("+v+"px, "+_+"px)":"translate3d("+v+"px, "+_+"px, 0)",q))}return Object.assign({},H,(e={},e[T]=S?_+"px":"",e[w]=y?v+"px":"",e.transform="",e))}function Gee(t){var e=t.state,n=t.options,r=n.gpuAcceleration,i=r===void 0?!0:r,s=n.adaptive,o=s===void 0?!0:s,a=n.roundOffsets,l=a===void 0?!0:a,c={placement:Pc(e.placement),variation:Z0(e.placement),popper:e.elements.popper,popperRect:e.rects.popper,gpuAcceleration:i,isFixed:e.options.strategy==="fixed"};e.modifiersData.popperOffsets!=null&&(e.styles.popper=Object.assign({},e.styles.popper,jL(Object.assign({},c,{offsets:e.modifiersData.popperOffsets,position:e.options.strategy,adaptive:o,roundOffsets:l})))),e.modifiersData.arrow!=null&&(e.styles.arrow=Object.assign({},e.styles.arrow,jL(Object.assign({},c,{offsets:e.modifiersData.arrow,position:"absolute",adaptive:!1,roundOffsets:l})))),e.attributes.popper=Object.assign({},e.attributes.popper,{"data-popper-placement":e.placement})}const Xee={name:"computeStyles",enabled:!0,phase:"beforeWrite",fn:Gee,data:{}};var G_={passive:!0};function qee(t){var e=t.state,n=t.instance,r=t.options,i=r.scroll,s=i===void 0?!0:i,o=r.resize,a=o===void 0?!0:o,l=Ca(e.elements.popper),c=[].concat(e.scrollParents.reference,e.scrollParents.popper);return s&&c.forEach(function(f){f.addEventListener("scroll",n.update,G_)}),a&&l.addEventListener("resize",n.update,G_),function(){s&&c.forEach(function(f){f.removeEventListener("scroll",n.update,G_)}),a&&l.removeEventListener("resize",n.update,G_)}}const Zee={name:"eventListeners",enabled:!0,phase:"write",fn:function(){},effect:qee,data:{}};var Yee={left:"right",right:"left",bottom:"top",top:"bottom"};function ES(t){return t.replace(/left|right|bottom|top/g,function(e){return Yee[e]})}var Kee={start:"end",end:"start"};function GL(t){return t.replace(/start|end/g,function(e){return Kee[e]})}function vR(t){var e=Ca(t),n=e.pageXOffset,r=e.pageYOffset;return{scrollLeft:n,scrollTop:r}}function yR(t){return q0(gf(t)).left+vR(t).scrollLeft}function Qee(t,e){var n=Ca(t),r=gf(t),i=n.visualViewport,s=r.clientWidth,o=r.clientHeight,a=0,l=0;if(i){s=i.width,o=i.height;var c=y7();(c||!c&&e==="fixed")&&(a=i.offsetLeft,l=i.offsetTop)}return{width:s,height:o,x:a+yR(t),y:l}}function Jee(t){var e,n=gf(t),r=vR(t),i=(e=t.ownerDocument)==null?void 0:e.body,s=qh(n.scrollWidth,n.clientWidth,i?i.scrollWidth:0,i?i.clientWidth:0),o=qh(n.scrollHeight,n.clientHeight,i?i.scrollHeight:0,i?i.clientHeight:0),a=-r.scrollLeft+yR(t),l=-r.scrollTop;return Du(i||n).direction==="rtl"&&(a+=qh(n.clientWidth,i?i.clientWidth:0)-s),{width:s,height:o,x:a,y:l}}function xR(t){var e=Du(t),n=e.overflow,r=e.overflowX,i=e.overflowY;return/auto|scroll|overlay|hidden/.test(n+i+r)}function w7(t){return["html","body","#document"].indexOf(Nc(t))>=0?t.ownerDocument.body:ol(t)&&xR(t)?t:w7(Bw(t))}function xv(t,e){var n;e===void 0&&(e=[]);var r=w7(t),i=r===((n=t.ownerDocument)==null?void 0:n.body),s=Ca(r),o=i?[s].concat(s.visualViewport||[],xR(r)?r:[]):r,a=e.concat(o);return i?a:a.concat(xv(Bw(o)))}function LT(t){return Object.assign({},t,{left:t.x,top:t.y,right:t.x+t.width,bottom:t.y+t.height})}function ete(t,e){var n=q0(t,!1,e==="fixed");return n.top=n.top+t.clientTop,n.left=n.left+t.clientLeft,n.bottom=n.top+t.clientHeight,n.right=n.left+t.clientWidth,n.width=t.clientWidth,n.height=t.clientHeight,n.x=n.left,n.y=n.top,n}function XL(t,e,n){return e===g7?LT(Qee(t,n)):up(e)?ete(e,n):LT(Jee(gf(t)))}function tte(t){var e=xv(Bw(t)),n=["absolute","fixed"].indexOf(Du(t).position)>=0,r=n&&ol(t)?ix(t):t;return up(r)?e.filter(function(i){return up(i)&&x7(i,r)&&Nc(i)!=="body"}):[]}function nte(t,e,n,r){var i=e==="clippingParents"?tte(t):[].concat(e),s=[].concat(i,[n]),o=s[0],a=s.reduce(function(l,c){var f=XL(t,c,r);return l.top=qh(f.top,l.top),l.right=h2(f.right,l.right),l.bottom=h2(f.bottom,l.bottom),l.left=qh(f.left,l.left),l},XL(t,o,r));return a.width=a.right-a.left,a.height=a.bottom-a.top,a.x=a.left,a.y=a.top,a}function M7(t){var e=t.reference,n=t.element,r=t.placement,i=r?Pc(r):null,s=r?Z0(r):null,o=e.x+e.width/2-n.width/2,a=e.y+e.height/2-n.height/2,l;switch(i){case Vo:l={x:o,y:e.y-n.height};break;case dl:l={x:o,y:e.y+e.height};break;case fl:l={x:e.x+e.width,y:a};break;case Wo:l={x:e.x-n.width,y:a};break;default:l={x:e.x,y:e.y}}var c=i?gR(i):null;if(c!=null){var f=c==="y"?"height":"width";switch(s){case G0:l[c]=l[c]-(e[f]/2-n[f]/2);break;case Qv:l[c]=l[c]+(e[f]/2-n[f]/2);break}}return l}function Jv(t,e){e===void 0&&(e={});var n=e,r=n.placement,i=r===void 0?t.placement:r,s=n.strategy,o=s===void 0?t.strategy:s,a=n.boundary,l=a===void 0?See:a,c=n.rootBoundary,f=c===void 0?g7:c,p=n.elementContext,g=p===void 0?M1:p,v=n.altBoundary,x=v===void 0?!1:v,_=n.padding,b=_===void 0?0:_,y=b7(typeof b!="number"?b:S7(b,rx)),S=g===M1?wee:M1,w=t.rects.popper,T=t.elements[x?S:g],L=nte(up(T)?T:T.contextElement||gf(t.elements.popper),l,f,o),R=q0(t.elements.reference),P=M7({reference:R,element:w,strategy:"absolute",placement:i}),F=LT(Object.assign({},w,P)),O=g===M1?F:R,I={top:L.top-O.top+y.top,bottom:O.bottom-L.bottom+y.bottom,left:L.left-O.left+y.left,right:O.right-L.right+y.right},H=t.modifiersData.offset;if(g===M1&&H){var Q=H[i];Object.keys(I).forEach(function(q){var le=[fl,dl].indexOf(q)>=0?1:-1,ie=[Vo,dl].indexOf(q)>=0?"y":"x";I[q]+=Q[ie]*le})}return I}function rte(t,e){e===void 0&&(e={});var n=e,r=n.placement,i=n.boundary,s=n.rootBoundary,o=n.padding,a=n.flipVariations,l=n.allowedAutoPlacements,c=l===void 0?v7:l,f=Z0(r),p=f?a?VL:VL.filter(function(x){return Z0(x)===f}):rx,g=p.filter(function(x){return c.indexOf(x)>=0});g.length===0&&(g=p);var v=g.reduce(function(x,_){return x[_]=Jv(t,{placement:_,boundary:i,rootBoundary:s,padding:o})[Pc(_)],x},{});return Object.keys(v).sort(function(x,_){return v[x]-v[_]})}function ite(t){if(Pc(t)===hR)return[];var e=ES(t);return[GL(t),e,GL(e)]}function ste(t){var e=t.state,n=t.options,r=t.name;if(!e.modifiersData[r]._skip){for(var i=n.mainAxis,s=i===void 0?!0:i,o=n.altAxis,a=o===void 0?!0:o,l=n.fallbackPlacements,c=n.padding,f=n.boundary,p=n.rootBoundary,g=n.altBoundary,v=n.flipVariations,x=v===void 0?!0:v,_=n.allowedAutoPlacements,b=e.options.placement,y=Pc(b),S=y===b,w=l||(S||!x?[ES(b)]:ite(b)),T=[b].concat(w).reduce(function(V,me){return V.concat(Pc(me)===hR?rte(e,{placement:me,boundary:f,rootBoundary:p,padding:c,flipVariations:x,allowedAutoPlacements:_}):me)},[]),L=e.rects.reference,R=e.rects.popper,P=new Map,F=!0,O=T[0],I=0;I=0,ie=le?"width":"height",ee=Jv(e,{placement:H,boundary:f,rootBoundary:p,altBoundary:g,padding:c}),ue=le?q?fl:Wo:q?dl:Vo;L[ie]>R[ie]&&(ue=ES(ue));var z=ES(ue),te=[];if(s&&te.push(ee[Q]<=0),a&&te.push(ee[ue]<=0,ee[z]<=0),te.every(function(V){return V})){O=H,F=!1;break}P.set(H,te)}if(F)for(var oe=x?3:1,de=function(me){var pe=T.find(function(Se){var je=P.get(Se);if(je)return je.slice(0,me).every(function(it){return it})});if(pe)return O=pe,"break"},Ce=oe;Ce>0;Ce--){var Le=de(Ce);if(Le==="break")break}e.placement!==O&&(e.modifiersData[r]._skip=!0,e.placement=O,e.reset=!0)}}const ote={name:"flip",enabled:!0,phase:"main",fn:ste,requiresIfExists:["offset"],data:{_skip:!1}};function qL(t,e,n){return n===void 0&&(n={x:0,y:0}),{top:t.top-e.height-n.y,right:t.right-e.width+n.x,bottom:t.bottom-e.height+n.y,left:t.left-e.width-n.x}}function ZL(t){return[Vo,fl,dl,Wo].some(function(e){return t[e]>=0})}function ate(t){var e=t.state,n=t.name,r=e.rects.reference,i=e.rects.popper,s=e.modifiersData.preventOverflow,o=Jv(e,{elementContext:"reference"}),a=Jv(e,{altBoundary:!0}),l=qL(o,r),c=qL(a,i,s),f=ZL(l),p=ZL(c);e.modifiersData[n]={referenceClippingOffsets:l,popperEscapeOffsets:c,isReferenceHidden:f,hasPopperEscaped:p},e.attributes.popper=Object.assign({},e.attributes.popper,{"data-popper-reference-hidden":f,"data-popper-escaped":p})}const lte={name:"hide",enabled:!0,phase:"main",requiresIfExists:["preventOverflow"],fn:ate};function cte(t,e,n){var r=Pc(t),i=[Wo,Vo].indexOf(r)>=0?-1:1,s=typeof n=="function"?n(Object.assign({},e,{placement:t})):n,o=s[0],a=s[1];return o=o||0,a=(a||0)*i,[Wo,fl].indexOf(r)>=0?{x:a,y:o}:{x:o,y:a}}function ute(t){var e=t.state,n=t.options,r=t.name,i=n.offset,s=i===void 0?[0,0]:i,o=v7.reduce(function(f,p){return f[p]=cte(p,e.rects,s),f},{}),a=o[e.placement],l=a.x,c=a.y;e.modifiersData.popperOffsets!=null&&(e.modifiersData.popperOffsets.x+=l,e.modifiersData.popperOffsets.y+=c),e.modifiersData[r]=o}const dte={name:"offset",enabled:!0,phase:"main",requires:["popperOffsets"],fn:ute};function fte(t){var e=t.state,n=t.name;e.modifiersData[n]=M7({reference:e.rects.reference,element:e.rects.popper,strategy:"absolute",placement:e.placement})}const hte={name:"popperOffsets",enabled:!0,phase:"read",fn:fte,data:{}};function pte(t){return t==="x"?"y":"x"}function mte(t){var e=t.state,n=t.options,r=t.name,i=n.mainAxis,s=i===void 0?!0:i,o=n.altAxis,a=o===void 0?!1:o,l=n.boundary,c=n.rootBoundary,f=n.altBoundary,p=n.padding,g=n.tether,v=g===void 0?!0:g,x=n.tetherOffset,_=x===void 0?0:x,b=Jv(e,{boundary:l,rootBoundary:c,padding:p,altBoundary:f}),y=Pc(e.placement),S=Z0(e.placement),w=!S,T=gR(y),L=pte(T),R=e.modifiersData.popperOffsets,P=e.rects.reference,F=e.rects.popper,O=typeof _=="function"?_(Object.assign({},e.rects,{placement:e.placement})):_,I=typeof O=="number"?{mainAxis:O,altAxis:O}:Object.assign({mainAxis:0,altAxis:0},O),H=e.modifiersData.offset?e.modifiersData.offset[e.placement]:null,Q={x:0,y:0};if(R){if(s){var q,le=T==="y"?Vo:Wo,ie=T==="y"?dl:fl,ee=T==="y"?"height":"width",ue=R[T],z=ue+b[le],te=ue-b[ie],oe=v?-F[ee]/2:0,de=S===G0?P[ee]:F[ee],Ce=S===G0?-F[ee]:-P[ee],Le=e.elements.arrow,V=v&&Le?mR(Le):{width:0,height:0},me=e.modifiersData["arrow#persistent"]?e.modifiersData["arrow#persistent"].padding:_7(),pe=me[le],Se=me[ie],je=yv(0,P[ee],V[ee]),it=w?P[ee]/2-oe-je-pe-I.mainAxis:de-je-pe-I.mainAxis,xe=w?-P[ee]/2+oe+je+Se+I.mainAxis:Ce+je+Se+I.mainAxis,et=e.elements.arrow&&ix(e.elements.arrow),Re=et?T==="y"?et.clientTop||0:et.clientLeft||0:0,Oe=(q=H==null?void 0:H[T])!=null?q:0,Te=ue+it-Oe-Re,ze=ue+xe-Oe,ke=yv(v?h2(z,Te):z,ue,v?qh(te,ze):te);R[T]=ke,Q[T]=ke-ue}if(a){var rt,tt=T==="x"?Vo:Wo,ae=T==="x"?dl:fl,G=R[L],be=L==="y"?"height":"width",$e=G+b[tt],Ze=G-b[ae],We=[Vo,Wo].indexOf(y)!==-1,Mt=(rt=H==null?void 0:H[L])!=null?rt:0,pt=We?$e:G-P[be]-F[be]-Mt+I.altAxis,at=We?G+P[be]+F[be]-Mt-I.altAxis:Ze,Ie=v&&We?zee(pt,G,at):yv(v?pt:$e,G,v?at:Ze);R[L]=Ie,Q[L]=Ie-G}e.modifiersData[r]=Q}}const gte={name:"preventOverflow",enabled:!0,phase:"main",fn:mte,requiresIfExists:["offset"]};function vte(t){return{scrollLeft:t.scrollLeft,scrollTop:t.scrollTop}}function yte(t){return t===Ca(t)||!ol(t)?vR(t):vte(t)}function xte(t){var e=t.getBoundingClientRect(),n=X0(e.width)/t.offsetWidth||1,r=X0(e.height)/t.offsetHeight||1;return n!==1||r!==1}function _te(t,e,n){n===void 0&&(n=!1);var r=ol(e),i=ol(e)&&xte(e),s=gf(e),o=q0(t,i,n),a={scrollLeft:0,scrollTop:0},l={x:0,y:0};return(r||!r&&!n)&&((Nc(e)!=="body"||xR(s))&&(a=yte(e)),ol(e)?(l=q0(e,!0),l.x+=e.clientLeft,l.y+=e.clientTop):s&&(l.x=yR(s))),{x:o.left+a.scrollLeft-l.x,y:o.top+a.scrollTop-l.y,width:o.width,height:o.height}}function bte(t){var e=new Map,n=new Set,r=[];t.forEach(function(s){e.set(s.name,s)});function i(s){n.add(s.name);var o=[].concat(s.requires||[],s.requiresIfExists||[]);o.forEach(function(a){if(!n.has(a)){var l=e.get(a);l&&i(l)}}),r.push(s)}return t.forEach(function(s){n.has(s.name)||i(s)}),r}function Ste(t){var e=bte(t);return kee.reduce(function(n,r){return n.concat(e.filter(function(i){return i.phase===r}))},[])}function wte(t){var e;return function(){return e||(e=new Promise(function(n){Promise.resolve().then(function(){e=void 0,n(t())})})),e}}function Mte(t){var e=t.reduce(function(n,r){var i=n[r.name];return n[r.name]=i?Object.assign({},i,r,{options:Object.assign({},i.options,r.options),data:Object.assign({},i.data,r.data)}):r,n},{});return Object.keys(e).map(function(n){return e[n]})}var YL={placement:"bottom",modifiers:[],strategy:"absolute"};function KL(){for(var t=arguments.length,e=new Array(t),n=0;nSn({root:["root"]},SJ(Ate)),Ote={},Nte=D.forwardRef(function(e,n){var r;const{anchorEl:i,children:s,direction:o,disablePortal:a,modifiers:l,open:c,placement:f,popperOptions:p,popperRef:g,slotProps:v={},slots:x={},TransitionProps:_}=e,b=Rt(e,Rte),y=D.useRef(null),S=Kr(y,n),w=D.useRef(null),T=Kr(w,g),L=D.useRef(T);Xo(()=>{L.current=T},[T]),D.useImperativeHandle(g,()=>w.current,[]);const R=Ite(f,o),[P,F]=D.useState(R),[O,I]=D.useState(kT(i));D.useEffect(()=>{w.current&&w.current.forceUpdate()}),D.useEffect(()=>{i&&I(kT(i))},[i]),Xo(()=>{if(!O||!c)return;const ie=z=>{F(z.placement)};let ee=[{name:"preventOverflow",options:{altBoundary:a}},{name:"flip",options:{altBoundary:a}},{name:"onUpdate",enabled:!0,phase:"afterWrite",fn:({state:z})=>{ie(z)}}];l!=null&&(ee=ee.concat(l)),p&&p.modifiers!=null&&(ee=ee.concat(p.modifiers));const ue=Tte(O,y.current,X({placement:R},p,{modifiers:ee}));return L.current(ue),()=>{ue.destroy(),L.current(null)}},[O,a,l,c,p,R]);const H={placement:P};_!==null&&(H.TransitionProps=_);const Q=kte(),q=(r=x.root)!=null?r:"div",le=Qi({elementType:q,externalSlotProps:v.root,externalForwardedProps:b,additionalProps:{role:"tooltip",ref:S},ownerState:e,className:Q.root});return C.jsx(q,X({},le,{children:typeof s=="function"?s(H):s}))}),Dte=D.forwardRef(function(e,n){const{anchorEl:r,children:i,container:s,direction:o="ltr",disablePortal:a=!1,keepMounted:l=!1,modifiers:c,open:f,placement:p="bottom",popperOptions:g=Ote,popperRef:v,style:x,transition:_=!1,slotProps:b={},slots:y={}}=e,S=Rt(e,Pte),[w,T]=D.useState(!0),L=()=>{T(!1)},R=()=>{T(!0)};if(!l&&!f&&(!_||w))return null;let P;if(s)P=s;else if(r){const I=kT(r);P=I&&Lte(I)?Oi(I).body:Oi(null).body}const F=!f&&l&&(!_||w)?"none":void 0,O=_?{in:f,onEnter:L,onExited:R}:void 0;return C.jsx(m7,{disablePortal:a,container:P,children:C.jsx(Nte,X({anchorEl:r,direction:o,disablePortal:a,modifiers:c,ref:n,open:_?!w:f,placement:p,popperOptions:g,popperRef:v,slotProps:b,slots:y},S,{style:X({position:"fixed",top:0,left:0,display:F},x),TransitionProps:O,children:i}))})}),Fte=2;function C7(t,e){return t-e}function QL(t,e){var n;const{index:r}=(n=t.reduce((i,s,o)=>{const a=Math.abs(e-s);return i===null||a({left:`${t}%`}),leap:t=>({width:`${t}%`})},"horizontal-reverse":{offset:t=>({right:`${t}%`}),leap:t=>({width:`${t}%`})},vertical:{offset:t=>({bottom:`${t}%`}),leap:t=>({height:`${t}%`})}},$te=t=>t;let Y_;function ek(){return Y_===void 0&&(typeof CSS<"u"&&typeof CSS.supports=="function"?Y_=CSS.supports("touch-action","none"):Y_=!0),Y_}function Vte(t){const{"aria-labelledby":e,defaultValue:n,disabled:r=!1,disableSwap:i=!1,isRtl:s=!1,marks:o=!1,max:a=100,min:l=0,name:c,onChange:f,onChangeCommitted:p,orientation:g="horizontal",rootRef:v,scale:x=$te,step:_=1,shiftStep:b=10,tabIndex:y,value:S}=t,w=D.useRef(),[T,L]=D.useState(-1),[R,P]=D.useState(-1),[F,O]=D.useState(!1),I=D.useRef(0),[H,Q]=Cu({controlled:S,default:n??l,name:"Slider"}),q=f&&((Ie,ge,Xe)=>{const St=Ie.nativeEvent||Ie,mt=new St.constructor(St.type,St);Object.defineProperty(mt,"target",{writable:!0,value:{value:ge,name:c}}),f(mt,ge,Xe)}),le=Array.isArray(H);let ie=le?H.slice().sort(C7):[H];ie=ie.map(Ie=>Ie==null?l:$m(Ie,l,a));const ee=o===!0&&_!==null?[...Array(Math.floor((a-l)/_)+1)].map((Ie,ge)=>({value:l+_*ge})):o||[],ue=ee.map(Ie=>Ie.value),{isFocusVisibleRef:z,onBlur:te,onFocus:oe,ref:de}=Tw(),[Ce,Le]=D.useState(-1),V=D.useRef(),me=Kr(de,V),pe=Kr(v,me),Se=Ie=>ge=>{var Xe;const St=Number(ge.currentTarget.getAttribute("data-index"));oe(ge),z.current===!0&&Le(St),P(St),Ie==null||(Xe=Ie.onFocus)==null||Xe.call(Ie,ge)},je=Ie=>ge=>{var Xe;te(ge),z.current===!1&&Le(-1),P(-1),Ie==null||(Xe=Ie.onBlur)==null||Xe.call(Ie,ge)},it=(Ie,ge)=>{const Xe=Number(Ie.currentTarget.getAttribute("data-index")),St=ie[Xe],mt=ue.indexOf(St);let Be=ge;if(ee&&_==null){const vt=ue[ue.length-1];Be>vt?Be=vt:Bege=>{var Xe;if(_!==null){const St=Number(ge.currentTarget.getAttribute("data-index")),mt=ie[St];let Be=null;(ge.key==="ArrowLeft"||ge.key==="ArrowDown")&&ge.shiftKey||ge.key==="PageDown"?Be=Math.max(mt-b,l):((ge.key==="ArrowRight"||ge.key==="ArrowUp")&&ge.shiftKey||ge.key==="PageUp")&&(Be=Math.min(mt+b,a)),Be!==null&&(it(ge,Be),ge.preventDefault())}Ie==null||(Xe=Ie.onKeyDown)==null||Xe.call(Ie,ge)};Xo(()=>{if(r&&V.current.contains(document.activeElement)){var Ie;(Ie=document.activeElement)==null||Ie.blur()}},[r]),r&&T!==-1&&L(-1),r&&Ce!==-1&&Le(-1);const et=Ie=>ge=>{var Xe;(Xe=Ie.onChange)==null||Xe.call(Ie,ge),it(ge,ge.target.valueAsNumber)},Re=D.useRef();let Oe=g;s&&g==="horizontal"&&(Oe+="-reverse");const Te=({finger:Ie,move:ge=!1})=>{const{current:Xe}=V,{width:St,height:mt,bottom:Be,left:vt}=Xe.getBoundingClientRect();let qe;Oe.indexOf("vertical")===0?qe=(Be-Ie.y)/mt:qe=(Ie.x-vt)/St,Oe.indexOf("-reverse")!==-1&&(qe=1-qe);let ce;if(ce=Ute(qe,l,a),_)ce=Bte(ce,_,l);else{const fe=QL(ue,ce);ce=ue[fe]}ce=$m(ce,l,a);let Ne=0;if(le){ge?Ne=Re.current:Ne=QL(ie,ce),i&&(ce=$m(ce,ie[Ne-1]||-1/0,ie[Ne+1]||1/0));const fe=ce;ce=JL({values:ie,newValue:ce,index:Ne}),i&&ge||(Ne=ce.indexOf(fe),Re.current=Ne)}return{newValue:ce,activeIndex:Ne}},ze=ts(Ie=>{const ge=X_(Ie,w);if(!ge)return;if(I.current+=1,Ie.type==="mousemove"&&Ie.buttons===0){ke(Ie);return}const{newValue:Xe,activeIndex:St}=Te({finger:ge,move:!0});q_({sliderRef:V,activeIndex:St,setActive:L}),Q(Xe),!F&&I.current>Fte&&O(!0),q&&!Z_(Xe,H)&&q(Ie,Xe,St)}),ke=ts(Ie=>{const ge=X_(Ie,w);if(O(!1),!ge)return;const{newValue:Xe}=Te({finger:ge,move:!0});L(-1),Ie.type==="touchend"&&P(-1),p&&p(Ie,Xe),w.current=void 0,tt()}),rt=ts(Ie=>{if(r)return;ek()||Ie.preventDefault();const ge=Ie.changedTouches[0];ge!=null&&(w.current=ge.identifier);const Xe=X_(Ie,w);if(Xe!==!1){const{newValue:mt,activeIndex:Be}=Te({finger:Xe});q_({sliderRef:V,activeIndex:Be,setActive:L}),Q(mt),q&&!Z_(mt,H)&&q(Ie,mt,Be)}I.current=0;const St=Oi(V.current);St.addEventListener("touchmove",ze,{passive:!0}),St.addEventListener("touchend",ke,{passive:!0})}),tt=D.useCallback(()=>{const Ie=Oi(V.current);Ie.removeEventListener("mousemove",ze),Ie.removeEventListener("mouseup",ke),Ie.removeEventListener("touchmove",ze),Ie.removeEventListener("touchend",ke)},[ke,ze]);D.useEffect(()=>{const{current:Ie}=V;return Ie.addEventListener("touchstart",rt,{passive:ek()}),()=>{Ie.removeEventListener("touchstart",rt),tt()}},[tt,rt]),D.useEffect(()=>{r&&tt()},[r,tt]);const ae=Ie=>ge=>{var Xe;if((Xe=Ie.onMouseDown)==null||Xe.call(Ie,ge),r||ge.defaultPrevented||ge.button!==0)return;ge.preventDefault();const St=X_(ge,w);if(St!==!1){const{newValue:Be,activeIndex:vt}=Te({finger:St});q_({sliderRef:V,activeIndex:vt,setActive:L}),Q(Be),q&&!Z_(Be,H)&&q(ge,Be,vt)}I.current=0;const mt=Oi(V.current);mt.addEventListener("mousemove",ze,{passive:!0}),mt.addEventListener("mouseup",ke)},G=p2(le?ie[0]:l,l,a),be=p2(ie[ie.length-1],l,a)-G,$e=(Ie={})=>{const ge=gv(Ie),Xe={onMouseDown:ae(ge||{})},St=X({},ge,Xe);return X({},Ie,{ref:pe},St)},Ze=Ie=>ge=>{var Xe;(Xe=Ie.onMouseOver)==null||Xe.call(Ie,ge);const St=Number(ge.currentTarget.getAttribute("data-index"));P(St)},We=Ie=>ge=>{var Xe;(Xe=Ie.onMouseLeave)==null||Xe.call(Ie,ge),P(-1)};return{active:T,axis:Oe,axisProps:Hte,dragging:F,focusedThumbIndex:Ce,getHiddenInputProps:(Ie={})=>{var ge;const Xe=gv(Ie),St={onChange:et(Xe||{}),onFocus:Se(Xe||{}),onBlur:je(Xe||{}),onKeyDown:xe(Xe||{})},mt=X({},Xe,St);return X({tabIndex:y,"aria-labelledby":e,"aria-orientation":g,"aria-valuemax":x(a),"aria-valuemin":x(l),name:c,type:"range",min:t.min,max:t.max,step:t.step===null&&t.marks?"any":(ge=t.step)!=null?ge:void 0,disabled:r},Ie,mt,{style:X({},_K,{direction:s?"rtl":"ltr",width:"100%",height:"100%"})})},getRootProps:$e,getThumbProps:(Ie={})=>{const ge=gv(Ie),Xe={onMouseOver:Ze(ge||{}),onMouseLeave:We(ge||{})};return X({},Ie,ge,Xe)},marks:ee,open:R,range:le,rootRef:pe,trackLeap:be,trackOffset:G,values:ie,getThumbStyle:Ie=>({pointerEvents:T!==-1&&T!==Ie?"none":void 0})}}const Wte=["onChange","maxRows","minRows","style","value"];function K_(t){return parseInt(t,10)||0}const jte={shadow:{visibility:"hidden",position:"absolute",overflow:"hidden",height:0,top:0,left:0,transform:"translateZ(0)"}};function Gte(t){return t==null||Object.keys(t).length===0||t.outerHeightStyle===0&&!t.overflowing}const Xte=D.forwardRef(function(e,n){const{onChange:r,maxRows:i,minRows:s=1,style:o,value:a}=e,l=Rt(e,Wte),{current:c}=D.useRef(a!=null),f=D.useRef(null),p=Kr(n,f),g=D.useRef(null),v=D.useCallback(()=>{const b=f.current,S=Oc(b).getComputedStyle(b);if(S.width==="0px")return{outerHeightStyle:0,overflowing:!1};const w=g.current;w.style.width=S.width,w.value=b.value||e.placeholder||"x",w.value.slice(-1)===`
+`&&(w.value+=" ");const T=S.boxSizing,L=K_(S.paddingBottom)+K_(S.paddingTop),R=K_(S.borderBottomWidth)+K_(S.borderTopWidth),P=w.scrollHeight;w.value="x";const F=w.scrollHeight;let O=P;s&&(O=Math.max(Number(s)*F,O)),i&&(O=Math.min(Number(i)*F,O)),O=Math.max(O,F);const I=O+(T==="border-box"?L+R:0),H=Math.abs(O-P)<=1;return{outerHeightStyle:I,overflowing:H}},[i,s,e.placeholder]),x=D.useCallback(()=>{const b=v();if(Gte(b))return;const y=f.current;y.style.height=`${b.outerHeightStyle}px`,y.style.overflow=b.overflowing?"hidden":""},[v]);Xo(()=>{const b=()=>{x()};let y;const S=Qy(b),w=f.current,T=Oc(w);T.addEventListener("resize",S);let L;return typeof ResizeObserver<"u"&&(L=new ResizeObserver(b),L.observe(w)),()=>{S.clear(),cancelAnimationFrame(y),T.removeEventListener("resize",S),L&&L.disconnect()}},[v,x]),Xo(()=>{x()});const _=b=>{c||x(),r&&r(b)};return C.jsxs(D.Fragment,{children:[C.jsx("textarea",X({value:a,onChange:_,ref:p,rows:s,style:o},l)),C.jsx("textarea",{"aria-hidden":!0,className:e.className,readOnly:!0,ref:g,tabIndex:-1,style:X({},jte.shadow,o,{paddingTop:0,paddingBottom:0})})]})});function tk(t){return typeof t.normalize<"u"?t.normalize("NFD").replace(/[\u0300-\u036f]/g,""):t}function qte(t={}){const{ignoreAccents:e=!0,ignoreCase:n=!0,limit:r,matchFrom:i="any",stringify:s,trim:o=!1}=t;return(a,{inputValue:l,getOptionLabel:c})=>{let f=o?l.trim():l;n&&(f=f.toLowerCase()),e&&(f=tk(f));const p=f?a.filter(g=>{let v=(s||c)(g);return n&&(v=v.toLowerCase()),e&&(v=tk(v)),i==="start"?v.indexOf(f)===0:v.indexOf(f)>-1}):a;return typeof r=="number"?p.slice(0,r):p}}function Q_(t,e){for(let n=0;n{var e;return t.current!==null&&((e=t.current.parentElement)==null?void 0:e.contains(document.activeElement))};function Kte(t){const{unstable_isActiveElementInListbox:e=Yte,unstable_classNamePrefix:n="Mui",autoComplete:r=!1,autoHighlight:i=!1,autoSelect:s=!1,blurOnSelect:o=!1,clearOnBlur:a=!t.freeSolo,clearOnEscape:l=!1,componentName:c="useAutocomplete",defaultValue:f=t.multiple?[]:null,disableClearable:p=!1,disableCloseOnSelect:g=!1,disabled:v,disabledItemsFocusable:x=!1,disableListWrap:_=!1,filterOptions:b=Zte,filterSelectedOptions:y=!1,freeSolo:S=!1,getOptionDisabled:w,getOptionKey:T,getOptionLabel:L=B=>{var ne;return(ne=B.label)!=null?ne:B},groupBy:R,handleHomeEndKeys:P=!t.freeSolo,id:F,includeInputInList:O=!1,inputValue:I,isOptionEqualToValue:H=(B,ne)=>B===ne,multiple:Q=!1,onChange:q,onClose:le,onHighlightChange:ie,onInputChange:ee,onOpen:ue,open:z,openOnFocus:te=!1,options:oe,readOnly:de=!1,selectOnFocus:Ce=!t.freeSolo,value:Le}=t,V=hg(F);let me=L;me=B=>{const ne=L(B);return typeof ne!="string"?String(ne):ne};const pe=D.useRef(!1),Se=D.useRef(!0),je=D.useRef(null),it=D.useRef(null),[xe,et]=D.useState(null),[Re,Oe]=D.useState(-1),Te=i?0:-1,ze=D.useRef(Te),[ke,rt]=Cu({controlled:Le,default:f,name:c}),[tt,ae]=Cu({controlled:I,default:"",name:c,state:"inputValue"}),[G,be]=D.useState(!1),$e=D.useCallback((B,ne)=>{if(!(Q?ke.length!(y&&(Q?ke:[ke]).some(ne=>ne!==null&&H(B,ne)))),{inputValue:at&&Mt?"":tt,getOptionLabel:me}):[],Xe=yK({filteredOptions:ge,value:ke,inputValue:tt});D.useEffect(()=>{const B=ke!==Xe.value;G&&!B||S&&!B||$e(null,ke)},[ke,$e,G,Xe.value,S]);const St=Ze&&ge.length>0&&!de,mt=ts(B=>{B===-1?je.current.focus():xe.querySelector(`[data-tag-index="${B}"]`).focus()});D.useEffect(()=>{Q&&Re>ke.length-1&&(Oe(-1),mt(-1))},[ke,Q,Re,mt]);function Be(B,ne){if(!it.current||B<0||B>=ge.length)return-1;let _e=B;for(;;){const ye=it.current.querySelector(`[data-option-index="${_e}"]`),we=x?!1:!ye||ye.disabled||ye.getAttribute("aria-disabled")==="true";if(ye&&ye.hasAttribute("tabindex")&&!we)return _e;if(ne==="next"?_e=(_e+1)%ge.length:_e=(_e-1+ge.length)%ge.length,_e===B)return-1}}const vt=ts(({event:B,index:ne,reason:_e="auto"})=>{if(ze.current=ne,ne===-1?je.current.removeAttribute("aria-activedescendant"):je.current.setAttribute("aria-activedescendant",`${V}-option-${ne}`),ie&&ie(B,ne===-1?null:ge[ne],_e),!it.current)return;const ye=it.current.querySelector(`[role="option"].${n}-focused`);ye&&(ye.classList.remove(`${n}-focused`),ye.classList.remove(`${n}-focusVisible`));let we=it.current;if(it.current.getAttribute("role")!=="listbox"&&(we=it.current.parentElement.querySelector('[role="listbox"]')),!we)return;if(ne===-1){we.scrollTop=0;return}const Qe=it.current.querySelector(`[data-option-index="${ne}"]`);if(Qe&&(Qe.classList.add(`${n}-focused`),_e==="keyboard"&&Qe.classList.add(`${n}-focusVisible`),we.scrollHeight>we.clientHeight&&_e!=="mouse"&&_e!=="touch")){const wt=Qe,Ft=we.clientHeight+we.scrollTop,zt=wt.offsetTop+wt.offsetHeight;zt>Ft?we.scrollTop=zt-we.clientHeight:wt.offsetTop-wt.offsetHeight*(R?1.3:0){if(!Ie)return;const Qe=Be((()=>{const wt=ge.length-1;if(ne==="reset")return Te;if(ne==="start")return 0;if(ne==="end")return wt;const Ft=ze.current+ne;return Ft<0?Ft===-1&&O?-1:_&&ze.current!==-1||Math.abs(ne)>1?0:wt:Ft>wt?Ft===wt+1&&O?-1:_||Math.abs(ne)>1?wt:0:Ft})(),_e);if(vt({index:Qe,reason:ye,event:B}),r&&ne!=="reset")if(Qe===-1)je.current.value=tt;else{const wt=me(ge[Qe]);je.current.value=wt,wt.toLowerCase().indexOf(tt.toLowerCase())===0&&tt.length>0&&je.current.setSelectionRange(tt.length,wt.length)}}),ce=()=>{const B=(ne,_e)=>{const ye=ne?me(ne):"",we=_e?me(_e):"";return ye===we};if(ze.current!==-1&&Xe.filteredOptions&&Xe.filteredOptions.length!==ge.length&&Xe.inputValue===tt&&(Q?ke.length===Xe.value.length&&Xe.value.every((ne,_e)=>me(ke[_e])===me(ne)):B(Xe.value,ke))){const ne=Xe.filteredOptions[ze.current];if(ne)return Q_(ge,_e=>me(_e)===me(ne))}return-1},Ne=D.useCallback(()=>{if(!Ie)return;const B=ce();if(B!==-1){ze.current=B;return}const ne=Q?ke[0]:ke;if(ge.length===0||ne==null){qe({diff:"reset"});return}if(it.current){if(ne!=null){const _e=ge[ze.current];if(Q&&_e&&Q_(ke,we=>H(_e,we))!==-1)return;const ye=Q_(ge,we=>H(we,ne));ye===-1?qe({diff:"reset"}):vt({index:ye});return}if(ze.current>=ge.length-1){vt({index:ge.length-1});return}vt({index:ze.current})}},[ge.length,Q?!1:ke,y,qe,vt,Ie,tt,Q]),fe=ts(B=>{Yv(it,B),B&&Ne()});D.useEffect(()=>{Ne()},[Ne]);const Fe=B=>{Ze||(We(!0),pt(!0),ue&&ue(B))},He=(B,ne)=>{Ze&&(We(!1),le&&le(B,ne))},ut=(B,ne,_e,ye)=>{if(Q){if(ke.length===ne.length&&ke.every((we,Qe)=>we===ne[Qe]))return}else if(ke===ne)return;q&&q(B,ne,_e,ye),rt(ne)},xt=D.useRef(!1),Xt=(B,ne,_e="selectOption",ye="options")=>{let we=_e,Qe=ne;if(Q){Qe=Array.isArray(ke)?ke.slice():[];const wt=Q_(Qe,Ft=>H(ne,Ft));wt===-1?Qe.push(ne):ye!=="freeSolo"&&(Qe.splice(wt,1),we="removeOption")}$e(B,Qe),ut(B,Qe,we,{option:ne}),!g&&(!B||!B.ctrlKey&&!B.metaKey)&&He(B,we),(o===!0||o==="touch"&&xt.current||o==="mouse"&&!xt.current)&&je.current.blur()};function vn(B,ne){if(B===-1)return-1;let _e=B;for(;;){if(ne==="next"&&_e===ke.length||ne==="previous"&&_e===-1)return-1;const ye=xe.querySelector(`[data-tag-index="${_e}"]`);if(!ye||!ye.hasAttribute("tabindex")||ye.disabled||ye.getAttribute("aria-disabled")==="true")_e+=ne==="next"?1:-1;else return _e}}const mn=(B,ne)=>{if(!Q)return;tt===""&&He(B,"toggleInput");let _e=Re;Re===-1?tt===""&&ne==="previous"&&(_e=ke.length-1):(_e+=ne==="next"?1:-1,_e<0&&(_e=0),_e===ke.length&&(_e=-1)),_e=vn(_e,ne),Oe(_e),mt(_e)},On=B=>{pe.current=!0,ae(""),ee&&ee(B,"","clear"),ut(B,Q?[]:null,"clear")},un=B=>ne=>{if(B.onKeyDown&&B.onKeyDown(ne),!ne.defaultMuiPrevented&&(Re!==-1&&["ArrowLeft","ArrowRight"].indexOf(ne.key)===-1&&(Oe(-1),mt(-1)),ne.which!==229))switch(ne.key){case"Home":Ie&&P&&(ne.preventDefault(),qe({diff:"start",direction:"next",reason:"keyboard",event:ne}));break;case"End":Ie&&P&&(ne.preventDefault(),qe({diff:"end",direction:"previous",reason:"keyboard",event:ne}));break;case"PageUp":ne.preventDefault(),qe({diff:-nk,direction:"previous",reason:"keyboard",event:ne}),Fe(ne);break;case"PageDown":ne.preventDefault(),qe({diff:nk,direction:"next",reason:"keyboard",event:ne}),Fe(ne);break;case"ArrowDown":ne.preventDefault(),qe({diff:1,direction:"next",reason:"keyboard",event:ne}),Fe(ne);break;case"ArrowUp":ne.preventDefault(),qe({diff:-1,direction:"previous",reason:"keyboard",event:ne}),Fe(ne);break;case"ArrowLeft":mn(ne,"previous");break;case"ArrowRight":mn(ne,"next");break;case"Enter":if(ze.current!==-1&&Ie){const _e=ge[ze.current],ye=w?w(_e):!1;if(ne.preventDefault(),ye)return;Xt(ne,_e,"selectOption"),r&&je.current.setSelectionRange(je.current.value.length,je.current.value.length)}else S&&tt!==""&&at===!1&&(Q&&ne.preventDefault(),Xt(ne,tt,"createOption","freeSolo"));break;case"Escape":Ie?(ne.preventDefault(),ne.stopPropagation(),He(ne,"escape")):l&&(tt!==""||Q&&ke.length>0)&&(ne.preventDefault(),ne.stopPropagation(),On(ne));break;case"Backspace":if(Q&&!de&&tt===""&&ke.length>0){const _e=Re===-1?ke.length-1:Re,ye=ke.slice();ye.splice(_e,1),ut(ne,ye,"removeOption",{option:ke[_e]})}break;case"Delete":if(Q&&!de&&tt===""&&ke.length>0&&Re!==-1){const _e=Re,ye=ke.slice();ye.splice(_e,1),ut(ne,ye,"removeOption",{option:ke[_e]})}break}},Nn=B=>{be(!0),te&&!pe.current&&Fe(B)},In=B=>{if(e(it)){je.current.focus();return}be(!1),Se.current=!0,pe.current=!1,s&&ze.current!==-1&&Ie?Xt(B,ge[ze.current],"blur"):s&&S&&tt!==""?Xt(B,tt,"blur","freeSolo"):a&&$e(B,ke),He(B,"blur")},or=B=>{const ne=B.target.value;tt!==ne&&(ae(ne),pt(!1),ee&&ee(B,ne,"input")),ne===""?!p&&!Q&&ut(B,null,"clear"):Fe(B)},Kn=B=>{const ne=Number(B.currentTarget.getAttribute("data-option-index"));ze.current!==ne&&vt({event:B,index:ne,reason:"mouse"})},Fr=B=>{vt({event:B,index:Number(B.currentTarget.getAttribute("data-option-index")),reason:"touch"}),xt.current=!0},gr=B=>{const ne=Number(B.currentTarget.getAttribute("data-option-index"));Xt(B,ge[ne],"selectOption"),xt.current=!1},ui=B=>ne=>{const _e=ke.slice();_e.splice(B,1),ut(ne,_e,"removeOption",{option:ke[B]})},ss=B=>{Ze?He(B,"toggleInput"):Fe(B)},Rr=B=>{B.currentTarget.contains(B.target)&&B.target.getAttribute("id")!==V&&B.preventDefault()},ji=B=>{B.currentTarget.contains(B.target)&&(je.current.focus(),Ce&&Se.current&&je.current.selectionEnd-je.current.selectionStart===0&&je.current.select(),Se.current=!1)},Ei=B=>{!v&&(tt===""||!Ze)&&ss(B)};let di=S&&tt.length>0;di=di||(Q?ke.length>0:ke!==null);let Gi=ge;return R&&(Gi=ge.reduce((B,ne,_e)=>{const ye=R(ne);return B.length>0&&B[B.length-1].group===ye?B[B.length-1].options.push(ne):B.push({key:_e,index:_e,group:ye,options:[ne]}),B},[])),v&&G&&In(),{getRootProps:(B={})=>X({"aria-owns":St?`${V}-listbox`:null},B,{onKeyDown:un(B),onMouseDown:Rr,onClick:ji}),getInputLabelProps:()=>({id:`${V}-label`,htmlFor:V}),getInputProps:()=>({id:V,value:tt,onBlur:In,onFocus:Nn,onChange:or,onMouseDown:Ei,"aria-activedescendant":Ie?"":null,"aria-autocomplete":r?"both":"list","aria-controls":St?`${V}-listbox`:void 0,"aria-expanded":St,autoComplete:"off",ref:je,autoCapitalize:"none",spellCheck:"false",role:"combobox",disabled:v}),getClearProps:()=>({tabIndex:-1,type:"button",onClick:On}),getPopupIndicatorProps:()=>({tabIndex:-1,type:"button",onClick:ss}),getTagProps:({index:B})=>X({key:B,"data-tag-index":B,tabIndex:-1},!de&&{onDelete:ui(B)}),getListboxProps:()=>({role:"listbox",id:`${V}-listbox`,"aria-labelledby":`${V}-label`,ref:fe,onMouseDown:B=>{B.preventDefault()}}),getOptionProps:({index:B,option:ne})=>{var _e;const ye=(Q?ke:[ke]).some(Qe=>Qe!=null&&H(ne,Qe)),we=w?w(ne):!1;return{key:(_e=T==null?void 0:T(ne))!=null?_e:me(ne),tabIndex:-1,role:"option",id:`${V}-option-${B}`,onMouseMove:Kn,onClick:gr,onTouchStart:Fr,"data-option-index":B,"aria-disabled":we,"aria-selected":ye}},id:V,inputValue:tt,value:ke,dirty:di,expanded:Ie&&xe,popupOpen:Ie,focused:G||Re!==-1,anchorEl:xe,setAnchorEl:et,focusedTag:Re,groupedOptions:Gi}}var _R={};Object.defineProperty(_R,"__esModule",{value:!0});var T7=_R.default=void 0,Qte=ene(D),Jte=X8;function A7(t){if(typeof WeakMap!="function")return null;var e=new WeakMap,n=new WeakMap;return(A7=function(r){return r?n:e})(t)}function ene(t,e){if(!e&&t&&t.__esModule)return t;if(t===null||typeof t!="object"&&typeof t!="function")return{default:t};var n=A7(e);if(n&&n.has(t))return n.get(t);var r={__proto__:null},i=Object.defineProperty&&Object.getOwnPropertyDescriptor;for(var s in t)if(s!=="default"&&Object.prototype.hasOwnProperty.call(t,s)){var o=i?Object.getOwnPropertyDescriptor(t,s):null;o&&(o.get||o.set)?Object.defineProperty(r,s,o):r[s]=t[s]}return r.default=t,n&&n.set(t,r),r}function tne(t){return Object.keys(t).length===0}function nne(t=null){const e=Qte.useContext(Jte.ThemeContext);return!e||tne(e)?t:e}T7=_R.default=nne;const rne=["anchorEl","component","components","componentsProps","container","disablePortal","keepMounted","modifiers","open","placement","popperOptions","popperRef","transition","slots","slotProps"],ine=lt(Dte,{name:"MuiPopper",slot:"Root",overridesResolver:(t,e)=>e.root})({}),sne=D.forwardRef(function(e,n){var r;const i=T7(),s=En({props:e,name:"MuiPopper"}),{anchorEl:o,component:a,components:l,componentsProps:c,container:f,disablePortal:p,keepMounted:g,modifiers:v,open:x,placement:_,popperOptions:b,popperRef:y,transition:S,slots:w,slotProps:T}=s,L=Rt(s,rne),R=(r=w==null?void 0:w.root)!=null?r:l==null?void 0:l.Root,P=X({anchorEl:o,container:f,disablePortal:p,keepMounted:g,modifiers:v,open:x,placement:_,popperOptions:b,popperRef:y,transition:S},L);return C.jsx(ine,X({as:a,direction:i==null?void 0:i.direction,slots:{root:R},slotProps:T??c},P,{ref:n}))}),Hw=sne;function one(t){return bn("MuiListSubheader",t)}pn("MuiListSubheader",["root","colorPrimary","colorInherit","gutters","inset","sticky"]);const ane=["className","color","component","disableGutters","disableSticky","inset"],lne=t=>{const{classes:e,color:n,disableGutters:r,inset:i,disableSticky:s}=t,o={root:["root",n!=="default"&&`color${gt(n)}`,!r&&"gutters",i&&"inset",!s&&"sticky"]};return Sn(o,one,e)},cne=lt("li",{name:"MuiListSubheader",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.color!=="default"&&e[`color${gt(n.color)}`],!n.disableGutters&&e.gutters,n.inset&&e.inset,!n.disableSticky&&e.sticky]}})(({theme:t,ownerState:e})=>X({boxSizing:"border-box",lineHeight:"48px",listStyle:"none",color:(t.vars||t).palette.text.secondary,fontFamily:t.typography.fontFamily,fontWeight:t.typography.fontWeightMedium,fontSize:t.typography.pxToRem(14)},e.color==="primary"&&{color:(t.vars||t).palette.primary.main},e.color==="inherit"&&{color:"inherit"},!e.disableGutters&&{paddingLeft:16,paddingRight:16},e.inset&&{paddingLeft:72},!e.disableSticky&&{position:"sticky",top:0,zIndex:1,backgroundColor:(t.vars||t).palette.background.paper})),R7=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiListSubheader"}),{className:i,color:s="default",component:o="li",disableGutters:a=!1,disableSticky:l=!1,inset:c=!1}=r,f=Rt(r,ane),p=X({},r,{color:s,component:o,disableGutters:a,disableSticky:l,inset:c}),g=lne(p);return C.jsx(cne,X({as:o,className:At(g.root,i),ref:n,ownerState:p},f))});R7.muiSkipListHighlight=!0;const une=R7,dne=bt(C.jsx("path",{d:"M12 2C6.47 2 2 6.47 2 12s4.47 10 10 10 10-4.47 10-10S17.53 2 12 2zm5 13.59L15.59 17 12 13.41 8.41 17 7 15.59 10.59 12 7 8.41 8.41 7 12 10.59 15.59 7 17 8.41 13.41 12 17 15.59z"}),"Cancel");function fne(t){return bn("MuiChip",t)}const hne=pn("MuiChip",["root","sizeSmall","sizeMedium","colorError","colorInfo","colorPrimary","colorSecondary","colorSuccess","colorWarning","disabled","clickable","clickableColorPrimary","clickableColorSecondary","deletable","deletableColorPrimary","deletableColorSecondary","outlined","filled","outlinedPrimary","outlinedSecondary","filledPrimary","filledSecondary","avatar","avatarSmall","avatarMedium","avatarColorPrimary","avatarColorSecondary","icon","iconSmall","iconMedium","iconColorPrimary","iconColorSecondary","label","labelSmall","labelMedium","deleteIcon","deleteIconSmall","deleteIconMedium","deleteIconColorPrimary","deleteIconColorSecondary","deleteIconOutlinedColorPrimary","deleteIconOutlinedColorSecondary","deleteIconFilledColorPrimary","deleteIconFilledColorSecondary","focusVisible"]),dr=hne,pne=["avatar","className","clickable","color","component","deleteIcon","disabled","icon","label","onClick","onDelete","onKeyDown","onKeyUp","size","variant","tabIndex","skipFocusWhenDisabled"],mne=t=>{const{classes:e,disabled:n,size:r,color:i,iconColor:s,onDelete:o,clickable:a,variant:l}=t,c={root:["root",l,n&&"disabled",`size${gt(r)}`,`color${gt(i)}`,a&&"clickable",a&&`clickableColor${gt(i)}`,o&&"deletable",o&&`deletableColor${gt(i)}`,`${l}${gt(i)}`],label:["label",`label${gt(r)}`],avatar:["avatar",`avatar${gt(r)}`,`avatarColor${gt(i)}`],icon:["icon",`icon${gt(r)}`,`iconColor${gt(s)}`],deleteIcon:["deleteIcon",`deleteIcon${gt(r)}`,`deleteIconColor${gt(i)}`,`deleteIcon${gt(l)}Color${gt(i)}`]};return Sn(c,fne,e)},gne=lt("div",{name:"MuiChip",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t,{color:r,iconColor:i,clickable:s,onDelete:o,size:a,variant:l}=n;return[{[`& .${dr.avatar}`]:e.avatar},{[`& .${dr.avatar}`]:e[`avatar${gt(a)}`]},{[`& .${dr.avatar}`]:e[`avatarColor${gt(r)}`]},{[`& .${dr.icon}`]:e.icon},{[`& .${dr.icon}`]:e[`icon${gt(a)}`]},{[`& .${dr.icon}`]:e[`iconColor${gt(i)}`]},{[`& .${dr.deleteIcon}`]:e.deleteIcon},{[`& .${dr.deleteIcon}`]:e[`deleteIcon${gt(a)}`]},{[`& .${dr.deleteIcon}`]:e[`deleteIconColor${gt(r)}`]},{[`& .${dr.deleteIcon}`]:e[`deleteIcon${gt(l)}Color${gt(r)}`]},e.root,e[`size${gt(a)}`],e[`color${gt(r)}`],s&&e.clickable,s&&r!=="default"&&e[`clickableColor${gt(r)})`],o&&e.deletable,o&&r!=="default"&&e[`deletableColor${gt(r)}`],e[l],e[`${l}${gt(r)}`]]}})(({theme:t,ownerState:e})=>{const n=t.palette.mode==="light"?t.palette.grey[700]:t.palette.grey[300];return X({maxWidth:"100%",fontFamily:t.typography.fontFamily,fontSize:t.typography.pxToRem(13),display:"inline-flex",alignItems:"center",justifyContent:"center",height:32,color:(t.vars||t).palette.text.primary,backgroundColor:(t.vars||t).palette.action.selected,borderRadius:32/2,whiteSpace:"nowrap",transition:t.transitions.create(["background-color","box-shadow"]),cursor:"unset",outline:0,textDecoration:"none",border:0,padding:0,verticalAlign:"middle",boxSizing:"border-box",[`&.${dr.disabled}`]:{opacity:(t.vars||t).palette.action.disabledOpacity,pointerEvents:"none"},[`& .${dr.avatar}`]:{marginLeft:5,marginRight:-6,width:24,height:24,color:t.vars?t.vars.palette.Chip.defaultAvatarColor:n,fontSize:t.typography.pxToRem(12)},[`& .${dr.avatarColorPrimary}`]:{color:(t.vars||t).palette.primary.contrastText,backgroundColor:(t.vars||t).palette.primary.dark},[`& .${dr.avatarColorSecondary}`]:{color:(t.vars||t).palette.secondary.contrastText,backgroundColor:(t.vars||t).palette.secondary.dark},[`& .${dr.avatarSmall}`]:{marginLeft:4,marginRight:-4,width:18,height:18,fontSize:t.typography.pxToRem(10)},[`& .${dr.icon}`]:X({marginLeft:5,marginRight:-6},e.size==="small"&&{fontSize:18,marginLeft:4,marginRight:-4},e.iconColor===e.color&&X({color:t.vars?t.vars.palette.Chip.defaultIconColor:n},e.color!=="default"&&{color:"inherit"})),[`& .${dr.deleteIcon}`]:X({WebkitTapHighlightColor:"transparent",color:t.vars?`rgba(${t.vars.palette.text.primaryChannel} / 0.26)`:qn(t.palette.text.primary,.26),fontSize:22,cursor:"pointer",margin:"0 5px 0 -6px","&:hover":{color:t.vars?`rgba(${t.vars.palette.text.primaryChannel} / 0.4)`:qn(t.palette.text.primary,.4)}},e.size==="small"&&{fontSize:16,marginRight:4,marginLeft:-4},e.color!=="default"&&{color:t.vars?`rgba(${t.vars.palette[e.color].contrastTextChannel} / 0.7)`:qn(t.palette[e.color].contrastText,.7),"&:hover, &:active":{color:(t.vars||t).palette[e.color].contrastText}})},e.size==="small"&&{height:24},e.color!=="default"&&{backgroundColor:(t.vars||t).palette[e.color].main,color:(t.vars||t).palette[e.color].contrastText},e.onDelete&&{[`&.${dr.focusVisible}`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.action.selectedChannel} / calc(${t.vars.palette.action.selectedOpacity} + ${t.vars.palette.action.focusOpacity}))`:qn(t.palette.action.selected,t.palette.action.selectedOpacity+t.palette.action.focusOpacity)}},e.onDelete&&e.color!=="default"&&{[`&.${dr.focusVisible}`]:{backgroundColor:(t.vars||t).palette[e.color].dark}})},({theme:t,ownerState:e})=>X({},e.clickable&&{userSelect:"none",WebkitTapHighlightColor:"transparent",cursor:"pointer","&:hover":{backgroundColor:t.vars?`rgba(${t.vars.palette.action.selectedChannel} / calc(${t.vars.palette.action.selectedOpacity} + ${t.vars.palette.action.hoverOpacity}))`:qn(t.palette.action.selected,t.palette.action.selectedOpacity+t.palette.action.hoverOpacity)},[`&.${dr.focusVisible}`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.action.selectedChannel} / calc(${t.vars.palette.action.selectedOpacity} + ${t.vars.palette.action.focusOpacity}))`:qn(t.palette.action.selected,t.palette.action.selectedOpacity+t.palette.action.focusOpacity)},"&:active":{boxShadow:(t.vars||t).shadows[1]}},e.clickable&&e.color!=="default"&&{[`&:hover, &.${dr.focusVisible}`]:{backgroundColor:(t.vars||t).palette[e.color].dark}}),({theme:t,ownerState:e})=>X({},e.variant==="outlined"&&{backgroundColor:"transparent",border:t.vars?`1px solid ${t.vars.palette.Chip.defaultBorder}`:`1px solid ${t.palette.mode==="light"?t.palette.grey[400]:t.palette.grey[700]}`,[`&.${dr.clickable}:hover`]:{backgroundColor:(t.vars||t).palette.action.hover},[`&.${dr.focusVisible}`]:{backgroundColor:(t.vars||t).palette.action.focus},[`& .${dr.avatar}`]:{marginLeft:4},[`& .${dr.avatarSmall}`]:{marginLeft:2},[`& .${dr.icon}`]:{marginLeft:4},[`& .${dr.iconSmall}`]:{marginLeft:2},[`& .${dr.deleteIcon}`]:{marginRight:5},[`& .${dr.deleteIconSmall}`]:{marginRight:3}},e.variant==="outlined"&&e.color!=="default"&&{color:(t.vars||t).palette[e.color].main,border:`1px solid ${t.vars?`rgba(${t.vars.palette[e.color].mainChannel} / 0.7)`:qn(t.palette[e.color].main,.7)}`,[`&.${dr.clickable}:hover`]:{backgroundColor:t.vars?`rgba(${t.vars.palette[e.color].mainChannel} / ${t.vars.palette.action.hoverOpacity})`:qn(t.palette[e.color].main,t.palette.action.hoverOpacity)},[`&.${dr.focusVisible}`]:{backgroundColor:t.vars?`rgba(${t.vars.palette[e.color].mainChannel} / ${t.vars.palette.action.focusOpacity})`:qn(t.palette[e.color].main,t.palette.action.focusOpacity)},[`& .${dr.deleteIcon}`]:{color:t.vars?`rgba(${t.vars.palette[e.color].mainChannel} / 0.7)`:qn(t.palette[e.color].main,.7),"&:hover, &:active":{color:(t.vars||t).palette[e.color].main}}})),vne=lt("span",{name:"MuiChip",slot:"Label",overridesResolver:(t,e)=>{const{ownerState:n}=t,{size:r}=n;return[e.label,e[`label${gt(r)}`]]}})(({ownerState:t})=>X({overflow:"hidden",textOverflow:"ellipsis",paddingLeft:12,paddingRight:12,whiteSpace:"nowrap"},t.variant==="outlined"&&{paddingLeft:11,paddingRight:11},t.size==="small"&&{paddingLeft:8,paddingRight:8},t.size==="small"&&t.variant==="outlined"&&{paddingLeft:7,paddingRight:7}));function rk(t){return t.key==="Backspace"||t.key==="Delete"}const yne=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiChip"}),{avatar:i,className:s,clickable:o,color:a="default",component:l,deleteIcon:c,disabled:f=!1,icon:p,label:g,onClick:v,onDelete:x,onKeyDown:_,onKeyUp:b,size:y="medium",variant:S="filled",tabIndex:w,skipFocusWhenDisabled:T=!1}=r,L=Rt(r,pne),R=D.useRef(null),P=Kr(R,n),F=te=>{te.stopPropagation(),x&&x(te)},O=te=>{te.currentTarget===te.target&&rk(te)&&te.preventDefault(),_&&_(te)},I=te=>{te.currentTarget===te.target&&(x&&rk(te)?x(te):te.key==="Escape"&&R.current&&R.current.blur()),b&&b(te)},H=o!==!1&&v?!0:o,Q=H||x?Nu:l||"div",q=X({},r,{component:Q,disabled:f,size:y,color:a,iconColor:D.isValidElement(p)&&p.props.color||a,onDelete:!!x,clickable:H,variant:S}),le=mne(q),ie=Q===Nu?X({component:l||"div",focusVisibleClassName:le.focusVisible},x&&{disableRipple:!0}):{};let ee=null;x&&(ee=c&&D.isValidElement(c)?D.cloneElement(c,{className:At(c.props.className,le.deleteIcon),onClick:F}):C.jsx(dne,{className:At(le.deleteIcon),onClick:F}));let ue=null;i&&D.isValidElement(i)&&(ue=D.cloneElement(i,{className:At(le.avatar,i.props.className)}));let z=null;return p&&D.isValidElement(p)&&(z=D.cloneElement(p,{className:At(le.icon,p.props.className)})),C.jsxs(gne,X({as:Q,className:At(le.root,s),disabled:H&&f?!0:void 0,onClick:v,onKeyDown:O,onKeyUp:I,ref:P,tabIndex:T&&f?-1:w,ownerState:q},ie,L,{children:[ue||z,C.jsx(vne,{className:At(le.label),ownerState:q,children:g}),ee]}))}),xne=yne;function vg({props:t,states:e,muiFormControl:n}){return e.reduce((r,i)=>(r[i]=t[i],n&&typeof t[i]>"u"&&(r[i]=n[i]),r),{})}const _ne=D.createContext(void 0),bR=_ne;function _p(){return D.useContext(bR)}function ik(t){return t!=null&&!(Array.isArray(t)&&t.length===0)}function m2(t,e=!1){return t&&(ik(t.value)&&t.value!==""||e&&ik(t.defaultValue)&&t.defaultValue!=="")}function bne(t){return t.startAdornment}function Sne(t){return bn("MuiInputBase",t)}const wne=pn("MuiInputBase",["root","formControl","focused","disabled","adornedStart","adornedEnd","error","sizeSmall","multiline","colorSecondary","fullWidth","hiddenLabel","readOnly","input","inputSizeSmall","inputMultiline","inputTypeSearch","inputAdornedStart","inputAdornedEnd","inputHiddenLabel"]),ma=wne,Mne=["aria-describedby","autoComplete","autoFocus","className","color","components","componentsProps","defaultValue","disabled","disableInjectingGlobalStyles","endAdornment","error","fullWidth","id","inputComponent","inputProps","inputRef","margin","maxRows","minRows","multiline","name","onBlur","onChange","onClick","onFocus","onKeyDown","onKeyUp","placeholder","readOnly","renderSuffix","rows","size","slotProps","slots","startAdornment","type","value"],$w=(t,e)=>{const{ownerState:n}=t;return[e.root,n.formControl&&e.formControl,n.startAdornment&&e.adornedStart,n.endAdornment&&e.adornedEnd,n.error&&e.error,n.size==="small"&&e.sizeSmall,n.multiline&&e.multiline,n.color&&e[`color${gt(n.color)}`],n.fullWidth&&e.fullWidth,n.hiddenLabel&&e.hiddenLabel]},Vw=(t,e)=>{const{ownerState:n}=t;return[e.input,n.size==="small"&&e.inputSizeSmall,n.multiline&&e.inputMultiline,n.type==="search"&&e.inputTypeSearch,n.startAdornment&&e.inputAdornedStart,n.endAdornment&&e.inputAdornedEnd,n.hiddenLabel&&e.inputHiddenLabel]},Ene=t=>{const{classes:e,color:n,disabled:r,error:i,endAdornment:s,focused:o,formControl:a,fullWidth:l,hiddenLabel:c,multiline:f,readOnly:p,size:g,startAdornment:v,type:x}=t,_={root:["root",`color${gt(n)}`,r&&"disabled",i&&"error",l&&"fullWidth",o&&"focused",a&&"formControl",g&&g!=="medium"&&`size${gt(g)}`,f&&"multiline",v&&"adornedStart",s&&"adornedEnd",c&&"hiddenLabel",p&&"readOnly"],input:["input",r&&"disabled",x==="search"&&"inputTypeSearch",f&&"inputMultiline",g==="small"&&"inputSizeSmall",c&&"inputHiddenLabel",v&&"inputAdornedStart",s&&"inputAdornedEnd",p&&"readOnly"]};return Sn(_,Sne,e)},Ww=lt("div",{name:"MuiInputBase",slot:"Root",overridesResolver:$w})(({theme:t,ownerState:e})=>X({},t.typography.body1,{color:(t.vars||t).palette.text.primary,lineHeight:"1.4375em",boxSizing:"border-box",position:"relative",cursor:"text",display:"inline-flex",alignItems:"center",[`&.${ma.disabled}`]:{color:(t.vars||t).palette.text.disabled,cursor:"default"}},e.multiline&&X({padding:"4px 0 5px"},e.size==="small"&&{paddingTop:1}),e.fullWidth&&{width:"100%"})),jw=lt("input",{name:"MuiInputBase",slot:"Input",overridesResolver:Vw})(({theme:t,ownerState:e})=>{const n=t.palette.mode==="light",r=X({color:"currentColor"},t.vars?{opacity:t.vars.opacity.inputPlaceholder}:{opacity:n?.42:.5},{transition:t.transitions.create("opacity",{duration:t.transitions.duration.shorter})}),i={opacity:"0 !important"},s=t.vars?{opacity:t.vars.opacity.inputPlaceholder}:{opacity:n?.42:.5};return X({font:"inherit",letterSpacing:"inherit",color:"currentColor",padding:"4px 0 5px",border:0,boxSizing:"content-box",background:"none",height:"1.4375em",margin:0,WebkitTapHighlightColor:"transparent",display:"block",minWidth:0,width:"100%",animationName:"mui-auto-fill-cancel",animationDuration:"10ms","&::-webkit-input-placeholder":r,"&::-moz-placeholder":r,"&:-ms-input-placeholder":r,"&::-ms-input-placeholder":r,"&:focus":{outline:0},"&:invalid":{boxShadow:"none"},"&::-webkit-search-decoration":{WebkitAppearance:"none"},[`label[data-shrink=false] + .${ma.formControl} &`]:{"&::-webkit-input-placeholder":i,"&::-moz-placeholder":i,"&:-ms-input-placeholder":i,"&::-ms-input-placeholder":i,"&:focus::-webkit-input-placeholder":s,"&:focus::-moz-placeholder":s,"&:focus:-ms-input-placeholder":s,"&:focus::-ms-input-placeholder":s},[`&.${ma.disabled}`]:{opacity:1,WebkitTextFillColor:(t.vars||t).palette.text.disabled},"&:-webkit-autofill":{animationDuration:"5000s",animationName:"mui-auto-fill"}},e.size==="small"&&{paddingTop:1},e.multiline&&{height:"auto",resize:"none",padding:0,paddingTop:0},e.type==="search"&&{MozAppearance:"textfield"})}),Cne=C.jsx(G8,{styles:{"@keyframes mui-auto-fill":{from:{display:"block"}},"@keyframes mui-auto-fill-cancel":{from:{display:"block"}}}}),Tne=D.forwardRef(function(e,n){var r;const i=En({props:e,name:"MuiInputBase"}),{"aria-describedby":s,autoComplete:o,autoFocus:a,className:l,components:c={},componentsProps:f={},defaultValue:p,disabled:g,disableInjectingGlobalStyles:v,endAdornment:x,fullWidth:_=!1,id:b,inputComponent:y="input",inputProps:S={},inputRef:w,maxRows:T,minRows:L,multiline:R=!1,name:P,onBlur:F,onChange:O,onClick:I,onFocus:H,onKeyDown:Q,onKeyUp:q,placeholder:le,readOnly:ie,renderSuffix:ee,rows:ue,slotProps:z={},slots:te={},startAdornment:oe,type:de="text",value:Ce}=i,Le=Rt(i,Mne),V=S.value!=null?S.value:Ce,{current:me}=D.useRef(V!=null),pe=D.useRef(),Se=D.useCallback(Ie=>{},[]),je=Kr(pe,w,S.ref,Se),[it,xe]=D.useState(!1),et=_p(),Re=vg({props:i,muiFormControl:et,states:["color","disabled","error","hiddenLabel","size","required","filled"]});Re.focused=et?et.focused:it,D.useEffect(()=>{!et&&g&&it&&(xe(!1),F&&F())},[et,g,it,F]);const Oe=et&&et.onFilled,Te=et&&et.onEmpty,ze=D.useCallback(Ie=>{m2(Ie)?Oe&&Oe():Te&&Te()},[Oe,Te]);Xo(()=>{me&&ze({value:V})},[V,ze,me]);const ke=Ie=>{if(Re.disabled){Ie.stopPropagation();return}H&&H(Ie),S.onFocus&&S.onFocus(Ie),et&&et.onFocus?et.onFocus(Ie):xe(!0)},rt=Ie=>{F&&F(Ie),S.onBlur&&S.onBlur(Ie),et&&et.onBlur?et.onBlur(Ie):xe(!1)},tt=(Ie,...ge)=>{if(!me){const Xe=Ie.target||pe.current;if(Xe==null)throw new Error(op(1));ze({value:Xe.value})}S.onChange&&S.onChange(Ie,...ge),O&&O(Ie,...ge)};D.useEffect(()=>{ze(pe.current)},[]);const ae=Ie=>{pe.current&&Ie.currentTarget===Ie.target&&pe.current.focus(),I&&I(Ie)};let G=y,be=S;R&&G==="input"&&(ue?be=X({type:void 0,minRows:ue,maxRows:ue},be):be=X({type:void 0,maxRows:T,minRows:L},be),G=Xte);const $e=Ie=>{ze(Ie.animationName==="mui-auto-fill-cancel"?pe.current:{value:"x"})};D.useEffect(()=>{et&&et.setAdornedStart(!!oe)},[et,oe]);const Ze=X({},i,{color:Re.color||"primary",disabled:Re.disabled,endAdornment:x,error:Re.error,focused:Re.focused,formControl:et,fullWidth:_,hiddenLabel:Re.hiddenLabel,multiline:R,size:Re.size,startAdornment:oe,type:de}),We=Ene(Ze),Mt=te.root||c.Root||Ww,pt=z.root||f.root||{},at=te.input||c.Input||jw;return be=X({},be,(r=z.input)!=null?r:f.input),C.jsxs(D.Fragment,{children:[!v&&Cne,C.jsxs(Mt,X({},pt,!Rc(Mt)&&{ownerState:X({},Ze,pt.ownerState)},{ref:n,onClick:ae},Le,{className:At(We.root,pt.className,l,ie&&"MuiInputBase-readOnly"),children:[oe,C.jsx(bR.Provider,{value:null,children:C.jsx(at,X({ownerState:Ze,"aria-invalid":Re.error,"aria-describedby":s,autoComplete:o,autoFocus:a,defaultValue:p,disabled:Re.disabled,id:b,onAnimationStart:$e,name:P,placeholder:le,readOnly:ie,required:Re.required,rows:ue,value:V,onKeyDown:Q,onKeyUp:q,type:de},be,!Rc(at)&&{as:G,ownerState:X({},Ze,be.ownerState)},{ref:je,className:At(We.input,be.className,ie&&"MuiInputBase-readOnly"),onBlur:rt,onChange:tt,onFocus:ke}))}),x,ee?ee(X({},Re,{startAdornment:oe})):null]}))]})}),SR=Tne;function Ane(t){return bn("MuiInput",t)}const Rne=X({},ma,pn("MuiInput",["root","underline","input"])),Fd=Rne;function Pne(t){return bn("MuiOutlinedInput",t)}const Ine=X({},ma,pn("MuiOutlinedInput",["root","notchedOutline","input"])),pc=Ine;function Lne(t){return bn("MuiFilledInput",t)}const kne=X({},ma,pn("MuiFilledInput",["root","underline","input"])),ga=kne,P7=bt(C.jsx("path",{d:"M7 10l5 5 5-5z"}),"ArrowDropDown");function One(t){return bn("MuiAutocomplete",t)}const Xn=pn("MuiAutocomplete",["root","expanded","fullWidth","focused","focusVisible","tag","tagSizeSmall","tagSizeMedium","hasPopupIcon","hasClearIcon","inputRoot","input","inputFocused","endAdornment","clearIndicator","popupIndicator","popupIndicatorOpen","popper","popperDisablePortal","paper","listbox","loading","noOptions","option","groupLabel","groupUl"]);var sk,ok;const Nne=["autoComplete","autoHighlight","autoSelect","blurOnSelect","ChipProps","className","clearIcon","clearOnBlur","clearOnEscape","clearText","closeText","componentsProps","defaultValue","disableClearable","disableCloseOnSelect","disabled","disabledItemsFocusable","disableListWrap","disablePortal","filterOptions","filterSelectedOptions","forcePopupIcon","freeSolo","fullWidth","getLimitTagsText","getOptionDisabled","getOptionKey","getOptionLabel","isOptionEqualToValue","groupBy","handleHomeEndKeys","id","includeInputInList","inputValue","limitTags","ListboxComponent","ListboxProps","loading","loadingText","multiple","noOptionsText","onChange","onClose","onHighlightChange","onInputChange","onOpen","open","openOnFocus","openText","options","PaperComponent","PopperComponent","popupIcon","readOnly","renderGroup","renderInput","renderOption","renderTags","selectOnFocus","size","slotProps","value"],Dne=["ref"],Fne=cR(),Une=t=>{const{classes:e,disablePortal:n,expanded:r,focused:i,fullWidth:s,hasClearIcon:o,hasPopupIcon:a,inputFocused:l,popupOpen:c,size:f}=t,p={root:["root",r&&"expanded",i&&"focused",s&&"fullWidth",o&&"hasClearIcon",a&&"hasPopupIcon"],inputRoot:["inputRoot"],input:["input",l&&"inputFocused"],tag:["tag",`tagSize${gt(f)}`],endAdornment:["endAdornment"],clearIndicator:["clearIndicator"],popupIndicator:["popupIndicator",c&&"popupIndicatorOpen"],popper:["popper",n&&"popperDisablePortal"],paper:["paper"],listbox:["listbox"],loading:["loading"],noOptions:["noOptions"],option:["option"],groupLabel:["groupLabel"],groupUl:["groupUl"]};return Sn(p,One,e)},zne=lt("div",{name:"MuiAutocomplete",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t,{fullWidth:r,hasClearIcon:i,hasPopupIcon:s,inputFocused:o,size:a}=n;return[{[`& .${Xn.tag}`]:e.tag},{[`& .${Xn.tag}`]:e[`tagSize${gt(a)}`]},{[`& .${Xn.inputRoot}`]:e.inputRoot},{[`& .${Xn.input}`]:e.input},{[`& .${Xn.input}`]:o&&e.inputFocused},e.root,r&&e.fullWidth,s&&e.hasPopupIcon,i&&e.hasClearIcon]}})({[`&.${Xn.focused} .${Xn.clearIndicator}`]:{visibility:"visible"},"@media (pointer: fine)":{[`&:hover .${Xn.clearIndicator}`]:{visibility:"visible"}},[`& .${Xn.tag}`]:{margin:3,maxWidth:"calc(100% - 6px)"},[`& .${Xn.inputRoot}`]:{flexWrap:"wrap",[`.${Xn.hasPopupIcon}&, .${Xn.hasClearIcon}&`]:{paddingRight:30},[`.${Xn.hasPopupIcon}.${Xn.hasClearIcon}&`]:{paddingRight:56},[`& .${Xn.input}`]:{width:0,minWidth:30}},[`& .${Fd.root}`]:{paddingBottom:1,"& .MuiInput-input":{padding:"4px 4px 4px 0px"}},[`& .${Fd.root}.${ma.sizeSmall}`]:{[`& .${Fd.input}`]:{padding:"2px 4px 3px 0"}},[`& .${pc.root}`]:{padding:9,[`.${Xn.hasPopupIcon}&, .${Xn.hasClearIcon}&`]:{paddingRight:39},[`.${Xn.hasPopupIcon}.${Xn.hasClearIcon}&`]:{paddingRight:65},[`& .${Xn.input}`]:{padding:"7.5px 4px 7.5px 5px"},[`& .${Xn.endAdornment}`]:{right:9}},[`& .${pc.root}.${ma.sizeSmall}`]:{paddingTop:6,paddingBottom:6,paddingLeft:6,[`& .${Xn.input}`]:{padding:"2.5px 4px 2.5px 8px"}},[`& .${ga.root}`]:{paddingTop:19,paddingLeft:8,[`.${Xn.hasPopupIcon}&, .${Xn.hasClearIcon}&`]:{paddingRight:39},[`.${Xn.hasPopupIcon}.${Xn.hasClearIcon}&`]:{paddingRight:65},[`& .${ga.input}`]:{padding:"7px 4px"},[`& .${Xn.endAdornment}`]:{right:9}},[`& .${ga.root}.${ma.sizeSmall}`]:{paddingBottom:1,[`& .${ga.input}`]:{padding:"2.5px 4px"}},[`& .${ma.hiddenLabel}`]:{paddingTop:8},[`& .${ga.root}.${ma.hiddenLabel}`]:{paddingTop:0,paddingBottom:0,[`& .${Xn.input}`]:{paddingTop:16,paddingBottom:17}},[`& .${ga.root}.${ma.hiddenLabel}.${ma.sizeSmall}`]:{[`& .${Xn.input}`]:{paddingTop:8,paddingBottom:9}},[`& .${Xn.input}`]:{flexGrow:1,textOverflow:"ellipsis",opacity:0},variants:[{props:{fullWidth:!0},style:{width:"100%"}},{props:{size:"small"},style:{[`& .${Xn.tag}`]:{margin:2,maxWidth:"calc(100% - 4px)"}}},{props:{inputFocused:!0},style:{[`& .${Xn.input}`]:{opacity:1}}}]}),Bne=lt("div",{name:"MuiAutocomplete",slot:"EndAdornment",overridesResolver:(t,e)=>e.endAdornment})({position:"absolute",right:0,top:"50%",transform:"translate(0, -50%)"}),Hne=lt(Vu,{name:"MuiAutocomplete",slot:"ClearIndicator",overridesResolver:(t,e)=>e.clearIndicator})({marginRight:-2,padding:4,visibility:"hidden"}),$ne=lt(Vu,{name:"MuiAutocomplete",slot:"PopupIndicator",overridesResolver:({ownerState:t},e)=>X({},e.popupIndicator,t.popupOpen&&e.popupIndicatorOpen)})({padding:2,marginRight:-2,variants:[{props:{popupOpen:!0},style:{transform:"rotate(180deg)"}}]}),Vne=lt(Hw,{name:"MuiAutocomplete",slot:"Popper",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[{[`& .${Xn.option}`]:e.option},e.popper,n.disablePortal&&e.popperDisablePortal]}})(({theme:t})=>({zIndex:(t.vars||t).zIndex.modal,variants:[{props:{disablePortal:!0},style:{position:"absolute"}}]})),Wne=lt(nx,{name:"MuiAutocomplete",slot:"Paper",overridesResolver:(t,e)=>e.paper})(({theme:t})=>X({},t.typography.body1,{overflow:"auto"})),jne=lt("div",{name:"MuiAutocomplete",slot:"Loading",overridesResolver:(t,e)=>e.loading})(({theme:t})=>({color:(t.vars||t).palette.text.secondary,padding:"14px 16px"})),Gne=lt("div",{name:"MuiAutocomplete",slot:"NoOptions",overridesResolver:(t,e)=>e.noOptions})(({theme:t})=>({color:(t.vars||t).palette.text.secondary,padding:"14px 16px"})),Xne=lt("div",{name:"MuiAutocomplete",slot:"Listbox",overridesResolver:(t,e)=>e.listbox})(({theme:t})=>({listStyle:"none",margin:0,padding:"8px 0",maxHeight:"40vh",overflow:"auto",position:"relative",[`& .${Xn.option}`]:{minHeight:48,display:"flex",overflow:"hidden",justifyContent:"flex-start",alignItems:"center",cursor:"pointer",paddingTop:6,boxSizing:"border-box",outline:"0",WebkitTapHighlightColor:"transparent",paddingBottom:6,paddingLeft:16,paddingRight:16,[t.breakpoints.up("sm")]:{minHeight:"auto"},[`&.${Xn.focused}`]:{backgroundColor:(t.vars||t).palette.action.hover,"@media (hover: none)":{backgroundColor:"transparent"}},'&[aria-disabled="true"]':{opacity:(t.vars||t).palette.action.disabledOpacity,pointerEvents:"none"},[`&.${Xn.focusVisible}`]:{backgroundColor:(t.vars||t).palette.action.focus},'&[aria-selected="true"]':{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / ${t.vars.palette.action.selectedOpacity})`:qn(t.palette.primary.main,t.palette.action.selectedOpacity),[`&.${Xn.focused}`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / calc(${t.vars.palette.action.selectedOpacity} + ${t.vars.palette.action.hoverOpacity}))`:qn(t.palette.primary.main,t.palette.action.selectedOpacity+t.palette.action.hoverOpacity),"@media (hover: none)":{backgroundColor:(t.vars||t).palette.action.selected}},[`&.${Xn.focusVisible}`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / calc(${t.vars.palette.action.selectedOpacity} + ${t.vars.palette.action.focusOpacity}))`:qn(t.palette.primary.main,t.palette.action.selectedOpacity+t.palette.action.focusOpacity)}}}})),qne=lt(une,{name:"MuiAutocomplete",slot:"GroupLabel",overridesResolver:(t,e)=>e.groupLabel})(({theme:t})=>({backgroundColor:(t.vars||t).palette.background.paper,top:-8})),Zne=lt("ul",{name:"MuiAutocomplete",slot:"GroupUl",overridesResolver:(t,e)=>e.groupUl})({padding:0,[`& .${Xn.option}`]:{paddingLeft:24}}),Yne=D.forwardRef(function(e,n){var r,i,s,o;const a=Fne({props:e,name:"MuiAutocomplete"}),{autoComplete:l=!1,autoHighlight:c=!1,autoSelect:f=!1,blurOnSelect:p=!1,ChipProps:g,className:v,clearIcon:x=sk||(sk=C.jsx(qJ,{fontSize:"small"})),clearOnBlur:_=!a.freeSolo,clearOnEscape:b=!1,clearText:y="Clear",closeText:S="Close",componentsProps:w={},defaultValue:T=a.multiple?[]:null,disableClearable:L=!1,disableCloseOnSelect:R=!1,disabled:P=!1,disabledItemsFocusable:F=!1,disableListWrap:O=!1,disablePortal:I=!1,filterSelectedOptions:H=!1,forcePopupIcon:Q="auto",freeSolo:q=!1,fullWidth:le=!1,getLimitTagsText:ie=ye=>`+${ye}`,getOptionLabel:ee,groupBy:ue,handleHomeEndKeys:z=!a.freeSolo,includeInputInList:te=!1,limitTags:oe=-1,ListboxComponent:de="ul",ListboxProps:Ce,loading:Le=!1,loadingText:V="Loading…",multiple:me=!1,noOptionsText:pe="No options",openOnFocus:Se=!1,openText:je="Open",PaperComponent:it=nx,PopperComponent:xe=Hw,popupIcon:et=ok||(ok=C.jsx(P7,{})),readOnly:Re=!1,renderGroup:Oe,renderInput:Te,renderOption:ze,renderTags:ke,selectOnFocus:rt=!a.freeSolo,size:tt="medium",slotProps:ae={}}=a,G=Rt(a,Nne),{getRootProps:be,getInputProps:$e,getInputLabelProps:Ze,getPopupIndicatorProps:We,getClearProps:Mt,getTagProps:pt,getListboxProps:at,getOptionProps:Ie,value:ge,dirty:Xe,expanded:St,id:mt,popupOpen:Be,focused:vt,focusedTag:qe,anchorEl:ce,setAnchorEl:Ne,inputValue:fe,groupedOptions:Fe}=Kte(X({},a,{componentName:"Autocomplete"})),He=!L&&!P&&Xe&&!Re,ut=(!q||Q===!0)&&Q!==!1,{onMouseDown:xt}=$e(),{ref:Xt}=Ce??{},vn=at(),{ref:mn}=vn,On=Rt(vn,Dne),un=Kr(mn,Xt),In=ee||(ye=>{var we;return(we=ye.label)!=null?we:ye}),or=X({},a,{disablePortal:I,expanded:St,focused:vt,fullWidth:le,getOptionLabel:In,hasClearIcon:He,hasPopupIcon:ut,inputFocused:qe===-1,popupOpen:Be,size:tt}),Kn=Une(or);let Fr;if(me&&ge.length>0){const ye=we=>X({className:Kn.tag,disabled:P},pt(we));ke?Fr=ke(ge,ye,or):Fr=ge.map((we,Qe)=>C.jsx(xne,X({label:In(we),size:tt},ye({index:Qe}),g)))}if(oe>-1&&Array.isArray(Fr)){const ye=Fr.length-oe;!vt&&ye>0&&(Fr=Fr.splice(0,oe),Fr.push(C.jsx("span",{className:Kn.tag,children:ie(ye)},Fr.length)))}const ui=Oe||(ye=>C.jsxs("li",{children:[C.jsx(qne,{className:Kn.groupLabel,ownerState:or,component:"div",children:ye.group}),C.jsx(Zne,{className:Kn.groupUl,ownerState:or,children:ye.children})]},ye.key)),Rr=ze||((ye,we)=>D.createElement("li",X({},ye,{key:ye.key}),In(we))),ji=(ye,we)=>{const Qe=Ie({option:ye,index:we});return Rr(X({},Qe,{className:Kn.option}),ye,{selected:Qe["aria-selected"],index:we,inputValue:fe},or)},Ei=(r=ae.clearIndicator)!=null?r:w.clearIndicator,di=(i=ae.paper)!=null?i:w.paper,Gi=(s=ae.popper)!=null?s:w.popper,B=(o=ae.popupIndicator)!=null?o:w.popupIndicator,ne=ye=>C.jsx(Vne,X({as:xe,disablePortal:I,style:{width:ce?ce.clientWidth:null},ownerState:or,role:"presentation",anchorEl:ce,open:Be},Gi,{className:At(Kn.popper,Gi==null?void 0:Gi.className),children:C.jsx(Wne,X({ownerState:or,as:it},di,{className:At(Kn.paper,di==null?void 0:di.className),children:ye}))}));let _e=null;return Fe.length>0?_e=ne(C.jsx(Xne,X({as:de,className:Kn.listbox,ownerState:or},On,Ce,{ref:un,children:Fe.map((ye,we)=>ue?ui({key:ye.key,group:ye.group,children:ye.options.map((Qe,wt)=>ji(Qe,ye.index+wt))}):ji(ye,we))}))):Le&&Fe.length===0?_e=ne(C.jsx(jne,{className:Kn.loading,ownerState:or,children:V})):Fe.length===0&&!q&&!Le&&(_e=ne(C.jsx(Gne,{className:Kn.noOptions,ownerState:or,role:"presentation",onMouseDown:ye=>{ye.preventDefault()},children:pe}))),C.jsxs(D.Fragment,{children:[C.jsx(zne,X({ref:n,className:At(Kn.root,v),ownerState:or},be(G),{children:Te({id:mt,disabled:P,fullWidth:!0,size:tt==="small"?"small":void 0,InputLabelProps:Ze(),InputProps:X({ref:Ne,className:Kn.inputRoot,startAdornment:Fr,onClick:ye=>{ye.target===ye.currentTarget&&xt(ye)}},(He||ut)&&{endAdornment:C.jsxs(Bne,{className:Kn.endAdornment,ownerState:or,children:[He?C.jsx(Hne,X({},Mt(),{"aria-label":y,title:y,ownerState:or},Ei,{className:At(Kn.clearIndicator,Ei==null?void 0:Ei.className),children:x})):null,ut?C.jsx($ne,X({},We(),{disabled:P,"aria-label":Be?S:je,title:Be?S:je,ownerState:or},B,{className:At(Kn.popupIndicator,B==null?void 0:B.className),children:et})):null]})}),inputProps:X({className:Kn.input,disabled:P,readOnly:Re},$e())})})),ce?_e:null]})}),Kne=Yne,Qne=["addEndListener","appear","children","easing","in","onEnter","onEntered","onEntering","onExit","onExited","onExiting","style","timeout","TransitionComponent"],Jne={entering:{opacity:1},entered:{opacity:1}},ere=D.forwardRef(function(e,n){const r=Bu(),i={enter:r.transitions.duration.enteringScreen,exit:r.transitions.duration.leavingScreen},{addEndListener:s,appear:o=!0,children:a,easing:l,in:c,onEnter:f,onEntered:p,onEntering:g,onExit:v,onExited:x,onExiting:_,style:b,timeout:y=i,TransitionComponent:S=uR}=e,w=Rt(e,Qne),T=D.useRef(null),L=Kr(T,a.ref,n),R=le=>ie=>{if(le){const ee=T.current;ie===void 0?le(ee):le(ee,ie)}},P=R(g),F=R((le,ie)=>{u7(le);const ee=j0({style:b,timeout:y,easing:l},{mode:"enter"});le.style.webkitTransition=r.transitions.create("opacity",ee),le.style.transition=r.transitions.create("opacity",ee),f&&f(le,ie)}),O=R(p),I=R(_),H=R(le=>{const ie=j0({style:b,timeout:y,easing:l},{mode:"exit"});le.style.webkitTransition=r.transitions.create("opacity",ie),le.style.transition=r.transitions.create("opacity",ie),v&&v(le)}),Q=R(x),q=le=>{s&&s(T.current,le)};return C.jsx(S,X({appear:o,in:c,nodeRef:T,onEnter:F,onEntered:O,onEntering:P,onExit:H,onExited:Q,onExiting:I,addEndListener:q,timeout:y},w,{children:(le,ie)=>D.cloneElement(a,X({style:X({opacity:0,visibility:le==="exited"&&!c?"hidden":void 0},Jne[le],b,a.props.style),ref:L},ie))}))}),I7=ere;function tre(t){return bn("MuiBackdrop",t)}pn("MuiBackdrop",["root","invisible"]);const nre=["children","className","component","components","componentsProps","invisible","open","slotProps","slots","TransitionComponent","transitionDuration"],rre=t=>{const{classes:e,invisible:n}=t;return Sn({root:["root",n&&"invisible"]},tre,e)},ire=lt("div",{name:"MuiBackdrop",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.invisible&&e.invisible]}})(({ownerState:t})=>X({position:"fixed",display:"flex",alignItems:"center",justifyContent:"center",right:0,bottom:0,top:0,left:0,backgroundColor:"rgba(0, 0, 0, 0.5)",WebkitTapHighlightColor:"transparent"},t.invisible&&{backgroundColor:"transparent"})),sre=D.forwardRef(function(e,n){var r,i,s;const o=En({props:e,name:"MuiBackdrop"}),{children:a,className:l,component:c="div",components:f={},componentsProps:p={},invisible:g=!1,open:v,slotProps:x={},slots:_={},TransitionComponent:b=I7,transitionDuration:y}=o,S=Rt(o,nre),w=X({},o,{component:c,invisible:g}),T=rre(w),L=(r=x.root)!=null?r:p.root;return C.jsx(b,X({in:v,timeout:y},S,{children:C.jsx(ire,X({"aria-hidden":!0},L,{as:(i=(s=_.root)!=null?s:f.Root)!=null?i:c,className:At(T.root,l,L==null?void 0:L.className),ownerState:X({},w,L==null?void 0:L.ownerState),classes:T,ref:n,children:a}))}))}),Uc=sre,ore=pn("MuiBox",["root"]),are=ore,lre=eR(),cre=$Y({themeId:lp,defaultTheme:lre,defaultClassName:are.root,generateClassName:Y3.generate}),_o=cre;function ure(t){return bn("MuiButton",t)}const dre=pn("MuiButton",["root","text","textInherit","textPrimary","textSecondary","textSuccess","textError","textInfo","textWarning","outlined","outlinedInherit","outlinedPrimary","outlinedSecondary","outlinedSuccess","outlinedError","outlinedInfo","outlinedWarning","contained","containedInherit","containedPrimary","containedSecondary","containedSuccess","containedError","containedInfo","containedWarning","disableElevation","focusVisible","disabled","colorInherit","colorPrimary","colorSecondary","colorSuccess","colorError","colorInfo","colorWarning","textSizeSmall","textSizeMedium","textSizeLarge","outlinedSizeSmall","outlinedSizeMedium","outlinedSizeLarge","containedSizeSmall","containedSizeMedium","containedSizeLarge","sizeMedium","sizeSmall","sizeLarge","fullWidth","startIcon","endIcon","icon","iconSizeSmall","iconSizeMedium","iconSizeLarge"]),J_=dre,fre=D.createContext({}),hre=fre,pre=D.createContext(void 0),mre=pre,gre=["children","color","component","className","disabled","disableElevation","disableFocusRipple","endIcon","focusVisibleClassName","fullWidth","size","startIcon","type","variant"],vre=t=>{const{color:e,disableElevation:n,fullWidth:r,size:i,variant:s,classes:o}=t,a={root:["root",s,`${s}${gt(e)}`,`size${gt(i)}`,`${s}Size${gt(i)}`,`color${gt(e)}`,n&&"disableElevation",r&&"fullWidth"],label:["label"],startIcon:["icon","startIcon",`iconSize${gt(i)}`],endIcon:["icon","endIcon",`iconSize${gt(i)}`]},l=Sn(a,ure,o);return X({},o,l)},L7=t=>X({},t.size==="small"&&{"& > *:nth-of-type(1)":{fontSize:18}},t.size==="medium"&&{"& > *:nth-of-type(1)":{fontSize:20}},t.size==="large"&&{"& > *:nth-of-type(1)":{fontSize:22}}),yre=lt(Nu,{shouldForwardProp:t=>La(t)||t==="classes",name:"MuiButton",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,e[n.variant],e[`${n.variant}${gt(n.color)}`],e[`size${gt(n.size)}`],e[`${n.variant}Size${gt(n.size)}`],n.color==="inherit"&&e.colorInherit,n.disableElevation&&e.disableElevation,n.fullWidth&&e.fullWidth]}})(({theme:t,ownerState:e})=>{var n,r;const i=t.palette.mode==="light"?t.palette.grey[300]:t.palette.grey[800],s=t.palette.mode==="light"?t.palette.grey.A100:t.palette.grey[700];return X({},t.typography.button,{minWidth:64,padding:"6px 16px",borderRadius:(t.vars||t).shape.borderRadius,transition:t.transitions.create(["background-color","box-shadow","border-color","color"],{duration:t.transitions.duration.short}),"&:hover":X({textDecoration:"none",backgroundColor:t.vars?`rgba(${t.vars.palette.text.primaryChannel} / ${t.vars.palette.action.hoverOpacity})`:qn(t.palette.text.primary,t.palette.action.hoverOpacity),"@media (hover: none)":{backgroundColor:"transparent"}},e.variant==="text"&&e.color!=="inherit"&&{backgroundColor:t.vars?`rgba(${t.vars.palette[e.color].mainChannel} / ${t.vars.palette.action.hoverOpacity})`:qn(t.palette[e.color].main,t.palette.action.hoverOpacity),"@media (hover: none)":{backgroundColor:"transparent"}},e.variant==="outlined"&&e.color!=="inherit"&&{border:`1px solid ${(t.vars||t).palette[e.color].main}`,backgroundColor:t.vars?`rgba(${t.vars.palette[e.color].mainChannel} / ${t.vars.palette.action.hoverOpacity})`:qn(t.palette[e.color].main,t.palette.action.hoverOpacity),"@media (hover: none)":{backgroundColor:"transparent"}},e.variant==="contained"&&{backgroundColor:t.vars?t.vars.palette.Button.inheritContainedHoverBg:s,boxShadow:(t.vars||t).shadows[4],"@media (hover: none)":{boxShadow:(t.vars||t).shadows[2],backgroundColor:(t.vars||t).palette.grey[300]}},e.variant==="contained"&&e.color!=="inherit"&&{backgroundColor:(t.vars||t).palette[e.color].dark,"@media (hover: none)":{backgroundColor:(t.vars||t).palette[e.color].main}}),"&:active":X({},e.variant==="contained"&&{boxShadow:(t.vars||t).shadows[8]}),[`&.${J_.focusVisible}`]:X({},e.variant==="contained"&&{boxShadow:(t.vars||t).shadows[6]}),[`&.${J_.disabled}`]:X({color:(t.vars||t).palette.action.disabled},e.variant==="outlined"&&{border:`1px solid ${(t.vars||t).palette.action.disabledBackground}`},e.variant==="contained"&&{color:(t.vars||t).palette.action.disabled,boxShadow:(t.vars||t).shadows[0],backgroundColor:(t.vars||t).palette.action.disabledBackground})},e.variant==="text"&&{padding:"6px 8px"},e.variant==="text"&&e.color!=="inherit"&&{color:(t.vars||t).palette[e.color].main},e.variant==="outlined"&&{padding:"5px 15px",border:"1px solid currentColor"},e.variant==="outlined"&&e.color!=="inherit"&&{color:(t.vars||t).palette[e.color].main,border:t.vars?`1px solid rgba(${t.vars.palette[e.color].mainChannel} / 0.5)`:`1px solid ${qn(t.palette[e.color].main,.5)}`},e.variant==="contained"&&{color:t.vars?t.vars.palette.text.primary:(n=(r=t.palette).getContrastText)==null?void 0:n.call(r,t.palette.grey[300]),backgroundColor:t.vars?t.vars.palette.Button.inheritContainedBg:i,boxShadow:(t.vars||t).shadows[2]},e.variant==="contained"&&e.color!=="inherit"&&{color:(t.vars||t).palette[e.color].contrastText,backgroundColor:(t.vars||t).palette[e.color].main},e.color==="inherit"&&{color:"inherit",borderColor:"currentColor"},e.size==="small"&&e.variant==="text"&&{padding:"4px 5px",fontSize:t.typography.pxToRem(13)},e.size==="large"&&e.variant==="text"&&{padding:"8px 11px",fontSize:t.typography.pxToRem(15)},e.size==="small"&&e.variant==="outlined"&&{padding:"3px 9px",fontSize:t.typography.pxToRem(13)},e.size==="large"&&e.variant==="outlined"&&{padding:"7px 21px",fontSize:t.typography.pxToRem(15)},e.size==="small"&&e.variant==="contained"&&{padding:"4px 10px",fontSize:t.typography.pxToRem(13)},e.size==="large"&&e.variant==="contained"&&{padding:"8px 22px",fontSize:t.typography.pxToRem(15)},e.fullWidth&&{width:"100%"})},({ownerState:t})=>t.disableElevation&&{boxShadow:"none","&:hover":{boxShadow:"none"},[`&.${J_.focusVisible}`]:{boxShadow:"none"},"&:active":{boxShadow:"none"},[`&.${J_.disabled}`]:{boxShadow:"none"}}),xre=lt("span",{name:"MuiButton",slot:"StartIcon",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.startIcon,e[`iconSize${gt(n.size)}`]]}})(({ownerState:t})=>X({display:"inherit",marginRight:8,marginLeft:-4},t.size==="small"&&{marginLeft:-2},L7(t))),_re=lt("span",{name:"MuiButton",slot:"EndIcon",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.endIcon,e[`iconSize${gt(n.size)}`]]}})(({ownerState:t})=>X({display:"inherit",marginRight:-4,marginLeft:8},t.size==="small"&&{marginRight:-2},L7(t))),bre=D.forwardRef(function(e,n){const r=D.useContext(hre),i=D.useContext(mre),s=D3(r,e),o=En({props:s,name:"MuiButton"}),{children:a,color:l="primary",component:c="button",className:f,disabled:p=!1,disableElevation:g=!1,disableFocusRipple:v=!1,endIcon:x,focusVisibleClassName:_,fullWidth:b=!1,size:y="medium",startIcon:S,type:w,variant:T="text"}=o,L=Rt(o,gre),R=X({},o,{color:l,component:c,disabled:p,disableElevation:g,disableFocusRipple:v,fullWidth:b,size:y,type:w,variant:T}),P=vre(R),F=S&&C.jsx(xre,{className:P.startIcon,ownerState:R,children:S}),O=x&&C.jsx(_re,{className:P.endIcon,ownerState:R,children:x}),I=i||"";return C.jsxs(yre,X({ownerState:R,className:At(r.className,P.root,f,I),component:c,disabled:p,focusRipple:!v,focusVisibleClassName:At(P.focusVisible,_),ref:n,type:w},L,{classes:P,children:[F,a,O]}))}),dp=bre;function Sre(t){return bn("PrivateSwitchBase",t)}pn("PrivateSwitchBase",["root","checked","disabled","input","edgeStart","edgeEnd"]);const wre=["autoFocus","checked","checkedIcon","className","defaultChecked","disabled","disableFocusRipple","edge","icon","id","inputProps","inputRef","name","onBlur","onChange","onFocus","readOnly","required","tabIndex","type","value"],Mre=t=>{const{classes:e,checked:n,disabled:r,edge:i}=t,s={root:["root",n&&"checked",r&&"disabled",i&&`edge${gt(i)}`],input:["input"]};return Sn(s,Sre,e)},Ere=lt(Nu)(({ownerState:t})=>X({padding:9,borderRadius:"50%"},t.edge==="start"&&{marginLeft:t.size==="small"?-3:-12},t.edge==="end"&&{marginRight:t.size==="small"?-3:-12})),Cre=lt("input",{shouldForwardProp:La})({cursor:"inherit",position:"absolute",opacity:0,width:"100%",height:"100%",top:0,left:0,margin:0,padding:0,zIndex:1}),Tre=D.forwardRef(function(e,n){const{autoFocus:r,checked:i,checkedIcon:s,className:o,defaultChecked:a,disabled:l,disableFocusRipple:c=!1,edge:f=!1,icon:p,id:g,inputProps:v,inputRef:x,name:_,onBlur:b,onChange:y,onFocus:S,readOnly:w,required:T=!1,tabIndex:L,type:R,value:P}=e,F=Rt(e,wre),[O,I]=Cu({controlled:i,default:!!a,name:"SwitchBase",state:"checked"}),H=_p(),Q=te=>{S&&S(te),H&&H.onFocus&&H.onFocus(te)},q=te=>{b&&b(te),H&&H.onBlur&&H.onBlur(te)},le=te=>{if(te.nativeEvent.defaultPrevented)return;const oe=te.target.checked;I(oe),y&&y(te,oe)};let ie=l;H&&typeof ie>"u"&&(ie=H.disabled);const ee=R==="checkbox"||R==="radio",ue=X({},e,{checked:O,disabled:ie,disableFocusRipple:c,edge:f}),z=Mre(ue);return C.jsxs(Ere,X({component:"span",className:At(z.root,o),centerRipple:!0,focusRipple:!c,disabled:ie,tabIndex:null,role:void 0,onFocus:Q,onBlur:q,ownerState:ue,ref:n},F,{children:[C.jsx(Cre,X({autoFocus:r,checked:i,defaultChecked:a,className:z.input,disabled:ie,id:ee?g:void 0,name:_,onChange:le,readOnly:w,ref:x,required:T,ownerState:ue,tabIndex:L,type:R},R==="checkbox"&&P===void 0?{}:{value:P},v)),O?s:p]}))}),Are=Tre;function Rre(t){return bn("MuiCircularProgress",t)}pn("MuiCircularProgress",["root","determinate","indeterminate","colorPrimary","colorSecondary","svg","circle","circleDeterminate","circleIndeterminate","circleDisableShrink"]);const Pre=["className","color","disableShrink","size","style","thickness","value","variant"];let Gw=t=>t,ak,lk,ck,uk;const Sd=44,Ire=dg(ak||(ak=Gw`
+ 0% {
+ transform: rotate(0deg);
+ }
+
+ 100% {
+ transform: rotate(360deg);
+ }
+`)),Lre=dg(lk||(lk=Gw`
+ 0% {
+ stroke-dasharray: 1px, 200px;
+ stroke-dashoffset: 0;
+ }
+
+ 50% {
+ stroke-dasharray: 100px, 200px;
+ stroke-dashoffset: -15px;
+ }
+
+ 100% {
+ stroke-dasharray: 100px, 200px;
+ stroke-dashoffset: -125px;
+ }
+`)),kre=t=>{const{classes:e,variant:n,color:r,disableShrink:i}=t,s={root:["root",n,`color${gt(r)}`],svg:["svg"],circle:["circle",`circle${gt(n)}`,i&&"circleDisableShrink"]};return Sn(s,Rre,e)},Ore=lt("span",{name:"MuiCircularProgress",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,e[n.variant],e[`color${gt(n.color)}`]]}})(({ownerState:t,theme:e})=>X({display:"inline-block"},t.variant==="determinate"&&{transition:e.transitions.create("transform")},t.color!=="inherit"&&{color:(e.vars||e).palette[t.color].main}),({ownerState:t})=>t.variant==="indeterminate"&&hw(ck||(ck=Gw`
+ animation: ${0} 1.4s linear infinite;
+ `),Ire)),Nre=lt("svg",{name:"MuiCircularProgress",slot:"Svg",overridesResolver:(t,e)=>e.svg})({display:"block"}),Dre=lt("circle",{name:"MuiCircularProgress",slot:"Circle",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.circle,e[`circle${gt(n.variant)}`],n.disableShrink&&e.circleDisableShrink]}})(({ownerState:t,theme:e})=>X({stroke:"currentColor"},t.variant==="determinate"&&{transition:e.transitions.create("stroke-dashoffset")},t.variant==="indeterminate"&&{strokeDasharray:"80px, 200px",strokeDashoffset:0}),({ownerState:t})=>t.variant==="indeterminate"&&!t.disableShrink&&hw(uk||(uk=Gw`
+ animation: ${0} 1.4s ease-in-out infinite;
+ `),Lre)),Fre=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiCircularProgress"}),{className:i,color:s="primary",disableShrink:o=!1,size:a=40,style:l,thickness:c=3.6,value:f=0,variant:p="indeterminate"}=r,g=Rt(r,Pre),v=X({},r,{color:s,disableShrink:o,size:a,thickness:c,value:f,variant:p}),x=kre(v),_={},b={},y={};if(p==="determinate"){const S=2*Math.PI*((Sd-c)/2);_.strokeDasharray=S.toFixed(3),y["aria-valuenow"]=Math.round(f),_.strokeDashoffset=`${((100-f)/100*S).toFixed(3)}px`,b.transform="rotate(-90deg)"}return C.jsx(Ore,X({className:At(x.root,i),style:X({width:a,height:a},b,l),ownerState:v,ref:n,role:"progressbar"},y,g,{children:C.jsx(Nre,{className:x.svg,ownerState:v,viewBox:`${Sd/2} ${Sd/2} ${Sd} ${Sd}`,children:C.jsx(Dre,{className:x.circle,style:_,ownerState:v,cx:Sd,cy:Sd,r:(Sd-c)/2,fill:"none",strokeWidth:c})})}))}),ka=Fre;function Ure(t){return bn("MuiModal",t)}pn("MuiModal",["root","hidden","backdrop"]);const zre=["BackdropComponent","BackdropProps","classes","className","closeAfterTransition","children","container","component","components","componentsProps","disableAutoFocus","disableEnforceFocus","disableEscapeKeyDown","disablePortal","disableRestoreFocus","disableScrollLock","hideBackdrop","keepMounted","onBackdropClick","onClose","onTransitionEnter","onTransitionExited","open","slotProps","slots","theme"],Bre=t=>{const{open:e,exited:n,classes:r}=t;return Sn({root:["root",!e&&n&&"hidden"],backdrop:["backdrop"]},Ure,r)},Hre=lt("div",{name:"MuiModal",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,!n.open&&n.exited&&e.hidden]}})(({theme:t,ownerState:e})=>X({position:"fixed",zIndex:(t.vars||t).zIndex.modal,right:0,bottom:0,top:0,left:0},!e.open&&e.exited&&{visibility:"hidden"})),$re=lt(Uc,{name:"MuiModal",slot:"Backdrop",overridesResolver:(t,e)=>e.backdrop})({zIndex:-1}),Vre=D.forwardRef(function(e,n){var r,i,s,o,a,l;const c=En({name:"MuiModal",props:e}),{BackdropComponent:f=$re,BackdropProps:p,className:g,closeAfterTransition:v=!1,children:x,container:_,component:b,components:y={},componentsProps:S={},disableAutoFocus:w=!1,disableEnforceFocus:T=!1,disableEscapeKeyDown:L=!1,disablePortal:R=!1,disableRestoreFocus:P=!1,disableScrollLock:F=!1,hideBackdrop:O=!1,keepMounted:I=!1,onBackdropClick:H,open:Q,slotProps:q,slots:le}=c,ie=Rt(c,zre),ee=X({},c,{closeAfterTransition:v,disableAutoFocus:w,disableEnforceFocus:T,disableEscapeKeyDown:L,disablePortal:R,disableRestoreFocus:P,disableScrollLock:F,hideBackdrop:O,keepMounted:I}),{getRootProps:ue,getBackdropProps:z,getTransitionProps:te,portalRef:oe,isTopModal:de,exited:Ce,hasTransition:Le}=bee(X({},ee,{rootRef:n})),V=X({},ee,{exited:Ce}),me=Bre(V),pe={};if(x.props.tabIndex===void 0&&(pe.tabIndex="-1"),Le){const{onEnter:Oe,onExited:Te}=te();pe.onEnter=Oe,pe.onExited=Te}const Se=(r=(i=le==null?void 0:le.root)!=null?i:y.Root)!=null?r:Hre,je=(s=(o=le==null?void 0:le.backdrop)!=null?o:y.Backdrop)!=null?s:f,it=(a=q==null?void 0:q.root)!=null?a:S.root,xe=(l=q==null?void 0:q.backdrop)!=null?l:S.backdrop,et=Qi({elementType:Se,externalSlotProps:it,externalForwardedProps:ie,getSlotProps:ue,additionalProps:{ref:n,as:b},ownerState:V,className:At(g,it==null?void 0:it.className,me==null?void 0:me.root,!V.open&&V.exited&&(me==null?void 0:me.hidden))}),Re=Qi({elementType:je,externalSlotProps:xe,additionalProps:p,getSlotProps:Oe=>z(X({},Oe,{onClick:Te=>{H&&H(Te),Oe!=null&&Oe.onClick&&Oe.onClick(Te)}})),className:At(xe==null?void 0:xe.className,p==null?void 0:p.className,me==null?void 0:me.backdrop),ownerState:V});return!I&&!Q&&(!Le||Ce)?null:C.jsx(m7,{ref:oe,container:_,disablePortal:R,children:C.jsxs(Se,X({},et,{children:[!O&&f?C.jsx(je,X({},Re)):null,C.jsx(dee,{disableEnforceFocus:T,disableAutoFocus:w,disableRestoreFocus:P,isEnabled:de,open:Q,children:D.cloneElement(x,pe)})]}))})}),k7=Vre;function Wre(t){return bn("MuiDialog",t)}const jre=pn("MuiDialog",["root","scrollPaper","scrollBody","container","paper","paperScrollPaper","paperScrollBody","paperWidthFalse","paperWidthXs","paperWidthSm","paperWidthMd","paperWidthLg","paperWidthXl","paperFullWidth","paperFullScreen"]),GE=jre,Gre=D.createContext({}),O7=Gre,Xre=["aria-describedby","aria-labelledby","BackdropComponent","BackdropProps","children","className","disableEscapeKeyDown","fullScreen","fullWidth","maxWidth","onBackdropClick","onClose","open","PaperComponent","PaperProps","scroll","TransitionComponent","transitionDuration","TransitionProps"],qre=lt(Uc,{name:"MuiDialog",slot:"Backdrop",overrides:(t,e)=>e.backdrop})({zIndex:-1}),Zre=t=>{const{classes:e,scroll:n,maxWidth:r,fullWidth:i,fullScreen:s}=t,o={root:["root"],container:["container",`scroll${gt(n)}`],paper:["paper",`paperScroll${gt(n)}`,`paperWidth${gt(String(r))}`,i&&"paperFullWidth",s&&"paperFullScreen"]};return Sn(o,Wre,e)},Yre=lt(k7,{name:"MuiDialog",slot:"Root",overridesResolver:(t,e)=>e.root})({"@media print":{position:"absolute !important"}}),Kre=lt("div",{name:"MuiDialog",slot:"Container",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.container,e[`scroll${gt(n.scroll)}`]]}})(({ownerState:t})=>X({height:"100%","@media print":{height:"auto"},outline:0},t.scroll==="paper"&&{display:"flex",justifyContent:"center",alignItems:"center"},t.scroll==="body"&&{overflowY:"auto",overflowX:"hidden",textAlign:"center","&::after":{content:'""',display:"inline-block",verticalAlign:"middle",height:"100%",width:"0"}})),Qre=lt(nx,{name:"MuiDialog",slot:"Paper",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.paper,e[`scrollPaper${gt(n.scroll)}`],e[`paperWidth${gt(String(n.maxWidth))}`],n.fullWidth&&e.paperFullWidth,n.fullScreen&&e.paperFullScreen]}})(({theme:t,ownerState:e})=>X({margin:32,position:"relative",overflowY:"auto","@media print":{overflowY:"visible",boxShadow:"none"}},e.scroll==="paper"&&{display:"flex",flexDirection:"column",maxHeight:"calc(100% - 64px)"},e.scroll==="body"&&{display:"inline-block",verticalAlign:"middle",textAlign:"left"},!e.maxWidth&&{maxWidth:"calc(100% - 64px)"},e.maxWidth==="xs"&&{maxWidth:t.breakpoints.unit==="px"?Math.max(t.breakpoints.values.xs,444):`max(${t.breakpoints.values.xs}${t.breakpoints.unit}, 444px)`,[`&.${GE.paperScrollBody}`]:{[t.breakpoints.down(Math.max(t.breakpoints.values.xs,444)+32*2)]:{maxWidth:"calc(100% - 64px)"}}},e.maxWidth&&e.maxWidth!=="xs"&&{maxWidth:`${t.breakpoints.values[e.maxWidth]}${t.breakpoints.unit}`,[`&.${GE.paperScrollBody}`]:{[t.breakpoints.down(t.breakpoints.values[e.maxWidth]+32*2)]:{maxWidth:"calc(100% - 64px)"}}},e.fullWidth&&{width:"calc(100% - 64px)"},e.fullScreen&&{margin:0,width:"100%",maxWidth:"100%",height:"100%",maxHeight:"none",borderRadius:0,[`&.${GE.paperScrollBody}`]:{margin:0,maxWidth:"100%"}})),Jre=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiDialog"}),i=Bu(),s={enter:i.transitions.duration.enteringScreen,exit:i.transitions.duration.leavingScreen},{"aria-describedby":o,"aria-labelledby":a,BackdropComponent:l,BackdropProps:c,children:f,className:p,disableEscapeKeyDown:g=!1,fullScreen:v=!1,fullWidth:x=!1,maxWidth:_="sm",onBackdropClick:b,onClose:y,open:S,PaperComponent:w=nx,PaperProps:T={},scroll:L="paper",TransitionComponent:R=I7,transitionDuration:P=s,TransitionProps:F}=r,O=Rt(r,Xre),I=X({},r,{disableEscapeKeyDown:g,fullScreen:v,fullWidth:x,maxWidth:_,scroll:L}),H=Zre(I),Q=D.useRef(),q=ue=>{Q.current=ue.target===ue.currentTarget},le=ue=>{Q.current&&(Q.current=null,b&&b(ue),y&&y(ue,"backdropClick"))},ie=hg(a),ee=D.useMemo(()=>({titleId:ie}),[ie]);return C.jsx(Yre,X({className:At(H.root,p),closeAfterTransition:!0,components:{Backdrop:qre},componentsProps:{backdrop:X({transitionDuration:P,as:l},c)},disableEscapeKeyDown:g,onClose:y,open:S,ref:n,onClick:le,ownerState:I},O,{children:C.jsx(R,X({appear:!0,in:S,timeout:P,role:"presentation"},F,{children:C.jsx(Kre,{className:At(H.container),onMouseDown:q,ownerState:I,children:C.jsx(Qre,X({as:w,elevation:24,role:"dialog","aria-describedby":o,"aria-labelledby":ie},T,{className:At(H.paper,T.className),ownerState:I,children:C.jsx(O7.Provider,{value:ee,children:f})}))})}))}))}),wR=Jre;function eie(t){return bn("MuiDialogActions",t)}pn("MuiDialogActions",["root","spacing"]);const tie=["className","disableSpacing"],nie=t=>{const{classes:e,disableSpacing:n}=t;return Sn({root:["root",!n&&"spacing"]},eie,e)},rie=lt("div",{name:"MuiDialogActions",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,!n.disableSpacing&&e.spacing]}})(({ownerState:t})=>X({display:"flex",alignItems:"center",padding:8,justifyContent:"flex-end",flex:"0 0 auto"},!t.disableSpacing&&{"& > :not(style) ~ :not(style)":{marginLeft:8}})),iie=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiDialogActions"}),{className:i,disableSpacing:s=!1}=r,o=Rt(r,tie),a=X({},r,{disableSpacing:s}),l=nie(a);return C.jsx(rie,X({className:At(l.root,i),ownerState:a,ref:n},o))}),MR=iie;function sie(t){return bn("MuiDialogContent",t)}pn("MuiDialogContent",["root","dividers"]);function oie(t){return bn("MuiDialogTitle",t)}const aie=pn("MuiDialogTitle",["root"]),lie=aie,cie=["className","dividers"],uie=t=>{const{classes:e,dividers:n}=t;return Sn({root:["root",n&&"dividers"]},sie,e)},die=lt("div",{name:"MuiDialogContent",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.dividers&&e.dividers]}})(({theme:t,ownerState:e})=>X({flex:"1 1 auto",WebkitOverflowScrolling:"touch",overflowY:"auto",padding:"20px 24px"},e.dividers?{padding:"16px 24px",borderTop:`1px solid ${(t.vars||t).palette.divider}`,borderBottom:`1px solid ${(t.vars||t).palette.divider}`}:{[`.${lie.root} + &`]:{paddingTop:0}})),fie=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiDialogContent"}),{className:i,dividers:s=!1}=r,o=Rt(r,cie),a=X({},r,{dividers:s}),l=uie(a);return C.jsx(die,X({className:At(l.root,i),ownerState:a,ref:n},o))}),ER=fie,hie=["className","id"],pie=t=>{const{classes:e}=t;return Sn({root:["root"]},oie,e)},mie=lt(mr,{name:"MuiDialogTitle",slot:"Root",overridesResolver:(t,e)=>e.root})({padding:"16px 24px",flex:"0 0 auto"}),gie=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiDialogTitle"}),{className:i,id:s}=r,o=Rt(r,hie),a=r,l=pie(a),{titleId:c=s}=D.useContext(O7);return C.jsx(mie,X({component:"h2",className:At(l.root,i),ownerState:a,ref:n,variant:"h6",id:s??c},o))}),CR=gie,vie=pn("MuiDivider",["root","absolute","fullWidth","inset","middle","flexItem","light","vertical","withChildren","withChildrenVertical","textAlignRight","textAlignLeft","wrapper","wrapperVertical"]),dk=vie,yie=["disableUnderline","components","componentsProps","fullWidth","hiddenLabel","inputComponent","multiline","slotProps","slots","type"],xie=t=>{const{classes:e,disableUnderline:n}=t,i=Sn({root:["root",!n&&"underline"],input:["input"]},Lne,e);return X({},e,i)},_ie=lt(Ww,{shouldForwardProp:t=>La(t)||t==="classes",name:"MuiFilledInput",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[...$w(t,e),!n.disableUnderline&&e.underline]}})(({theme:t,ownerState:e})=>{var n;const r=t.palette.mode==="light",i=r?"rgba(0, 0, 0, 0.42)":"rgba(255, 255, 255, 0.7)",s=r?"rgba(0, 0, 0, 0.06)":"rgba(255, 255, 255, 0.09)",o=r?"rgba(0, 0, 0, 0.09)":"rgba(255, 255, 255, 0.13)",a=r?"rgba(0, 0, 0, 0.12)":"rgba(255, 255, 255, 0.12)";return X({position:"relative",backgroundColor:t.vars?t.vars.palette.FilledInput.bg:s,borderTopLeftRadius:(t.vars||t).shape.borderRadius,borderTopRightRadius:(t.vars||t).shape.borderRadius,transition:t.transitions.create("background-color",{duration:t.transitions.duration.shorter,easing:t.transitions.easing.easeOut}),"&:hover":{backgroundColor:t.vars?t.vars.palette.FilledInput.hoverBg:o,"@media (hover: none)":{backgroundColor:t.vars?t.vars.palette.FilledInput.bg:s}},[`&.${ga.focused}`]:{backgroundColor:t.vars?t.vars.palette.FilledInput.bg:s},[`&.${ga.disabled}`]:{backgroundColor:t.vars?t.vars.palette.FilledInput.disabledBg:a}},!e.disableUnderline&&{"&::after":{borderBottom:`2px solid ${(n=(t.vars||t).palette[e.color||"primary"])==null?void 0:n.main}`,left:0,bottom:0,content:'""',position:"absolute",right:0,transform:"scaleX(0)",transition:t.transitions.create("transform",{duration:t.transitions.duration.shorter,easing:t.transitions.easing.easeOut}),pointerEvents:"none"},[`&.${ga.focused}:after`]:{transform:"scaleX(1) translateX(0)"},[`&.${ga.error}`]:{"&::before, &::after":{borderBottomColor:(t.vars||t).palette.error.main}},"&::before":{borderBottom:`1px solid ${t.vars?`rgba(${t.vars.palette.common.onBackgroundChannel} / ${t.vars.opacity.inputUnderline})`:i}`,left:0,bottom:0,content:'"\\00a0"',position:"absolute",right:0,transition:t.transitions.create("border-bottom-color",{duration:t.transitions.duration.shorter}),pointerEvents:"none"},[`&:hover:not(.${ga.disabled}, .${ga.error}):before`]:{borderBottom:`1px solid ${(t.vars||t).palette.text.primary}`},[`&.${ga.disabled}:before`]:{borderBottomStyle:"dotted"}},e.startAdornment&&{paddingLeft:12},e.endAdornment&&{paddingRight:12},e.multiline&&X({padding:"25px 12px 8px"},e.size==="small"&&{paddingTop:21,paddingBottom:4},e.hiddenLabel&&{paddingTop:16,paddingBottom:17},e.hiddenLabel&&e.size==="small"&&{paddingTop:8,paddingBottom:9}))}),bie=lt(jw,{name:"MuiFilledInput",slot:"Input",overridesResolver:Vw})(({theme:t,ownerState:e})=>X({paddingTop:25,paddingRight:12,paddingBottom:8,paddingLeft:12},!t.vars&&{"&:-webkit-autofill":{WebkitBoxShadow:t.palette.mode==="light"?null:"0 0 0 100px #266798 inset",WebkitTextFillColor:t.palette.mode==="light"?null:"#fff",caretColor:t.palette.mode==="light"?null:"#fff",borderTopLeftRadius:"inherit",borderTopRightRadius:"inherit"}},t.vars&&{"&:-webkit-autofill":{borderTopLeftRadius:"inherit",borderTopRightRadius:"inherit"},[t.getColorSchemeSelector("dark")]:{"&:-webkit-autofill":{WebkitBoxShadow:"0 0 0 100px #266798 inset",WebkitTextFillColor:"#fff",caretColor:"#fff"}}},e.size==="small"&&{paddingTop:21,paddingBottom:4},e.hiddenLabel&&{paddingTop:16,paddingBottom:17},e.startAdornment&&{paddingLeft:0},e.endAdornment&&{paddingRight:0},e.hiddenLabel&&e.size==="small"&&{paddingTop:8,paddingBottom:9},e.multiline&&{paddingTop:0,paddingBottom:0,paddingLeft:0,paddingRight:0})),N7=D.forwardRef(function(e,n){var r,i,s,o;const a=En({props:e,name:"MuiFilledInput"}),{components:l={},componentsProps:c,fullWidth:f=!1,inputComponent:p="input",multiline:g=!1,slotProps:v,slots:x={},type:_="text"}=a,b=Rt(a,yie),y=X({},a,{fullWidth:f,inputComponent:p,multiline:g,type:_}),S=xie(a),w={root:{ownerState:y},input:{ownerState:y}},T=v??c?vo(w,v??c):w,L=(r=(i=x.root)!=null?i:l.Root)!=null?r:_ie,R=(s=(o=x.input)!=null?o:l.Input)!=null?s:bie;return C.jsx(SR,X({slots:{root:L,input:R},componentsProps:T,fullWidth:f,inputComponent:p,multiline:g,ref:n,type:_},b,{classes:S}))});N7.muiName="Input";const D7=N7;function Sie(t){return bn("MuiFormControl",t)}pn("MuiFormControl",["root","marginNone","marginNormal","marginDense","fullWidth","disabled"]);const wie=["children","className","color","component","disabled","error","focused","fullWidth","hiddenLabel","margin","required","size","variant"],Mie=t=>{const{classes:e,margin:n,fullWidth:r}=t,i={root:["root",n!=="none"&&`margin${gt(n)}`,r&&"fullWidth"]};return Sn(i,Sie,e)},Eie=lt("div",{name:"MuiFormControl",slot:"Root",overridesResolver:({ownerState:t},e)=>X({},e.root,e[`margin${gt(t.margin)}`],t.fullWidth&&e.fullWidth)})(({ownerState:t})=>X({display:"inline-flex",flexDirection:"column",position:"relative",minWidth:0,padding:0,margin:0,border:0,verticalAlign:"top"},t.margin==="normal"&&{marginTop:16,marginBottom:8},t.margin==="dense"&&{marginTop:8,marginBottom:4},t.fullWidth&&{width:"100%"})),Cie=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiFormControl"}),{children:i,className:s,color:o="primary",component:a="div",disabled:l=!1,error:c=!1,focused:f,fullWidth:p=!1,hiddenLabel:g=!1,margin:v="none",required:x=!1,size:_="medium",variant:b="outlined"}=r,y=Rt(r,wie),S=X({},r,{color:o,component:a,disabled:l,error:c,fullWidth:p,hiddenLabel:g,margin:v,required:x,size:_,variant:b}),w=Mie(S),[T,L]=D.useState(()=>{let q=!1;return i&&D.Children.forEach(i,le=>{if(!mv(le,["Input","Select"]))return;const ie=mv(le,["Select"])?le.props.input:le;ie&&bne(ie.props)&&(q=!0)}),q}),[R,P]=D.useState(()=>{let q=!1;return i&&D.Children.forEach(i,le=>{mv(le,["Input","Select"])&&(m2(le.props,!0)||m2(le.props.inputProps,!0))&&(q=!0)}),q}),[F,O]=D.useState(!1);l&&F&&O(!1);const I=f!==void 0&&!l?f:F;let H;const Q=D.useMemo(()=>({adornedStart:T,setAdornedStart:L,color:o,disabled:l,error:c,filled:R,focused:I,fullWidth:p,hiddenLabel:g,size:_,onBlur:()=>{O(!1)},onEmpty:()=>{P(!1)},onFilled:()=>{P(!0)},onFocus:()=>{O(!0)},registerEffect:H,required:x,variant:b}),[T,o,l,c,R,I,p,g,H,x,_,b]);return C.jsx(bR.Provider,{value:Q,children:C.jsx(Eie,X({as:a,ownerState:S,className:At(w.root,s),ref:n},y,{children:i}))})}),Xw=Cie,Tie=DK({createStyledComponent:lt("div",{name:"MuiStack",slot:"Root",overridesResolver:(t,e)=>e.root}),useThemeProps:t=>En({props:t,name:"MuiStack"})}),bp=Tie;function Aie(t){return bn("MuiFormHelperText",t)}const Rie=pn("MuiFormHelperText",["root","error","disabled","sizeSmall","sizeMedium","contained","focused","filled","required"]),fk=Rie;var hk;const Pie=["children","className","component","disabled","error","filled","focused","margin","required","variant"],Iie=t=>{const{classes:e,contained:n,size:r,disabled:i,error:s,filled:o,focused:a,required:l}=t,c={root:["root",i&&"disabled",s&&"error",r&&`size${gt(r)}`,n&&"contained",a&&"focused",o&&"filled",l&&"required"]};return Sn(c,Aie,e)},Lie=lt("p",{name:"MuiFormHelperText",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.size&&e[`size${gt(n.size)}`],n.contained&&e.contained,n.filled&&e.filled]}})(({theme:t,ownerState:e})=>X({color:(t.vars||t).palette.text.secondary},t.typography.caption,{textAlign:"left",marginTop:3,marginRight:0,marginBottom:0,marginLeft:0,[`&.${fk.disabled}`]:{color:(t.vars||t).palette.text.disabled},[`&.${fk.error}`]:{color:(t.vars||t).palette.error.main}},e.size==="small"&&{marginTop:4},e.contained&&{marginLeft:14,marginRight:14})),kie=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiFormHelperText"}),{children:i,className:s,component:o="p"}=r,a=Rt(r,Pie),l=_p(),c=vg({props:r,muiFormControl:l,states:["variant","size","disabled","error","filled","focused","required"]}),f=X({},r,{component:o,contained:c.variant==="filled"||c.variant==="outlined",variant:c.variant,size:c.size,disabled:c.disabled,error:c.error,filled:c.filled,focused:c.focused,required:c.required}),p=Iie(f);return C.jsx(Lie,X({as:o,ownerState:f,className:At(p.root,s),ref:n},a,{children:i===" "?hk||(hk=C.jsx("span",{className:"notranslate",children:""})):i}))}),Oie=kie;function Nie(t){return bn("MuiFormLabel",t)}const Die=pn("MuiFormLabel",["root","colorSecondary","focused","disabled","error","filled","required","asterisk"]),_v=Die,Fie=["children","className","color","component","disabled","error","filled","focused","required"],Uie=t=>{const{classes:e,color:n,focused:r,disabled:i,error:s,filled:o,required:a}=t,l={root:["root",`color${gt(n)}`,i&&"disabled",s&&"error",o&&"filled",r&&"focused",a&&"required"],asterisk:["asterisk",s&&"error"]};return Sn(l,Nie,e)},zie=lt("label",{name:"MuiFormLabel",slot:"Root",overridesResolver:({ownerState:t},e)=>X({},e.root,t.color==="secondary"&&e.colorSecondary,t.filled&&e.filled)})(({theme:t,ownerState:e})=>X({color:(t.vars||t).palette.text.secondary},t.typography.body1,{lineHeight:"1.4375em",padding:0,position:"relative",[`&.${_v.focused}`]:{color:(t.vars||t).palette[e.color].main},[`&.${_v.disabled}`]:{color:(t.vars||t).palette.text.disabled},[`&.${_v.error}`]:{color:(t.vars||t).palette.error.main}})),Bie=lt("span",{name:"MuiFormLabel",slot:"Asterisk",overridesResolver:(t,e)=>e.asterisk})(({theme:t})=>({[`&.${_v.error}`]:{color:(t.vars||t).palette.error.main}})),Hie=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiFormLabel"}),{children:i,className:s,component:o="label"}=r,a=Rt(r,Fie),l=_p(),c=vg({props:r,muiFormControl:l,states:["color","required","focused","disabled","error","filled"]}),f=X({},r,{color:c.color||"primary",component:o,disabled:c.disabled,error:c.error,filled:c.filled,focused:c.focused,required:c.required}),p=Uie(f);return C.jsxs(zie,X({as:o,ownerState:f,className:At(p.root,s),ref:n},a,{children:[i,c.required&&C.jsxs(Bie,{ownerState:f,"aria-hidden":!0,className:p.asterisk,children:[" ","*"]})]}))}),$ie=Hie,Vie=D.createContext(),pk=Vie;function Wie(t){return bn("MuiGrid",t)}const jie=[0,1,2,3,4,5,6,7,8,9,10],Gie=["column-reverse","column","row-reverse","row"],Xie=["nowrap","wrap-reverse","wrap"],E1=["auto",!0,1,2,3,4,5,6,7,8,9,10,11,12],ey=pn("MuiGrid",["root","container","item","zeroMinWidth",...jie.map(t=>`spacing-xs-${t}`),...Gie.map(t=>`direction-xs-${t}`),...Xie.map(t=>`wrap-xs-${t}`),...E1.map(t=>`grid-xs-${t}`),...E1.map(t=>`grid-sm-${t}`),...E1.map(t=>`grid-md-${t}`),...E1.map(t=>`grid-lg-${t}`),...E1.map(t=>`grid-xl-${t}`)]),qie=["className","columns","columnSpacing","component","container","direction","item","rowSpacing","spacing","wrap","zeroMinWidth"];function _0(t){const e=parseFloat(t);return`${e}${String(t).replace(String(e),"")||"px"}`}function Zie({theme:t,ownerState:e}){let n;return t.breakpoints.keys.reduce((r,i)=>{let s={};if(e[i]&&(n=e[i]),!n)return r;if(n===!0)s={flexBasis:0,flexGrow:1,maxWidth:"100%"};else if(n==="auto")s={flexBasis:"auto",flexGrow:0,flexShrink:0,maxWidth:"none",width:"auto"};else{const o=Xh({values:e.columns,breakpoints:t.breakpoints.values}),a=typeof o=="object"?o[i]:o;if(a==null)return r;const l=`${Math.round(n/a*1e8)/1e6}%`;let c={};if(e.container&&e.item&&e.columnSpacing!==0){const f=t.spacing(e.columnSpacing);if(f!=="0px"){const p=`calc(${l} + ${_0(f)})`;c={flexBasis:p,maxWidth:p}}}s=X({flexBasis:l,flexGrow:0,maxWidth:l},c)}return t.breakpoints.values[i]===0?Object.assign(r,s):r[t.breakpoints.up(i)]=s,r},{})}function Yie({theme:t,ownerState:e}){const n=Xh({values:e.direction,breakpoints:t.breakpoints.values});return jo({theme:t},n,r=>{const i={flexDirection:r};return r.indexOf("column")===0&&(i[`& > .${ey.item}`]={maxWidth:"none"}),i})}function F7({breakpoints:t,values:e}){let n="";Object.keys(e).forEach(i=>{n===""&&e[i]!==0&&(n=i)});const r=Object.keys(t).sort((i,s)=>t[i]-t[s]);return r.slice(0,r.indexOf(n))}function Kie({theme:t,ownerState:e}){const{container:n,rowSpacing:r}=e;let i={};if(n&&r!==0){const s=Xh({values:r,breakpoints:t.breakpoints.values});let o;typeof s=="object"&&(o=F7({breakpoints:t.breakpoints.values,values:s})),i=jo({theme:t},s,(a,l)=>{var c;const f=t.spacing(a);return f!=="0px"?{marginTop:`-${_0(f)}`,[`& > .${ey.item}`]:{paddingTop:_0(f)}}:(c=o)!=null&&c.includes(l)?{}:{marginTop:0,[`& > .${ey.item}`]:{paddingTop:0}}})}return i}function Qie({theme:t,ownerState:e}){const{container:n,columnSpacing:r}=e;let i={};if(n&&r!==0){const s=Xh({values:r,breakpoints:t.breakpoints.values});let o;typeof s=="object"&&(o=F7({breakpoints:t.breakpoints.values,values:s})),i=jo({theme:t},s,(a,l)=>{var c;const f=t.spacing(a);return f!=="0px"?{width:`calc(100% + ${_0(f)})`,marginLeft:`-${_0(f)}`,[`& > .${ey.item}`]:{paddingLeft:_0(f)}}:(c=o)!=null&&c.includes(l)?{}:{width:"100%",marginLeft:0,[`& > .${ey.item}`]:{paddingLeft:0}}})}return i}function Jie(t,e,n={}){if(!t||t<=0)return[];if(typeof t=="string"&&!Number.isNaN(Number(t))||typeof t=="number")return[n[`spacing-xs-${String(t)}`]];const r=[];return e.forEach(i=>{const s=t[i];Number(s)>0&&r.push(n[`spacing-${i}-${String(s)}`])}),r}const ese=lt("div",{name:"MuiGrid",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t,{container:r,direction:i,item:s,spacing:o,wrap:a,zeroMinWidth:l,breakpoints:c}=n;let f=[];r&&(f=Jie(o,c,e));const p=[];return c.forEach(g=>{const v=n[g];v&&p.push(e[`grid-${g}-${String(v)}`])}),[e.root,r&&e.container,s&&e.item,l&&e.zeroMinWidth,...f,i!=="row"&&e[`direction-xs-${String(i)}`],a!=="wrap"&&e[`wrap-xs-${String(a)}`],...p]}})(({ownerState:t})=>X({boxSizing:"border-box"},t.container&&{display:"flex",flexWrap:"wrap",width:"100%"},t.item&&{margin:0},t.zeroMinWidth&&{minWidth:0},t.wrap!=="wrap"&&{flexWrap:t.wrap}),Yie,Kie,Qie,Zie);function tse(t,e){if(!t||t<=0)return[];if(typeof t=="string"&&!Number.isNaN(Number(t))||typeof t=="number")return[`spacing-xs-${String(t)}`];const n=[];return e.forEach(r=>{const i=t[r];if(Number(i)>0){const s=`spacing-${r}-${String(i)}`;n.push(s)}}),n}const nse=t=>{const{classes:e,container:n,direction:r,item:i,spacing:s,wrap:o,zeroMinWidth:a,breakpoints:l}=t;let c=[];n&&(c=tse(s,l));const f=[];l.forEach(g=>{const v=t[g];v&&f.push(`grid-${g}-${String(v)}`)});const p={root:["root",n&&"container",i&&"item",a&&"zeroMinWidth",...c,r!=="row"&&`direction-xs-${String(r)}`,o!=="wrap"&&`wrap-xs-${String(o)}`,...f]};return Sn(p,Wie,e)},rse=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiGrid"}),{breakpoints:i}=Bu(),s=Ky(r),{className:o,columns:a,columnSpacing:l,component:c="div",container:f=!1,direction:p="row",item:g=!1,rowSpacing:v,spacing:x=0,wrap:_="wrap",zeroMinWidth:b=!1}=s,y=Rt(s,qie),S=v||x,w=l||x,T=D.useContext(pk),L=f?a||12:T,R={},P=X({},y);i.keys.forEach(I=>{y[I]!=null&&(R[I]=y[I],delete P[I])});const F=X({},s,{columns:L,container:f,direction:p,item:g,rowSpacing:S,columnSpacing:w,wrap:_,zeroMinWidth:b,spacing:x},R,{breakpoints:i.keys}),O=nse(F);return C.jsx(pk.Provider,{value:L,children:C.jsx(ese,X({ownerState:F,className:At(O.root,o),as:c,ref:n},P))})}),eb=rse,ise=["addEndListener","appear","children","easing","in","onEnter","onEntered","onEntering","onExit","onExited","onExiting","style","timeout","TransitionComponent"];function OT(t){return`scale(${t}, ${t**2})`}const sse={entering:{opacity:1,transform:OT(1)},entered:{opacity:1,transform:"none"}},XE=typeof navigator<"u"&&/^((?!chrome|android).)*(safari|mobile)/i.test(navigator.userAgent)&&/(os |version\/)15(.|_)4/i.test(navigator.userAgent),U7=D.forwardRef(function(e,n){const{addEndListener:r,appear:i=!0,children:s,easing:o,in:a,onEnter:l,onEntered:c,onEntering:f,onExit:p,onExited:g,onExiting:v,style:x,timeout:_="auto",TransitionComponent:b=uR}=e,y=Rt(e,ise),S=Ah(),w=D.useRef(),T=Bu(),L=D.useRef(null),R=Kr(L,s.ref,n),P=ie=>ee=>{if(ie){const ue=L.current;ee===void 0?ie(ue):ie(ue,ee)}},F=P(f),O=P((ie,ee)=>{u7(ie);const{duration:ue,delay:z,easing:te}=j0({style:x,timeout:_,easing:o},{mode:"enter"});let oe;_==="auto"?(oe=T.transitions.getAutoHeightDuration(ie.clientHeight),w.current=oe):oe=ue,ie.style.transition=[T.transitions.create("opacity",{duration:oe,delay:z}),T.transitions.create("transform",{duration:XE?oe:oe*.666,delay:z,easing:te})].join(","),l&&l(ie,ee)}),I=P(c),H=P(v),Q=P(ie=>{const{duration:ee,delay:ue,easing:z}=j0({style:x,timeout:_,easing:o},{mode:"exit"});let te;_==="auto"?(te=T.transitions.getAutoHeightDuration(ie.clientHeight),w.current=te):te=ee,ie.style.transition=[T.transitions.create("opacity",{duration:te,delay:ue}),T.transitions.create("transform",{duration:XE?te:te*.666,delay:XE?ue:ue||te*.333,easing:z})].join(","),ie.style.opacity=0,ie.style.transform=OT(.75),p&&p(ie)}),q=P(g),le=ie=>{_==="auto"&&S.start(w.current||0,ie),r&&r(L.current,ie)};return C.jsx(b,X({appear:i,in:a,nodeRef:L,onEnter:O,onEntered:I,onEntering:F,onExit:Q,onExited:q,onExiting:H,addEndListener:le,timeout:_==="auto"?null:_},y,{children:(ie,ee)=>D.cloneElement(s,X({style:X({opacity:0,transform:OT(.75),visibility:ie==="exited"&&!a?"hidden":void 0},sse[ie],x,s.props.style),ref:R},ee))}))});U7.muiSupportAuto=!0;const NT=U7,ose=["disableUnderline","components","componentsProps","fullWidth","inputComponent","multiline","slotProps","slots","type"],ase=t=>{const{classes:e,disableUnderline:n}=t,i=Sn({root:["root",!n&&"underline"],input:["input"]},Ane,e);return X({},e,i)},lse=lt(Ww,{shouldForwardProp:t=>La(t)||t==="classes",name:"MuiInput",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[...$w(t,e),!n.disableUnderline&&e.underline]}})(({theme:t,ownerState:e})=>{let r=t.palette.mode==="light"?"rgba(0, 0, 0, 0.42)":"rgba(255, 255, 255, 0.7)";return t.vars&&(r=`rgba(${t.vars.palette.common.onBackgroundChannel} / ${t.vars.opacity.inputUnderline})`),X({position:"relative"},e.formControl&&{"label + &":{marginTop:16}},!e.disableUnderline&&{"&::after":{borderBottom:`2px solid ${(t.vars||t).palette[e.color].main}`,left:0,bottom:0,content:'""',position:"absolute",right:0,transform:"scaleX(0)",transition:t.transitions.create("transform",{duration:t.transitions.duration.shorter,easing:t.transitions.easing.easeOut}),pointerEvents:"none"},[`&.${Fd.focused}:after`]:{transform:"scaleX(1) translateX(0)"},[`&.${Fd.error}`]:{"&::before, &::after":{borderBottomColor:(t.vars||t).palette.error.main}},"&::before":{borderBottom:`1px solid ${r}`,left:0,bottom:0,content:'"\\00a0"',position:"absolute",right:0,transition:t.transitions.create("border-bottom-color",{duration:t.transitions.duration.shorter}),pointerEvents:"none"},[`&:hover:not(.${Fd.disabled}, .${Fd.error}):before`]:{borderBottom:`2px solid ${(t.vars||t).palette.text.primary}`,"@media (hover: none)":{borderBottom:`1px solid ${r}`}},[`&.${Fd.disabled}:before`]:{borderBottomStyle:"dotted"}})}),cse=lt(jw,{name:"MuiInput",slot:"Input",overridesResolver:Vw})({}),z7=D.forwardRef(function(e,n){var r,i,s,o;const a=En({props:e,name:"MuiInput"}),{disableUnderline:l,components:c={},componentsProps:f,fullWidth:p=!1,inputComponent:g="input",multiline:v=!1,slotProps:x,slots:_={},type:b="text"}=a,y=Rt(a,ose),S=ase(a),T={root:{ownerState:{disableUnderline:l}}},L=x??f?vo(x??f,T):T,R=(r=(i=_.root)!=null?i:c.Root)!=null?r:lse,P=(s=(o=_.input)!=null?o:c.Input)!=null?s:cse;return C.jsx(SR,X({slots:{root:R,input:P},slotProps:L,fullWidth:p,inputComponent:g,multiline:v,ref:n,type:b},y,{classes:S}))});z7.muiName="Input";const qw=z7;function use(t){return bn("MuiInputLabel",t)}pn("MuiInputLabel",["root","focused","disabled","error","required","asterisk","formControl","sizeSmall","shrink","animated","standard","filled","outlined"]);const dse=["disableAnimation","margin","shrink","variant","className"],fse=t=>{const{classes:e,formControl:n,size:r,shrink:i,disableAnimation:s,variant:o,required:a}=t,l={root:["root",n&&"formControl",!s&&"animated",i&&"shrink",r&&r!=="normal"&&`size${gt(r)}`,o],asterisk:[a&&"asterisk"]},c=Sn(l,use,e);return X({},e,c)},hse=lt($ie,{shouldForwardProp:t=>La(t)||t==="classes",name:"MuiInputLabel",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[{[`& .${_v.asterisk}`]:e.asterisk},e.root,n.formControl&&e.formControl,n.size==="small"&&e.sizeSmall,n.shrink&&e.shrink,!n.disableAnimation&&e.animated,n.focused&&e.focused,e[n.variant]]}})(({theme:t,ownerState:e})=>X({display:"block",transformOrigin:"top left",whiteSpace:"nowrap",overflow:"hidden",textOverflow:"ellipsis",maxWidth:"100%"},e.formControl&&{position:"absolute",left:0,top:0,transform:"translate(0, 20px) scale(1)"},e.size==="small"&&{transform:"translate(0, 17px) scale(1)"},e.shrink&&{transform:"translate(0, -1.5px) scale(0.75)",transformOrigin:"top left",maxWidth:"133%"},!e.disableAnimation&&{transition:t.transitions.create(["color","transform","max-width"],{duration:t.transitions.duration.shorter,easing:t.transitions.easing.easeOut})},e.variant==="filled"&&X({zIndex:1,pointerEvents:"none",transform:"translate(12px, 16px) scale(1)",maxWidth:"calc(100% - 24px)"},e.size==="small"&&{transform:"translate(12px, 13px) scale(1)"},e.shrink&&X({userSelect:"none",pointerEvents:"auto",transform:"translate(12px, 7px) scale(0.75)",maxWidth:"calc(133% - 24px)"},e.size==="small"&&{transform:"translate(12px, 4px) scale(0.75)"})),e.variant==="outlined"&&X({zIndex:1,pointerEvents:"none",transform:"translate(14px, 16px) scale(1)",maxWidth:"calc(100% - 24px)"},e.size==="small"&&{transform:"translate(14px, 9px) scale(1)"},e.shrink&&{userSelect:"none",pointerEvents:"auto",maxWidth:"calc(133% - 32px)",transform:"translate(14px, -9px) scale(0.75)"}))),pse=D.forwardRef(function(e,n){const r=En({name:"MuiInputLabel",props:e}),{disableAnimation:i=!1,shrink:s,className:o}=r,a=Rt(r,dse),l=_p();let c=s;typeof c>"u"&&l&&(c=l.filled||l.focused||l.adornedStart);const f=vg({props:r,muiFormControl:l,states:["size","variant","required","focused"]}),p=X({},r,{disableAnimation:i,formControl:l,shrink:c,size:f.size,variant:f.variant,required:f.required,focused:f.focused}),g=fse(p);return C.jsx(hse,X({"data-shrink":c,ownerState:p,ref:n,className:At(g.root,o)},a,{classes:g}))}),mse=pse,gse=D.createContext({}),Tu=gse;function vse(t){return bn("MuiList",t)}pn("MuiList",["root","padding","dense","subheader"]);const yse=["children","className","component","dense","disablePadding","subheader"],xse=t=>{const{classes:e,disablePadding:n,dense:r,subheader:i}=t;return Sn({root:["root",!n&&"padding",r&&"dense",i&&"subheader"]},vse,e)},_se=lt("ul",{name:"MuiList",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,!n.disablePadding&&e.padding,n.dense&&e.dense,n.subheader&&e.subheader]}})(({ownerState:t})=>X({listStyle:"none",margin:0,padding:0,position:"relative"},!t.disablePadding&&{paddingTop:8,paddingBottom:8},t.subheader&&{paddingTop:0})),bse=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiList"}),{children:i,className:s,component:o="ul",dense:a=!1,disablePadding:l=!1,subheader:c}=r,f=Rt(r,yse),p=D.useMemo(()=>({dense:a}),[a]),g=X({},r,{component:o,dense:a,disablePadding:l}),v=xse(g);return C.jsx(Tu.Provider,{value:p,children:C.jsxs(_se,X({as:o,className:At(v.root,s),ref:n,ownerState:g},f,{children:[c,i]}))})}),TR=bse;function Sse(t){return bn("MuiListItem",t)}const wse=pn("MuiListItem",["root","container","focusVisible","dense","alignItemsFlexStart","disabled","divider","gutters","padding","button","secondaryAction","selected"]),Wm=wse,Mse=pn("MuiListItemButton",["root","focusVisible","dense","alignItemsFlexStart","disabled","divider","gutters","selected"]),Ese=Mse;function Cse(t){return bn("MuiListItemSecondaryAction",t)}pn("MuiListItemSecondaryAction",["root","disableGutters"]);const Tse=["className"],Ase=t=>{const{disableGutters:e,classes:n}=t;return Sn({root:["root",e&&"disableGutters"]},Cse,n)},Rse=lt("div",{name:"MuiListItemSecondaryAction",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.disableGutters&&e.disableGutters]}})(({ownerState:t})=>X({position:"absolute",right:16,top:"50%",transform:"translateY(-50%)"},t.disableGutters&&{right:0})),B7=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiListItemSecondaryAction"}),{className:i}=r,s=Rt(r,Tse),o=D.useContext(Tu),a=X({},r,{disableGutters:o.disableGutters}),l=Ase(a);return C.jsx(Rse,X({className:At(l.root,i),ownerState:a,ref:n},s))});B7.muiName="ListItemSecondaryAction";const Pse=B7,Ise=["className"],Lse=["alignItems","autoFocus","button","children","className","component","components","componentsProps","ContainerComponent","ContainerProps","dense","disabled","disableGutters","disablePadding","divider","focusVisibleClassName","secondaryAction","selected","slotProps","slots"],kse=(t,e)=>{const{ownerState:n}=t;return[e.root,n.dense&&e.dense,n.alignItems==="flex-start"&&e.alignItemsFlexStart,n.divider&&e.divider,!n.disableGutters&&e.gutters,!n.disablePadding&&e.padding,n.button&&e.button,n.hasSecondaryAction&&e.secondaryAction]},Ose=t=>{const{alignItems:e,button:n,classes:r,dense:i,disabled:s,disableGutters:o,disablePadding:a,divider:l,hasSecondaryAction:c,selected:f}=t;return Sn({root:["root",i&&"dense",!o&&"gutters",!a&&"padding",l&&"divider",s&&"disabled",n&&"button",e==="flex-start"&&"alignItemsFlexStart",c&&"secondaryAction",f&&"selected"],container:["container"]},Sse,r)},Nse=lt("div",{name:"MuiListItem",slot:"Root",overridesResolver:kse})(({theme:t,ownerState:e})=>X({display:"flex",justifyContent:"flex-start",alignItems:"center",position:"relative",textDecoration:"none",width:"100%",boxSizing:"border-box",textAlign:"left"},!e.disablePadding&&X({paddingTop:8,paddingBottom:8},e.dense&&{paddingTop:4,paddingBottom:4},!e.disableGutters&&{paddingLeft:16,paddingRight:16},!!e.secondaryAction&&{paddingRight:48}),!!e.secondaryAction&&{[`& > .${Ese.root}`]:{paddingRight:48}},{[`&.${Wm.focusVisible}`]:{backgroundColor:(t.vars||t).palette.action.focus},[`&.${Wm.selected}`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / ${t.vars.palette.action.selectedOpacity})`:qn(t.palette.primary.main,t.palette.action.selectedOpacity),[`&.${Wm.focusVisible}`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / calc(${t.vars.palette.action.selectedOpacity} + ${t.vars.palette.action.focusOpacity}))`:qn(t.palette.primary.main,t.palette.action.selectedOpacity+t.palette.action.focusOpacity)}},[`&.${Wm.disabled}`]:{opacity:(t.vars||t).palette.action.disabledOpacity}},e.alignItems==="flex-start"&&{alignItems:"flex-start"},e.divider&&{borderBottom:`1px solid ${(t.vars||t).palette.divider}`,backgroundClip:"padding-box"},e.button&&{transition:t.transitions.create("background-color",{duration:t.transitions.duration.shortest}),"&:hover":{textDecoration:"none",backgroundColor:(t.vars||t).palette.action.hover,"@media (hover: none)":{backgroundColor:"transparent"}},[`&.${Wm.selected}:hover`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / calc(${t.vars.palette.action.selectedOpacity} + ${t.vars.palette.action.hoverOpacity}))`:qn(t.palette.primary.main,t.palette.action.selectedOpacity+t.palette.action.hoverOpacity),"@media (hover: none)":{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / ${t.vars.palette.action.selectedOpacity})`:qn(t.palette.primary.main,t.palette.action.selectedOpacity)}}},e.hasSecondaryAction&&{paddingRight:48})),Dse=lt("li",{name:"MuiListItem",slot:"Container",overridesResolver:(t,e)=>e.container})({position:"relative"}),Fse=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiListItem"}),{alignItems:i="center",autoFocus:s=!1,button:o=!1,children:a,className:l,component:c,components:f={},componentsProps:p={},ContainerComponent:g="li",ContainerProps:{className:v}={},dense:x=!1,disabled:_=!1,disableGutters:b=!1,disablePadding:y=!1,divider:S=!1,focusVisibleClassName:w,secondaryAction:T,selected:L=!1,slotProps:R={},slots:P={}}=r,F=Rt(r.ContainerProps,Ise),O=Rt(r,Lse),I=D.useContext(Tu),H=D.useMemo(()=>({dense:x||I.dense||!1,alignItems:i,disableGutters:b}),[i,I.dense,x,b]),Q=D.useRef(null);Xo(()=>{s&&Q.current&&Q.current.focus()},[s]);const q=D.Children.toArray(a),le=q.length&&mv(q[q.length-1],["ListItemSecondaryAction"]),ie=X({},r,{alignItems:i,autoFocus:s,button:o,dense:H.dense,disabled:_,disableGutters:b,disablePadding:y,divider:S,hasSecondaryAction:le,selected:L}),ee=Ose(ie),ue=Kr(Q,n),z=P.root||f.Root||Nse,te=R.root||p.root||{},oe=X({className:At(ee.root,te.className,l),disabled:_},O);let de=c||"li";return o&&(oe.component=c||"div",oe.focusVisibleClassName=At(Wm.focusVisible,w),de=Nu),le?(de=!oe.component&&!c?"div":de,g==="li"&&(de==="li"?de="div":oe.component==="li"&&(oe.component="div")),C.jsx(Tu.Provider,{value:H,children:C.jsxs(Dse,X({as:g,className:At(ee.container,v),ref:ue,ownerState:ie},F,{children:[C.jsx(z,X({},te,!Rc(z)&&{as:de,ownerState:X({},ie,te.ownerState)},oe,{children:q})),q.pop()]}))})):C.jsx(Tu.Provider,{value:H,children:C.jsxs(z,X({},te,{as:de,ref:ue},!Rc(z)&&{ownerState:X({},ie,te.ownerState)},oe,{children:[q,T&&C.jsx(Pse,{children:T})]}))})}),mc=Fse;function Use(t){return bn("MuiListItemIcon",t)}const mk=pn("MuiListItemIcon",["root","alignItemsFlexStart"]),zse=["className"],Bse=t=>{const{alignItems:e,classes:n}=t;return Sn({root:["root",e==="flex-start"&&"alignItemsFlexStart"]},Use,n)},Hse=lt("div",{name:"MuiListItemIcon",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.alignItems==="flex-start"&&e.alignItemsFlexStart]}})(({theme:t,ownerState:e})=>X({minWidth:56,color:(t.vars||t).palette.action.active,flexShrink:0,display:"inline-flex"},e.alignItems==="flex-start"&&{marginTop:8})),$se=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiListItemIcon"}),{className:i}=r,s=Rt(r,zse),o=D.useContext(Tu),a=X({},r,{alignItems:o.alignItems}),l=Bse(a);return C.jsx(Hse,X({className:At(l.root,i),ownerState:a,ref:n},s))}),gk=$se;function Vse(t){return bn("MuiListItemText",t)}const Wse=pn("MuiListItemText",["root","multiline","dense","inset","primary","secondary"]),g2=Wse,jse=["children","className","disableTypography","inset","primary","primaryTypographyProps","secondary","secondaryTypographyProps"],Gse=t=>{const{classes:e,inset:n,primary:r,secondary:i,dense:s}=t;return Sn({root:["root",n&&"inset",s&&"dense",r&&i&&"multiline"],primary:["primary"],secondary:["secondary"]},Vse,e)},Xse=lt("div",{name:"MuiListItemText",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[{[`& .${g2.primary}`]:e.primary},{[`& .${g2.secondary}`]:e.secondary},e.root,n.inset&&e.inset,n.primary&&n.secondary&&e.multiline,n.dense&&e.dense]}})(({ownerState:t})=>X({flex:"1 1 auto",minWidth:0,marginTop:4,marginBottom:4},t.primary&&t.secondary&&{marginTop:6,marginBottom:6},t.inset&&{paddingLeft:56})),qse=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiListItemText"}),{children:i,className:s,disableTypography:o=!1,inset:a=!1,primary:l,primaryTypographyProps:c,secondary:f,secondaryTypographyProps:p}=r,g=Rt(r,jse),{dense:v}=D.useContext(Tu);let x=l??i,_=f;const b=X({},r,{disableTypography:o,inset:a,primary:!!x,secondary:!!_,dense:v}),y=Gse(b);return x!=null&&x.type!==mr&&!o&&(x=C.jsx(mr,X({variant:v?"body2":"body1",className:y.primary,component:c!=null&&c.variant?void 0:"span",display:"block"},c,{children:x}))),_!=null&&_.type!==mr&&!o&&(_=C.jsx(mr,X({variant:"body2",className:y.secondary,color:"text.secondary",display:"block"},p,{children:_}))),C.jsxs(Xse,X({className:At(y.root,s),ownerState:b,ref:n},g,{children:[x,_]}))}),gc=qse,Zse=["actions","autoFocus","autoFocusItem","children","className","disabledItemsFocusable","disableListWrap","onKeyDown","variant"];function qE(t,e,n){return t===e?t.firstChild:e&&e.nextElementSibling?e.nextElementSibling:n?null:t.firstChild}function vk(t,e,n){return t===e?n?t.firstChild:t.lastChild:e&&e.previousElementSibling?e.previousElementSibling:n?null:t.lastChild}function H7(t,e){if(e===void 0)return!0;let n=t.innerText;return n===void 0&&(n=t.textContent),n=n.trim().toLowerCase(),n.length===0?!1:e.repeating?n[0]===e.keys[0]:n.indexOf(e.keys.join(""))===0}function C1(t,e,n,r,i,s){let o=!1,a=i(t,e,e?n:!1);for(;a;){if(a===t.firstChild){if(o)return!1;o=!0}const l=r?!1:a.disabled||a.getAttribute("aria-disabled")==="true";if(!a.hasAttribute("tabindex")||!H7(a,s)||l)a=i(t,a,n);else return a.focus(),!0}return!1}const Yse=D.forwardRef(function(e,n){const{actions:r,autoFocus:i=!1,autoFocusItem:s=!1,children:o,className:a,disabledItemsFocusable:l=!1,disableListWrap:c=!1,onKeyDown:f,variant:p="selectedMenu"}=e,g=Rt(e,Zse),v=D.useRef(null),x=D.useRef({keys:[],repeating:!0,previousKeyMatched:!0,lastTime:null});Xo(()=>{i&&v.current.focus()},[i]),D.useImperativeHandle(r,()=>({adjustStyleForScrollbar:(w,{direction:T})=>{const L=!v.current.style.width;if(w.clientHeight{const T=v.current,L=w.key,R=Oi(T).activeElement;if(L==="ArrowDown")w.preventDefault(),C1(T,R,c,l,qE);else if(L==="ArrowUp")w.preventDefault(),C1(T,R,c,l,vk);else if(L==="Home")w.preventDefault(),C1(T,null,c,l,qE);else if(L==="End")w.preventDefault(),C1(T,null,c,l,vk);else if(L.length===1){const P=x.current,F=L.toLowerCase(),O=performance.now();P.keys.length>0&&(O-P.lastTime>500?(P.keys=[],P.repeating=!0,P.previousKeyMatched=!0):P.repeating&&F!==P.keys[0]&&(P.repeating=!1)),P.lastTime=O,P.keys.push(F);const I=R&&!P.repeating&&H7(R,P);P.previousKeyMatched&&(I||C1(T,R,!1,l,qE,P))?w.preventDefault():P.previousKeyMatched=!1}f&&f(w)},b=Kr(v,n);let y=-1;D.Children.forEach(o,(w,T)=>{if(!D.isValidElement(w)){y===T&&(y+=1,y>=o.length&&(y=-1));return}w.props.disabled||(p==="selectedMenu"&&w.props.selected||y===-1)&&(y=T),y===T&&(w.props.disabled||w.props.muiSkipListHighlight||w.type.muiSkipListHighlight)&&(y+=1,y>=o.length&&(y=-1))});const S=D.Children.map(o,(w,T)=>{if(T===y){const L={};return s&&(L.autoFocus=!0),w.props.tabIndex===void 0&&p==="selectedMenu"&&(L.tabIndex=0),D.cloneElement(w,L)}return w});return C.jsx(TR,X({role:"menu",ref:b,className:a,onKeyDown:_,tabIndex:i?0:-1},g,{children:S}))}),Kse=Yse;function Qse(t){return bn("MuiPopover",t)}pn("MuiPopover",["root","paper"]);const Jse=["onEntering"],eoe=["action","anchorEl","anchorOrigin","anchorPosition","anchorReference","children","className","container","elevation","marginThreshold","open","PaperProps","slots","slotProps","transformOrigin","TransitionComponent","transitionDuration","TransitionProps","disableScrollLock"],toe=["slotProps"];function yk(t,e){let n=0;return typeof e=="number"?n=e:e==="center"?n=t.height/2:e==="bottom"&&(n=t.height),n}function xk(t,e){let n=0;return typeof e=="number"?n=e:e==="center"?n=t.width/2:e==="right"&&(n=t.width),n}function _k(t){return[t.horizontal,t.vertical].map(e=>typeof e=="number"?`${e}px`:e).join(" ")}function ZE(t){return typeof t=="function"?t():t}const noe=t=>{const{classes:e}=t;return Sn({root:["root"],paper:["paper"]},Qse,e)},roe=lt(k7,{name:"MuiPopover",slot:"Root",overridesResolver:(t,e)=>e.root})({}),$7=lt(nx,{name:"MuiPopover",slot:"Paper",overridesResolver:(t,e)=>e.paper})({position:"absolute",overflowY:"auto",overflowX:"hidden",minWidth:16,minHeight:16,maxWidth:"calc(100% - 32px)",maxHeight:"calc(100% - 32px)",outline:0}),ioe=D.forwardRef(function(e,n){var r,i,s;const o=En({props:e,name:"MuiPopover"}),{action:a,anchorEl:l,anchorOrigin:c={vertical:"top",horizontal:"left"},anchorPosition:f,anchorReference:p="anchorEl",children:g,className:v,container:x,elevation:_=8,marginThreshold:b=16,open:y,PaperProps:S={},slots:w,slotProps:T,transformOrigin:L={vertical:"top",horizontal:"left"},TransitionComponent:R=NT,transitionDuration:P="auto",TransitionProps:{onEntering:F}={},disableScrollLock:O=!1}=o,I=Rt(o.TransitionProps,Jse),H=Rt(o,eoe),Q=(r=T==null?void 0:T.paper)!=null?r:S,q=D.useRef(),le=Kr(q,Q.ref),ie=X({},o,{anchorOrigin:c,anchorReference:p,elevation:_,marginThreshold:b,externalPaperSlotProps:Q,transformOrigin:L,TransitionComponent:R,transitionDuration:P,TransitionProps:I}),ee=noe(ie),ue=D.useCallback(()=>{if(p==="anchorPosition")return f;const Oe=ZE(l),ze=(Oe&&Oe.nodeType===1?Oe:Oi(q.current).body).getBoundingClientRect();return{top:ze.top+yk(ze,c.vertical),left:ze.left+xk(ze,c.horizontal)}},[l,c.horizontal,c.vertical,f,p]),z=D.useCallback(Oe=>({vertical:yk(Oe,L.vertical),horizontal:xk(Oe,L.horizontal)}),[L.horizontal,L.vertical]),te=D.useCallback(Oe=>{const Te={width:Oe.offsetWidth,height:Oe.offsetHeight},ze=z(Te);if(p==="none")return{top:null,left:null,transformOrigin:_k(ze)};const ke=ue();let rt=ke.top-ze.vertical,tt=ke.left-ze.horizontal;const ae=rt+Te.height,G=tt+Te.width,be=Oc(ZE(l)),$e=be.innerHeight-b,Ze=be.innerWidth-b;if(b!==null&&rt$e){const We=ae-$e;rt-=We,ze.vertical+=We}if(b!==null&&ttZe){const We=G-Ze;tt-=We,ze.horizontal+=We}return{top:`${Math.round(rt)}px`,left:`${Math.round(tt)}px`,transformOrigin:_k(ze)}},[l,p,ue,z,b]),[oe,de]=D.useState(y),Ce=D.useCallback(()=>{const Oe=q.current;if(!Oe)return;const Te=te(Oe);Te.top!==null&&(Oe.style.top=Te.top),Te.left!==null&&(Oe.style.left=Te.left),Oe.style.transformOrigin=Te.transformOrigin,de(!0)},[te]);D.useEffect(()=>(O&&window.addEventListener("scroll",Ce),()=>window.removeEventListener("scroll",Ce)),[l,O,Ce]);const Le=(Oe,Te)=>{F&&F(Oe,Te),Ce()},V=()=>{de(!1)};D.useEffect(()=>{y&&Ce()}),D.useImperativeHandle(a,()=>y?{updatePosition:()=>{Ce()}}:null,[y,Ce]),D.useEffect(()=>{if(!y)return;const Oe=Qy(()=>{Ce()}),Te=Oc(l);return Te.addEventListener("resize",Oe),()=>{Oe.clear(),Te.removeEventListener("resize",Oe)}},[l,y,Ce]);let me=P;P==="auto"&&!R.muiSupportAuto&&(me=void 0);const pe=x||(l?Oi(ZE(l)).body:void 0),Se=(i=w==null?void 0:w.root)!=null?i:roe,je=(s=w==null?void 0:w.paper)!=null?s:$7,it=Qi({elementType:je,externalSlotProps:X({},Q,{style:oe?Q.style:X({},Q.style,{opacity:0})}),additionalProps:{elevation:_,ref:le},ownerState:ie,className:At(ee.paper,Q==null?void 0:Q.className)}),xe=Qi({elementType:Se,externalSlotProps:(T==null?void 0:T.root)||{},externalForwardedProps:H,additionalProps:{ref:n,slotProps:{backdrop:{invisible:!0}},container:pe,open:y},ownerState:ie,className:At(ee.root,v)}),{slotProps:et}=xe,Re=Rt(xe,toe);return C.jsx(Se,X({},Re,!Rc(Se)&&{slotProps:et,disableScrollLock:O},{children:C.jsx(R,X({appear:!0,in:y,onEntering:Le,onExited:V,timeout:me},I,{children:C.jsx(je,X({},it,{children:g}))}))}))}),soe=ioe;function ooe(t){return bn("MuiMenu",t)}pn("MuiMenu",["root","paper","list"]);const aoe=["onEntering"],loe=["autoFocus","children","className","disableAutoFocusItem","MenuListProps","onClose","open","PaperProps","PopoverClasses","transitionDuration","TransitionProps","variant","slots","slotProps"],coe={vertical:"top",horizontal:"right"},uoe={vertical:"top",horizontal:"left"},doe=t=>{const{classes:e}=t;return Sn({root:["root"],paper:["paper"],list:["list"]},ooe,e)},foe=lt(soe,{shouldForwardProp:t=>La(t)||t==="classes",name:"MuiMenu",slot:"Root",overridesResolver:(t,e)=>e.root})({}),hoe=lt($7,{name:"MuiMenu",slot:"Paper",overridesResolver:(t,e)=>e.paper})({maxHeight:"calc(100% - 96px)",WebkitOverflowScrolling:"touch"}),poe=lt(Kse,{name:"MuiMenu",slot:"List",overridesResolver:(t,e)=>e.list})({outline:0}),moe=D.forwardRef(function(e,n){var r,i;const s=En({props:e,name:"MuiMenu"}),{autoFocus:o=!0,children:a,className:l,disableAutoFocusItem:c=!1,MenuListProps:f={},onClose:p,open:g,PaperProps:v={},PopoverClasses:x,transitionDuration:_="auto",TransitionProps:{onEntering:b}={},variant:y="selectedMenu",slots:S={},slotProps:w={}}=s,T=Rt(s.TransitionProps,aoe),L=Rt(s,loe),R=ex(),P=X({},s,{autoFocus:o,disableAutoFocusItem:c,MenuListProps:f,onEntering:b,PaperProps:v,transitionDuration:_,TransitionProps:T,variant:y}),F=doe(P),O=o&&!c&&g,I=D.useRef(null),H=(z,te)=>{I.current&&I.current.adjustStyleForScrollbar(z,{direction:R?"rtl":"ltr"}),b&&b(z,te)},Q=z=>{z.key==="Tab"&&(z.preventDefault(),p&&p(z,"tabKeyDown"))};let q=-1;D.Children.map(a,(z,te)=>{D.isValidElement(z)&&(z.props.disabled||(y==="selectedMenu"&&z.props.selected||q===-1)&&(q=te))});const le=(r=S.paper)!=null?r:hoe,ie=(i=w.paper)!=null?i:v,ee=Qi({elementType:S.root,externalSlotProps:w.root,ownerState:P,className:[F.root,l]}),ue=Qi({elementType:le,externalSlotProps:ie,ownerState:P,className:F.paper});return C.jsx(foe,X({onClose:p,anchorOrigin:{vertical:"bottom",horizontal:R?"right":"left"},transformOrigin:R?coe:uoe,slots:{paper:le,root:S.root},slotProps:{root:ee,paper:ue},open:g,ref:n,transitionDuration:_,TransitionProps:X({onEntering:H},T),ownerState:P},L,{classes:x,children:C.jsx(poe,X({onKeyDown:Q,actions:I,autoFocus:o&&(q===-1||c),autoFocusItem:O,variant:y},f,{className:At(F.list,f.className),children:a}))}))}),goe=moe;function voe(t){return bn("MuiMenuItem",t)}const yoe=pn("MuiMenuItem",["root","focusVisible","dense","disabled","divider","gutters","selected"]),T1=yoe,xoe=["autoFocus","component","dense","divider","disableGutters","focusVisibleClassName","role","tabIndex","className"],_oe=(t,e)=>{const{ownerState:n}=t;return[e.root,n.dense&&e.dense,n.divider&&e.divider,!n.disableGutters&&e.gutters]},boe=t=>{const{disabled:e,dense:n,divider:r,disableGutters:i,selected:s,classes:o}=t,l=Sn({root:["root",n&&"dense",e&&"disabled",!i&&"gutters",r&&"divider",s&&"selected"]},voe,o);return X({},o,l)},Soe=lt(Nu,{shouldForwardProp:t=>La(t)||t==="classes",name:"MuiMenuItem",slot:"Root",overridesResolver:_oe})(({theme:t,ownerState:e})=>X({},t.typography.body1,{display:"flex",justifyContent:"flex-start",alignItems:"center",position:"relative",textDecoration:"none",minHeight:48,paddingTop:6,paddingBottom:6,boxSizing:"border-box",whiteSpace:"nowrap"},!e.disableGutters&&{paddingLeft:16,paddingRight:16},e.divider&&{borderBottom:`1px solid ${(t.vars||t).palette.divider}`,backgroundClip:"padding-box"},{"&:hover":{textDecoration:"none",backgroundColor:(t.vars||t).palette.action.hover,"@media (hover: none)":{backgroundColor:"transparent"}},[`&.${T1.selected}`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / ${t.vars.palette.action.selectedOpacity})`:qn(t.palette.primary.main,t.palette.action.selectedOpacity),[`&.${T1.focusVisible}`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / calc(${t.vars.palette.action.selectedOpacity} + ${t.vars.palette.action.focusOpacity}))`:qn(t.palette.primary.main,t.palette.action.selectedOpacity+t.palette.action.focusOpacity)}},[`&.${T1.selected}:hover`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / calc(${t.vars.palette.action.selectedOpacity} + ${t.vars.palette.action.hoverOpacity}))`:qn(t.palette.primary.main,t.palette.action.selectedOpacity+t.palette.action.hoverOpacity),"@media (hover: none)":{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / ${t.vars.palette.action.selectedOpacity})`:qn(t.palette.primary.main,t.palette.action.selectedOpacity)}},[`&.${T1.focusVisible}`]:{backgroundColor:(t.vars||t).palette.action.focus},[`&.${T1.disabled}`]:{opacity:(t.vars||t).palette.action.disabledOpacity},[`& + .${dk.root}`]:{marginTop:t.spacing(1),marginBottom:t.spacing(1)},[`& + .${dk.inset}`]:{marginLeft:52},[`& .${g2.root}`]:{marginTop:0,marginBottom:0},[`& .${g2.inset}`]:{paddingLeft:36},[`& .${mk.root}`]:{minWidth:36}},!e.dense&&{[t.breakpoints.up("sm")]:{minHeight:"auto"}},e.dense&&X({minHeight:32,paddingTop:4,paddingBottom:4},t.typography.body2,{[`& .${mk.root} svg`]:{fontSize:"1.25rem"}}))),woe=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiMenuItem"}),{autoFocus:i=!1,component:s="li",dense:o=!1,divider:a=!1,disableGutters:l=!1,focusVisibleClassName:c,role:f="menuitem",tabIndex:p,className:g}=r,v=Rt(r,xoe),x=D.useContext(Tu),_=D.useMemo(()=>({dense:o||x.dense||!1,disableGutters:l}),[x.dense,o,l]),b=D.useRef(null);Xo(()=>{i&&b.current&&b.current.focus()},[i]);const y=X({},r,{dense:_.dense,divider:a,disableGutters:l}),S=boe(r),w=Kr(b,n);let T;return r.disabled||(T=p!==void 0?p:-1),C.jsx(Tu.Provider,{value:_,children:C.jsx(Soe,X({ref:w,role:f,tabIndex:T,component:s,focusVisibleClassName:At(S.focusVisible,c),className:At(S.root,g)},v,{ownerState:y,classes:S}))})}),ty=woe;function Moe(t){return bn("MuiNativeSelect",t)}const Eoe=pn("MuiNativeSelect",["root","select","multiple","filled","outlined","standard","disabled","icon","iconOpen","iconFilled","iconOutlined","iconStandard","nativeInput","error"]),AR=Eoe,Coe=["className","disabled","error","IconComponent","inputRef","variant"],Toe=t=>{const{classes:e,variant:n,disabled:r,multiple:i,open:s,error:o}=t,a={select:["select",n,r&&"disabled",i&&"multiple",o&&"error"],icon:["icon",`icon${gt(n)}`,s&&"iconOpen",r&&"disabled"]};return Sn(a,Moe,e)},V7=({ownerState:t,theme:e})=>X({MozAppearance:"none",WebkitAppearance:"none",userSelect:"none",borderRadius:0,cursor:"pointer","&:focus":X({},e.vars?{backgroundColor:`rgba(${e.vars.palette.common.onBackgroundChannel} / 0.05)`}:{backgroundColor:e.palette.mode==="light"?"rgba(0, 0, 0, 0.05)":"rgba(255, 255, 255, 0.05)"},{borderRadius:0}),"&::-ms-expand":{display:"none"},[`&.${AR.disabled}`]:{cursor:"default"},"&[multiple]":{height:"auto"},"&:not([multiple]) option, &:not([multiple]) optgroup":{backgroundColor:(e.vars||e).palette.background.paper},"&&&":{paddingRight:24,minWidth:16}},t.variant==="filled"&&{"&&&":{paddingRight:32}},t.variant==="outlined"&&{borderRadius:(e.vars||e).shape.borderRadius,"&:focus":{borderRadius:(e.vars||e).shape.borderRadius},"&&&":{paddingRight:32}}),Aoe=lt("select",{name:"MuiNativeSelect",slot:"Select",shouldForwardProp:La,overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.select,e[n.variant],n.error&&e.error,{[`&.${AR.multiple}`]:e.multiple}]}})(V7),W7=({ownerState:t,theme:e})=>X({position:"absolute",right:0,top:"calc(50% - .5em)",pointerEvents:"none",color:(e.vars||e).palette.action.active,[`&.${AR.disabled}`]:{color:(e.vars||e).palette.action.disabled}},t.open&&{transform:"rotate(180deg)"},t.variant==="filled"&&{right:7},t.variant==="outlined"&&{right:7}),Roe=lt("svg",{name:"MuiNativeSelect",slot:"Icon",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.icon,n.variant&&e[`icon${gt(n.variant)}`],n.open&&e.iconOpen]}})(W7),Poe=D.forwardRef(function(e,n){const{className:r,disabled:i,error:s,IconComponent:o,inputRef:a,variant:l="standard"}=e,c=Rt(e,Coe),f=X({},e,{disabled:i,variant:l,error:s}),p=Toe(f);return C.jsxs(D.Fragment,{children:[C.jsx(Aoe,X({ownerState:f,className:At(p.select,r),disabled:i,ref:a||n},c)),e.multiple?null:C.jsx(Roe,{as:o,ownerState:f,className:p.icon})]})}),Ioe=Poe;var bk;const Loe=["children","classes","className","label","notched"],koe=lt("fieldset",{shouldForwardProp:La})({textAlign:"left",position:"absolute",bottom:0,right:0,top:-5,left:0,margin:0,padding:"0 8px",pointerEvents:"none",borderRadius:"inherit",borderStyle:"solid",borderWidth:1,overflow:"hidden",minWidth:"0%"}),Ooe=lt("legend",{shouldForwardProp:La})(({ownerState:t,theme:e})=>X({float:"unset",width:"auto",overflow:"hidden"},!t.withLabel&&{padding:0,lineHeight:"11px",transition:e.transitions.create("width",{duration:150,easing:e.transitions.easing.easeOut})},t.withLabel&&X({display:"block",padding:0,height:11,fontSize:"0.75em",visibility:"hidden",maxWidth:.01,transition:e.transitions.create("max-width",{duration:50,easing:e.transitions.easing.easeOut}),whiteSpace:"nowrap","& > span":{paddingLeft:5,paddingRight:5,display:"inline-block",opacity:0,visibility:"visible"}},t.notched&&{maxWidth:"100%",transition:e.transitions.create("max-width",{duration:100,easing:e.transitions.easing.easeOut,delay:50})})));function Noe(t){const{className:e,label:n,notched:r}=t,i=Rt(t,Loe),s=n!=null&&n!=="",o=X({},t,{notched:r,withLabel:s});return C.jsx(koe,X({"aria-hidden":!0,className:e,ownerState:o},i,{children:C.jsx(Ooe,{ownerState:o,children:s?C.jsx("span",{children:n}):bk||(bk=C.jsx("span",{className:"notranslate",children:""}))})}))}const Doe=["components","fullWidth","inputComponent","label","multiline","notched","slots","type"],Foe=t=>{const{classes:e}=t,r=Sn({root:["root"],notchedOutline:["notchedOutline"],input:["input"]},Pne,e);return X({},e,r)},Uoe=lt(Ww,{shouldForwardProp:t=>La(t)||t==="classes",name:"MuiOutlinedInput",slot:"Root",overridesResolver:$w})(({theme:t,ownerState:e})=>{const n=t.palette.mode==="light"?"rgba(0, 0, 0, 0.23)":"rgba(255, 255, 255, 0.23)";return X({position:"relative",borderRadius:(t.vars||t).shape.borderRadius,[`&:hover .${pc.notchedOutline}`]:{borderColor:(t.vars||t).palette.text.primary},"@media (hover: none)":{[`&:hover .${pc.notchedOutline}`]:{borderColor:t.vars?`rgba(${t.vars.palette.common.onBackgroundChannel} / 0.23)`:n}},[`&.${pc.focused} .${pc.notchedOutline}`]:{borderColor:(t.vars||t).palette[e.color].main,borderWidth:2},[`&.${pc.error} .${pc.notchedOutline}`]:{borderColor:(t.vars||t).palette.error.main},[`&.${pc.disabled} .${pc.notchedOutline}`]:{borderColor:(t.vars||t).palette.action.disabled}},e.startAdornment&&{paddingLeft:14},e.endAdornment&&{paddingRight:14},e.multiline&&X({padding:"16.5px 14px"},e.size==="small"&&{padding:"8.5px 14px"}))}),zoe=lt(Noe,{name:"MuiOutlinedInput",slot:"NotchedOutline",overridesResolver:(t,e)=>e.notchedOutline})(({theme:t})=>{const e=t.palette.mode==="light"?"rgba(0, 0, 0, 0.23)":"rgba(255, 255, 255, 0.23)";return{borderColor:t.vars?`rgba(${t.vars.palette.common.onBackgroundChannel} / 0.23)`:e}}),Boe=lt(jw,{name:"MuiOutlinedInput",slot:"Input",overridesResolver:Vw})(({theme:t,ownerState:e})=>X({padding:"16.5px 14px"},!t.vars&&{"&:-webkit-autofill":{WebkitBoxShadow:t.palette.mode==="light"?null:"0 0 0 100px #266798 inset",WebkitTextFillColor:t.palette.mode==="light"?null:"#fff",caretColor:t.palette.mode==="light"?null:"#fff",borderRadius:"inherit"}},t.vars&&{"&:-webkit-autofill":{borderRadius:"inherit"},[t.getColorSchemeSelector("dark")]:{"&:-webkit-autofill":{WebkitBoxShadow:"0 0 0 100px #266798 inset",WebkitTextFillColor:"#fff",caretColor:"#fff"}}},e.size==="small"&&{padding:"8.5px 14px"},e.multiline&&{padding:0},e.startAdornment&&{paddingLeft:0},e.endAdornment&&{paddingRight:0})),j7=D.forwardRef(function(e,n){var r,i,s,o,a;const l=En({props:e,name:"MuiOutlinedInput"}),{components:c={},fullWidth:f=!1,inputComponent:p="input",label:g,multiline:v=!1,notched:x,slots:_={},type:b="text"}=l,y=Rt(l,Doe),S=Foe(l),w=_p(),T=vg({props:l,muiFormControl:w,states:["color","disabled","error","focused","hiddenLabel","size","required"]}),L=X({},l,{color:T.color||"primary",disabled:T.disabled,error:T.error,focused:T.focused,formControl:w,fullWidth:f,hiddenLabel:T.hiddenLabel,multiline:v,size:T.size,type:b}),R=(r=(i=_.root)!=null?i:c.Root)!=null?r:Uoe,P=(s=(o=_.input)!=null?o:c.Input)!=null?s:Boe;return C.jsx(SR,X({slots:{root:R,input:P},renderSuffix:F=>C.jsx(zoe,{ownerState:L,className:S.notchedOutline,label:g!=null&&g!==""&&T.required?a||(a=C.jsxs(D.Fragment,{children:[g," ","*"]})):g,notched:typeof x<"u"?x:!!(F.startAdornment||F.filled||F.focused)}),fullWidth:f,inputComponent:p,multiline:v,ref:n,type:b},y,{classes:X({},S,{notchedOutline:null})}))});j7.muiName="Input";const RR=j7;function Hoe(t){return bn("MuiSelect",t)}const A1=pn("MuiSelect",["root","select","multiple","filled","outlined","standard","disabled","focused","icon","iconOpen","iconFilled","iconOutlined","iconStandard","nativeInput","error"]);var Sk;const $oe=["aria-describedby","aria-label","autoFocus","autoWidth","children","className","defaultOpen","defaultValue","disabled","displayEmpty","error","IconComponent","inputRef","labelId","MenuProps","multiple","name","onBlur","onChange","onClose","onFocus","onOpen","open","readOnly","renderValue","SelectDisplayProps","tabIndex","type","value","variant"],Voe=lt("div",{name:"MuiSelect",slot:"Select",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[{[`&.${A1.select}`]:e.select},{[`&.${A1.select}`]:e[n.variant]},{[`&.${A1.error}`]:e.error},{[`&.${A1.multiple}`]:e.multiple}]}})(V7,{[`&.${A1.select}`]:{height:"auto",minHeight:"1.4375em",textOverflow:"ellipsis",whiteSpace:"nowrap",overflow:"hidden"}}),Woe=lt("svg",{name:"MuiSelect",slot:"Icon",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.icon,n.variant&&e[`icon${gt(n.variant)}`],n.open&&e.iconOpen]}})(W7),joe=lt("input",{shouldForwardProp:t=>Aw(t)&&t!=="classes",name:"MuiSelect",slot:"NativeInput",overridesResolver:(t,e)=>e.nativeInput})({bottom:0,left:0,position:"absolute",opacity:0,pointerEvents:"none",width:"100%",boxSizing:"border-box"});function wk(t,e){return typeof e=="object"&&e!==null?t===e:String(t)===String(e)}function Goe(t){return t==null||typeof t=="string"&&!t.trim()}const Xoe=t=>{const{classes:e,variant:n,disabled:r,multiple:i,open:s,error:o}=t,a={select:["select",n,r&&"disabled",i&&"multiple",o&&"error"],icon:["icon",`icon${gt(n)}`,s&&"iconOpen",r&&"disabled"],nativeInput:["nativeInput"]};return Sn(a,Hoe,e)},qoe=D.forwardRef(function(e,n){var r;const{"aria-describedby":i,"aria-label":s,autoFocus:o,autoWidth:a,children:l,className:c,defaultOpen:f,defaultValue:p,disabled:g,displayEmpty:v,error:x=!1,IconComponent:_,inputRef:b,labelId:y,MenuProps:S={},multiple:w,name:T,onBlur:L,onChange:R,onClose:P,onFocus:F,onOpen:O,open:I,readOnly:H,renderValue:Q,SelectDisplayProps:q={},tabIndex:le,value:ie,variant:ee="standard"}=e,ue=Rt(e,$oe),[z,te]=Cu({controlled:ie,default:p,name:"Select"}),[oe,de]=Cu({controlled:I,default:f,name:"Select"}),Ce=D.useRef(null),Le=D.useRef(null),[V,me]=D.useState(null),{current:pe}=D.useRef(I!=null),[Se,je]=D.useState(),it=Kr(n,b),xe=D.useCallback(Be=>{Le.current=Be,Be&&me(Be)},[]),et=V==null?void 0:V.parentNode;D.useImperativeHandle(it,()=>({focus:()=>{Le.current.focus()},node:Ce.current,value:z}),[z]),D.useEffect(()=>{f&&oe&&V&&!pe&&(je(a?null:et.clientWidth),Le.current.focus())},[V,a]),D.useEffect(()=>{o&&Le.current.focus()},[o]),D.useEffect(()=>{if(!y)return;const Be=Oi(Le.current).getElementById(y);if(Be){const vt=()=>{getSelection().isCollapsed&&Le.current.focus()};return Be.addEventListener("click",vt),()=>{Be.removeEventListener("click",vt)}}},[y]);const Re=(Be,vt)=>{Be?O&&O(vt):P&&P(vt),pe||(je(a?null:et.clientWidth),de(Be))},Oe=Be=>{Be.button===0&&(Be.preventDefault(),Le.current.focus(),Re(!0,Be))},Te=Be=>{Re(!1,Be)},ze=D.Children.toArray(l),ke=Be=>{const vt=ze.find(qe=>qe.props.value===Be.target.value);vt!==void 0&&(te(vt.props.value),R&&R(Be,vt))},rt=Be=>vt=>{let qe;if(vt.currentTarget.hasAttribute("tabindex")){if(w){qe=Array.isArray(z)?z.slice():[];const ce=z.indexOf(Be.props.value);ce===-1?qe.push(Be.props.value):qe.splice(ce,1)}else qe=Be.props.value;if(Be.props.onClick&&Be.props.onClick(vt),z!==qe&&(te(qe),R)){const ce=vt.nativeEvent||vt,Ne=new ce.constructor(ce.type,ce);Object.defineProperty(Ne,"target",{writable:!0,value:{value:qe,name:T}}),R(Ne,Be)}w||Re(!1,vt)}},tt=Be=>{H||[" ","ArrowUp","ArrowDown","Enter"].indexOf(Be.key)!==-1&&(Be.preventDefault(),Re(!0,Be))},ae=V!==null&&oe,G=Be=>{!ae&&L&&(Object.defineProperty(Be,"target",{writable:!0,value:{value:z,name:T}}),L(Be))};delete ue["aria-invalid"];let be,$e;const Ze=[];let We=!1;(m2({value:z})||v)&&(Q?be=Q(z):We=!0);const Mt=ze.map(Be=>{if(!D.isValidElement(Be))return null;let vt;if(w){if(!Array.isArray(z))throw new Error(op(2));vt=z.some(qe=>wk(qe,Be.props.value)),vt&&We&&Ze.push(Be.props.children)}else vt=wk(z,Be.props.value),vt&&We&&($e=Be.props.children);return D.cloneElement(Be,{"aria-selected":vt?"true":"false",onClick:rt(Be),onKeyUp:qe=>{qe.key===" "&&qe.preventDefault(),Be.props.onKeyUp&&Be.props.onKeyUp(qe)},role:"option",selected:vt,value:void 0,"data-value":Be.props.value})});We&&(w?Ze.length===0?be=null:be=Ze.reduce((Be,vt,qe)=>(Be.push(vt),qe{const{classes:e}=t;return e},PR={name:"MuiSelect",overridesResolver:(t,e)=>e.root,shouldForwardProp:t=>La(t)&&t!=="variant",slot:"Root"},Joe=lt(qw,PR)(""),eae=lt(RR,PR)(""),tae=lt(D7,PR)(""),G7=D.forwardRef(function(e,n){const r=En({name:"MuiSelect",props:e}),{autoWidth:i=!1,children:s,classes:o={},className:a,defaultOpen:l=!1,displayEmpty:c=!1,IconComponent:f=P7,id:p,input:g,inputProps:v,label:x,labelId:_,MenuProps:b,multiple:y=!1,native:S=!1,onClose:w,onOpen:T,open:L,renderValue:R,SelectDisplayProps:P,variant:F="outlined"}=r,O=Rt(r,Yoe),I=S?Ioe:Zoe,H=_p(),Q=vg({props:r,muiFormControl:H,states:["variant","error"]}),q=Q.variant||F,le=X({},r,{variant:q,classes:o}),ie=Qoe(le),ee=Rt(ie,Koe),ue=g||{standard:C.jsx(Joe,{ownerState:le}),outlined:C.jsx(eae,{label:x,ownerState:le}),filled:C.jsx(tae,{ownerState:le})}[q],z=Kr(n,ue.ref);return C.jsx(D.Fragment,{children:D.cloneElement(ue,X({inputComponent:I,inputProps:X({children:s,error:Q.error,IconComponent:f,variant:q,type:void 0,multiple:y},S?{id:p}:{autoWidth:i,defaultOpen:l,displayEmpty:c,labelId:_,MenuProps:b,onClose:w,onOpen:T,open:L,renderValue:R,SelectDisplayProps:X({id:p},P)},v,{classes:v?vo(ee,v.classes):ee},g?g.props.inputProps:{})},(y&&S||c)&&q==="outlined"?{notched:!0}:{},{ref:z,className:At(ue.props.className,a,ie.root)},!g&&{variant:q},O))})});G7.muiName="Select";const X7=G7,nae=t=>!t||!Rc(t);function rae(t){return bn("MuiSlider",t)}const iae=pn("MuiSlider",["root","active","colorPrimary","colorSecondary","colorError","colorInfo","colorSuccess","colorWarning","disabled","dragging","focusVisible","mark","markActive","marked","markLabel","markLabelActive","rail","sizeSmall","thumb","thumbColorPrimary","thumbColorSecondary","thumbColorError","thumbColorSuccess","thumbColorInfo","thumbColorWarning","track","trackInverted","trackFalse","thumbSizeSmall","valueLabel","valueLabelOpen","valueLabelCircle","valueLabelLabel","vertical"]),rl=iae,sae=t=>{const{open:e}=t;return{offset:At(e&&rl.valueLabelOpen),circle:rl.valueLabelCircle,label:rl.valueLabelLabel}};function oae(t){const{children:e,className:n,value:r}=t,i=sae(t);return e?D.cloneElement(e,{className:At(e.props.className)},C.jsxs(D.Fragment,{children:[e.props.children,C.jsx("span",{className:At(i.offset,n),"aria-hidden":!0,children:C.jsx("span",{className:i.circle,children:C.jsx("span",{className:i.label,children:r})})})]})):null}const aae=["aria-label","aria-valuetext","aria-labelledby","component","components","componentsProps","color","classes","className","disableSwap","disabled","getAriaLabel","getAriaValueText","marks","max","min","name","onChange","onChangeCommitted","orientation","shiftStep","size","step","scale","slotProps","slots","tabIndex","track","value","valueLabelDisplay","valueLabelFormat"],lae=cR();function Mk(t){return t}const cae=lt("span",{name:"MuiSlider",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,e[`color${gt(n.color)}`],n.size!=="medium"&&e[`size${gt(n.size)}`],n.marked&&e.marked,n.orientation==="vertical"&&e.vertical,n.track==="inverted"&&e.trackInverted,n.track===!1&&e.trackFalse]}})(({theme:t})=>{var e;return{borderRadius:12,boxSizing:"content-box",display:"inline-block",position:"relative",cursor:"pointer",touchAction:"none",WebkitTapHighlightColor:"transparent","@media print":{colorAdjust:"exact"},[`&.${rl.disabled}`]:{pointerEvents:"none",cursor:"default",color:(t.vars||t).palette.grey[400]},[`&.${rl.dragging}`]:{[`& .${rl.thumb}, & .${rl.track}`]:{transition:"none"}},variants:[...Object.keys(((e=t.vars)!=null?e:t).palette).filter(n=>{var r;return((r=t.vars)!=null?r:t).palette[n].main}).map(n=>({props:{color:n},style:{color:(t.vars||t).palette[n].main}})),{props:{orientation:"horizontal"},style:{height:4,width:"100%",padding:"13px 0","@media (pointer: coarse)":{padding:"20px 0"}}},{props:{orientation:"horizontal",size:"small"},style:{height:2}},{props:{orientation:"horizontal",marked:!0},style:{marginBottom:20}},{props:{orientation:"vertical"},style:{height:"100%",width:4,padding:"0 13px","@media (pointer: coarse)":{padding:"0 20px"}}},{props:{orientation:"vertical",size:"small"},style:{width:2}},{props:{orientation:"vertical",marked:!0},style:{marginRight:44}}]}}),uae=lt("span",{name:"MuiSlider",slot:"Rail",overridesResolver:(t,e)=>e.rail})({display:"block",position:"absolute",borderRadius:"inherit",backgroundColor:"currentColor",opacity:.38,variants:[{props:{orientation:"horizontal"},style:{width:"100%",height:"inherit",top:"50%",transform:"translateY(-50%)"}},{props:{orientation:"vertical"},style:{height:"100%",width:"inherit",left:"50%",transform:"translateX(-50%)"}},{props:{track:"inverted"},style:{opacity:1}}]}),dae=lt("span",{name:"MuiSlider",slot:"Track",overridesResolver:(t,e)=>e.track})(({theme:t})=>{var e;return{display:"block",position:"absolute",borderRadius:"inherit",border:"1px solid currentColor",backgroundColor:"currentColor",transition:t.transitions.create(["left","width","bottom","height"],{duration:t.transitions.duration.shortest}),variants:[{props:{size:"small"},style:{border:"none"}},{props:{orientation:"horizontal"},style:{height:"inherit",top:"50%",transform:"translateY(-50%)"}},{props:{orientation:"vertical"},style:{width:"inherit",left:"50%",transform:"translateX(-50%)"}},{props:{track:!1},style:{display:"none"}},...Object.keys(((e=t.vars)!=null?e:t).palette).filter(n=>{var r;return((r=t.vars)!=null?r:t).palette[n].main}).map(n=>({props:{color:n,track:"inverted"},style:X({},t.vars?{backgroundColor:t.vars.palette.Slider[`${n}Track`],borderColor:t.vars.palette.Slider[`${n}Track`]}:X({backgroundColor:qv(t.palette[n].main,.62),borderColor:qv(t.palette[n].main,.62)},t.applyStyles("dark",{backgroundColor:Xv(t.palette[n].main,.5)}),t.applyStyles("dark",{borderColor:Xv(t.palette[n].main,.5)})))}))]}}),fae=lt("span",{name:"MuiSlider",slot:"Thumb",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.thumb,e[`thumbColor${gt(n.color)}`],n.size!=="medium"&&e[`thumbSize${gt(n.size)}`]]}})(({theme:t})=>{var e;return{position:"absolute",width:20,height:20,boxSizing:"border-box",borderRadius:"50%",outline:0,backgroundColor:"currentColor",display:"flex",alignItems:"center",justifyContent:"center",transition:t.transitions.create(["box-shadow","left","bottom"],{duration:t.transitions.duration.shortest}),"&::before":{position:"absolute",content:'""',borderRadius:"inherit",width:"100%",height:"100%",boxShadow:(t.vars||t).shadows[2]},"&::after":{position:"absolute",content:'""',borderRadius:"50%",width:42,height:42,top:"50%",left:"50%",transform:"translate(-50%, -50%)"},[`&.${rl.disabled}`]:{"&:hover":{boxShadow:"none"}},variants:[...Object.keys(((e=t.vars)!=null?e:t).palette).filter(n=>{var r;return((r=t.vars)!=null?r:t).palette[n].main}).map(n=>({props:{color:n},style:{[`&:hover, &.${rl.focusVisible}`]:X({},t.vars?{boxShadow:`0px 0px 0px 8px rgba(${t.vars.palette[n].mainChannel} / 0.16)`}:{boxShadow:`0px 0px 0px 8px ${qn(t.palette[n].main,.16)}`},{"@media (hover: none)":{boxShadow:"none"}}),[`&.${rl.active}`]:X({},t.vars?{boxShadow:`0px 0px 0px 14px rgba(${t.vars.palette[n].mainChannel} / 0.16)}`}:{boxShadow:`0px 0px 0px 14px ${qn(t.palette[n].main,.16)}`})}})),{props:{size:"small"},style:{width:12,height:12,"&::before":{boxShadow:"none"}}},{props:{orientation:"horizontal"},style:{top:"50%",transform:"translate(-50%, -50%)"}},{props:{orientation:"vertical"},style:{left:"50%",transform:"translate(-50%, 50%)"}}]}}),hae=lt(oae,{name:"MuiSlider",slot:"ValueLabel",overridesResolver:(t,e)=>e.valueLabel})(({theme:t})=>X({zIndex:1,whiteSpace:"nowrap"},t.typography.body2,{fontWeight:500,transition:t.transitions.create(["transform"],{duration:t.transitions.duration.shortest}),position:"absolute",backgroundColor:(t.vars||t).palette.grey[600],borderRadius:2,color:(t.vars||t).palette.common.white,display:"flex",alignItems:"center",justifyContent:"center",padding:"0.25rem 0.75rem",variants:[{props:{orientation:"horizontal"},style:{transform:"translateY(-100%) scale(0)",top:"-10px",transformOrigin:"bottom center","&::before":{position:"absolute",content:'""',width:8,height:8,transform:"translate(-50%, 50%) rotate(45deg)",backgroundColor:"inherit",bottom:0,left:"50%"},[`&.${rl.valueLabelOpen}`]:{transform:"translateY(-100%) scale(1)"}}},{props:{orientation:"vertical"},style:{transform:"translateY(-50%) scale(0)",right:"30px",top:"50%",transformOrigin:"right center","&::before":{position:"absolute",content:'""',width:8,height:8,transform:"translate(-50%, -50%) rotate(45deg)",backgroundColor:"inherit",right:-8,top:"50%"},[`&.${rl.valueLabelOpen}`]:{transform:"translateY(-50%) scale(1)"}}},{props:{size:"small"},style:{fontSize:t.typography.pxToRem(12),padding:"0.25rem 0.5rem"}},{props:{orientation:"vertical",size:"small"},style:{right:"20px"}}]})),pae=lt("span",{name:"MuiSlider",slot:"Mark",shouldForwardProp:t=>Aw(t)&&t!=="markActive",overridesResolver:(t,e)=>{const{markActive:n}=t;return[e.mark,n&&e.markActive]}})(({theme:t})=>({position:"absolute",width:2,height:2,borderRadius:1,backgroundColor:"currentColor",variants:[{props:{orientation:"horizontal"},style:{top:"50%",transform:"translate(-1px, -50%)"}},{props:{orientation:"vertical"},style:{left:"50%",transform:"translate(-50%, 1px)"}},{props:{markActive:!0},style:{backgroundColor:(t.vars||t).palette.background.paper,opacity:.8}}]})),mae=lt("span",{name:"MuiSlider",slot:"MarkLabel",shouldForwardProp:t=>Aw(t)&&t!=="markLabelActive",overridesResolver:(t,e)=>e.markLabel})(({theme:t})=>X({},t.typography.body2,{color:(t.vars||t).palette.text.secondary,position:"absolute",whiteSpace:"nowrap",variants:[{props:{orientation:"horizontal"},style:{top:30,transform:"translateX(-50%)","@media (pointer: coarse)":{top:40}}},{props:{orientation:"vertical"},style:{left:36,transform:"translateY(50%)","@media (pointer: coarse)":{left:44}}},{props:{markLabelActive:!0},style:{color:(t.vars||t).palette.text.primary}}]})),gae=t=>{const{disabled:e,dragging:n,marked:r,orientation:i,track:s,classes:o,color:a,size:l}=t,c={root:["root",e&&"disabled",n&&"dragging",r&&"marked",i==="vertical"&&"vertical",s==="inverted"&&"trackInverted",s===!1&&"trackFalse",a&&`color${gt(a)}`,l&&`size${gt(l)}`],rail:["rail"],track:["track"],mark:["mark"],markActive:["markActive"],markLabel:["markLabel"],markLabelActive:["markLabelActive"],valueLabel:["valueLabel"],thumb:["thumb",e&&"disabled",l&&`thumbSize${gt(l)}`,a&&`thumbColor${gt(a)}`],active:["active"],disabled:["disabled"],focusVisible:["focusVisible"]};return Sn(c,rae,o)},vae=({children:t})=>t,yae=D.forwardRef(function(e,n){var r,i,s,o,a,l,c,f,p,g,v,x,_,b,y,S,w,T,L,R,P,F,O,I;const H=lae({props:e,name:"MuiSlider"}),Q=ex(),{"aria-label":q,"aria-valuetext":le,"aria-labelledby":ie,component:ee="span",components:ue={},componentsProps:z={},color:te="primary",classes:oe,className:de,disableSwap:Ce=!1,disabled:Le=!1,getAriaLabel:V,getAriaValueText:me,marks:pe=!1,max:Se=100,min:je=0,orientation:it="horizontal",shiftStep:xe=10,size:et="medium",step:Re=1,scale:Oe=Mk,slotProps:Te,slots:ze,track:ke="normal",valueLabelDisplay:rt="off",valueLabelFormat:tt=Mk}=H,ae=Rt(H,aae),G=X({},H,{isRtl:Q,max:Se,min:je,classes:oe,disabled:Le,disableSwap:Ce,orientation:it,marks:pe,color:te,size:et,step:Re,shiftStep:xe,scale:Oe,track:ke,valueLabelDisplay:rt,valueLabelFormat:tt}),{axisProps:be,getRootProps:$e,getHiddenInputProps:Ze,getThumbProps:We,open:Mt,active:pt,axis:at,focusedThumbIndex:Ie,range:ge,dragging:Xe,marks:St,values:mt,trackOffset:Be,trackLeap:vt,getThumbStyle:qe}=Vte(X({},G,{rootRef:n}));G.marked=St.length>0&&St.some(B=>B.label),G.dragging=Xe,G.focusedThumbIndex=Ie;const ce=gae(G),Ne=(r=(i=ze==null?void 0:ze.root)!=null?i:ue.Root)!=null?r:cae,fe=(s=(o=ze==null?void 0:ze.rail)!=null?o:ue.Rail)!=null?s:uae,Fe=(a=(l=ze==null?void 0:ze.track)!=null?l:ue.Track)!=null?a:dae,He=(c=(f=ze==null?void 0:ze.thumb)!=null?f:ue.Thumb)!=null?c:fae,ut=(p=(g=ze==null?void 0:ze.valueLabel)!=null?g:ue.ValueLabel)!=null?p:hae,xt=(v=(x=ze==null?void 0:ze.mark)!=null?x:ue.Mark)!=null?v:pae,Xt=(_=(b=ze==null?void 0:ze.markLabel)!=null?b:ue.MarkLabel)!=null?_:mae,vn=(y=(S=ze==null?void 0:ze.input)!=null?S:ue.Input)!=null?y:"input",mn=(w=Te==null?void 0:Te.root)!=null?w:z.root,On=(T=Te==null?void 0:Te.rail)!=null?T:z.rail,un=(L=Te==null?void 0:Te.track)!=null?L:z.track,Nn=(R=Te==null?void 0:Te.thumb)!=null?R:z.thumb,In=(P=Te==null?void 0:Te.valueLabel)!=null?P:z.valueLabel,or=(F=Te==null?void 0:Te.mark)!=null?F:z.mark,Kn=(O=Te==null?void 0:Te.markLabel)!=null?O:z.markLabel,Fr=(I=Te==null?void 0:Te.input)!=null?I:z.input,gr=Qi({elementType:Ne,getSlotProps:$e,externalSlotProps:mn,externalForwardedProps:ae,additionalProps:X({},nae(Ne)&&{as:ee}),ownerState:X({},G,mn==null?void 0:mn.ownerState),className:[ce.root,de]}),ui=Qi({elementType:fe,externalSlotProps:On,ownerState:G,className:ce.rail}),ss=Qi({elementType:Fe,externalSlotProps:un,additionalProps:{style:X({},be[at].offset(Be),be[at].leap(vt))},ownerState:X({},G,un==null?void 0:un.ownerState),className:ce.track}),Rr=Qi({elementType:He,getSlotProps:We,externalSlotProps:Nn,ownerState:X({},G,Nn==null?void 0:Nn.ownerState),className:ce.thumb}),ji=Qi({elementType:ut,externalSlotProps:In,ownerState:X({},G,In==null?void 0:In.ownerState),className:ce.valueLabel}),Ei=Qi({elementType:xt,externalSlotProps:or,ownerState:G,className:ce.mark}),di=Qi({elementType:Xt,externalSlotProps:Kn,ownerState:G,className:ce.markLabel}),Gi=Qi({elementType:vn,getSlotProps:Ze,externalSlotProps:Fr,ownerState:G});return C.jsxs(Ne,X({},gr,{children:[C.jsx(fe,X({},ui)),C.jsx(Fe,X({},ss)),St.filter(B=>B.value>=je&&B.value<=Se).map((B,ne)=>{const _e=p2(B.value,je,Se),ye=be[at].offset(_e);let we;return ke===!1?we=mt.indexOf(B.value)!==-1:we=ke==="normal"&&(ge?B.value>=mt[0]&&B.value<=mt[mt.length-1]:B.value<=mt[0])||ke==="inverted"&&(ge?B.value<=mt[0]||B.value>=mt[mt.length-1]:B.value>=mt[0]),C.jsxs(D.Fragment,{children:[C.jsx(xt,X({"data-index":ne},Ei,!Rc(xt)&&{markActive:we},{style:X({},ye,Ei.style),className:At(Ei.className,we&&ce.markActive)})),B.label!=null?C.jsx(Xt,X({"aria-hidden":!0,"data-index":ne},di,!Rc(Xt)&&{markLabelActive:we},{style:X({},ye,di.style),className:At(ce.markLabel,di.className,we&&ce.markLabelActive),children:B.label})):null]},ne)}),mt.map((B,ne)=>{const _e=p2(B,je,Se),ye=be[at].offset(_e),we=rt==="off"?vae:ut;return C.jsx(we,X({},!Rc(we)&&{valueLabelFormat:tt,valueLabelDisplay:rt,value:typeof tt=="function"?tt(Oe(B),ne):tt,index:ne,open:Mt===ne||pt===ne||rt==="on",disabled:Le},ji,{children:C.jsx(He,X({"data-index":ne},Rr,{className:At(ce.thumb,Rr.className,pt===ne&&ce.active,Ie===ne&&ce.focusVisible),style:X({},ye,qe(ne),Rr.style),children:C.jsx(vn,X({"data-index":ne,"aria-label":V?V(ne):q,"aria-valuenow":Oe(B),"aria-labelledby":ie,"aria-valuetext":me?me(Oe(B),ne):le,value:mt[ne]},Gi))}))}),ne)})]}))}),IR=yae;function xae(t){return bn("MuiTooltip",t)}const _ae=pn("MuiTooltip",["popper","popperInteractive","popperArrow","popperClose","tooltip","tooltipArrow","touch","tooltipPlacementLeft","tooltipPlacementRight","tooltipPlacementTop","tooltipPlacementBottom","arrow"]),Zd=_ae,bae=["arrow","children","classes","components","componentsProps","describeChild","disableFocusListener","disableHoverListener","disableInteractive","disableTouchListener","enterDelay","enterNextDelay","enterTouchDelay","followCursor","id","leaveDelay","leaveTouchDelay","onClose","onOpen","open","placement","PopperComponent","PopperProps","slotProps","slots","title","TransitionComponent","TransitionProps"];function Sae(t){return Math.round(t*1e5)/1e5}const wae=t=>{const{classes:e,disableInteractive:n,arrow:r,touch:i,placement:s}=t,o={popper:["popper",!n&&"popperInteractive",r&&"popperArrow"],tooltip:["tooltip",r&&"tooltipArrow",i&&"touch",`tooltipPlacement${gt(s.split("-")[0])}`],arrow:["arrow"]};return Sn(o,xae,e)},Mae=lt(Hw,{name:"MuiTooltip",slot:"Popper",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.popper,!n.disableInteractive&&e.popperInteractive,n.arrow&&e.popperArrow,!n.open&&e.popperClose]}})(({theme:t,ownerState:e,open:n})=>X({zIndex:(t.vars||t).zIndex.tooltip,pointerEvents:"none"},!e.disableInteractive&&{pointerEvents:"auto"},!n&&{pointerEvents:"none"},e.arrow&&{[`&[data-popper-placement*="bottom"] .${Zd.arrow}`]:{top:0,marginTop:"-0.71em","&::before":{transformOrigin:"0 100%"}},[`&[data-popper-placement*="top"] .${Zd.arrow}`]:{bottom:0,marginBottom:"-0.71em","&::before":{transformOrigin:"100% 0"}},[`&[data-popper-placement*="right"] .${Zd.arrow}`]:X({},e.isRtl?{right:0,marginRight:"-0.71em"}:{left:0,marginLeft:"-0.71em"},{height:"1em",width:"0.71em","&::before":{transformOrigin:"100% 100%"}}),[`&[data-popper-placement*="left"] .${Zd.arrow}`]:X({},e.isRtl?{left:0,marginLeft:"-0.71em"}:{right:0,marginRight:"-0.71em"},{height:"1em",width:"0.71em","&::before":{transformOrigin:"0 0"}})})),Eae=lt("div",{name:"MuiTooltip",slot:"Tooltip",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.tooltip,n.touch&&e.touch,n.arrow&&e.tooltipArrow,e[`tooltipPlacement${gt(n.placement.split("-")[0])}`]]}})(({theme:t,ownerState:e})=>X({backgroundColor:t.vars?t.vars.palette.Tooltip.bg:qn(t.palette.grey[700],.92),borderRadius:(t.vars||t).shape.borderRadius,color:(t.vars||t).palette.common.white,fontFamily:t.typography.fontFamily,padding:"4px 8px",fontSize:t.typography.pxToRem(11),maxWidth:300,margin:2,wordWrap:"break-word",fontWeight:t.typography.fontWeightMedium},e.arrow&&{position:"relative",margin:0},e.touch&&{padding:"8px 16px",fontSize:t.typography.pxToRem(14),lineHeight:`${Sae(16/14)}em`,fontWeight:t.typography.fontWeightRegular},{[`.${Zd.popper}[data-popper-placement*="left"] &`]:X({transformOrigin:"right center"},e.isRtl?X({marginLeft:"14px"},e.touch&&{marginLeft:"24px"}):X({marginRight:"14px"},e.touch&&{marginRight:"24px"})),[`.${Zd.popper}[data-popper-placement*="right"] &`]:X({transformOrigin:"left center"},e.isRtl?X({marginRight:"14px"},e.touch&&{marginRight:"24px"}):X({marginLeft:"14px"},e.touch&&{marginLeft:"24px"})),[`.${Zd.popper}[data-popper-placement*="top"] &`]:X({transformOrigin:"center bottom",marginBottom:"14px"},e.touch&&{marginBottom:"24px"}),[`.${Zd.popper}[data-popper-placement*="bottom"] &`]:X({transformOrigin:"center top",marginTop:"14px"},e.touch&&{marginTop:"24px"})})),Cae=lt("span",{name:"MuiTooltip",slot:"Arrow",overridesResolver:(t,e)=>e.arrow})(({theme:t})=>({overflow:"hidden",position:"absolute",width:"1em",height:"0.71em",boxSizing:"border-box",color:t.vars?t.vars.palette.Tooltip.bg:qn(t.palette.grey[700],.9),"&::before":{content:'""',margin:"auto",display:"block",width:"100%",height:"100%",backgroundColor:"currentColor",transform:"rotate(45deg)"}}));let tb=!1;const Ek=new Jy;let R1={x:0,y:0};function nb(t,e){return(n,...r)=>{e&&e(n,...r),t(n,...r)}}const Tae=D.forwardRef(function(e,n){var r,i,s,o,a,l,c,f,p,g,v,x,_,b,y,S,w,T,L;const R=En({props:e,name:"MuiTooltip"}),{arrow:P=!1,children:F,components:O={},componentsProps:I={},describeChild:H=!1,disableFocusListener:Q=!1,disableHoverListener:q=!1,disableInteractive:le=!1,disableTouchListener:ie=!1,enterDelay:ee=100,enterNextDelay:ue=0,enterTouchDelay:z=700,followCursor:te=!1,id:oe,leaveDelay:de=0,leaveTouchDelay:Ce=1500,onClose:Le,onOpen:V,open:me,placement:pe="bottom",PopperComponent:Se,PopperProps:je={},slotProps:it={},slots:xe={},title:et,TransitionComponent:Re=NT,TransitionProps:Oe}=R,Te=Rt(R,bae),ze=D.isValidElement(F)?F:C.jsx("span",{children:F}),ke=Bu(),rt=ex(),[tt,ae]=D.useState(),[G,be]=D.useState(null),$e=D.useRef(!1),Ze=le||te,We=Ah(),Mt=Ah(),pt=Ah(),at=Ah(),[Ie,ge]=Cu({controlled:me,default:!1,name:"Tooltip",state:"open"});let Xe=Ie;const St=hg(oe),mt=D.useRef(),Be=ts(()=>{mt.current!==void 0&&(document.body.style.WebkitUserSelect=mt.current,mt.current=void 0),at.clear()});D.useEffect(()=>Be,[Be]);const vt=Qe=>{Ek.clear(),tb=!0,ge(!0),V&&!Xe&&V(Qe)},qe=ts(Qe=>{Ek.start(800+de,()=>{tb=!1}),ge(!1),Le&&Xe&&Le(Qe),We.start(ke.transitions.duration.shortest,()=>{$e.current=!1})}),ce=Qe=>{$e.current&&Qe.type!=="touchstart"||(tt&&tt.removeAttribute("title"),Mt.clear(),pt.clear(),ee||tb&&ue?Mt.start(tb?ue:ee,()=>{vt(Qe)}):vt(Qe))},Ne=Qe=>{Mt.clear(),pt.start(de,()=>{qe(Qe)})},{isFocusVisibleRef:fe,onBlur:Fe,onFocus:He,ref:ut}=Tw(),[,xt]=D.useState(!1),Xt=Qe=>{Fe(Qe),fe.current===!1&&(xt(!1),Ne(Qe))},vn=Qe=>{tt||ae(Qe.currentTarget),He(Qe),fe.current===!0&&(xt(!0),ce(Qe))},mn=Qe=>{$e.current=!0;const wt=ze.props;wt.onTouchStart&&wt.onTouchStart(Qe)},On=Qe=>{mn(Qe),pt.clear(),We.clear(),Be(),mt.current=document.body.style.WebkitUserSelect,document.body.style.WebkitUserSelect="none",at.start(z,()=>{document.body.style.WebkitUserSelect=mt.current,ce(Qe)})},un=Qe=>{ze.props.onTouchEnd&&ze.props.onTouchEnd(Qe),Be(),pt.start(Ce,()=>{qe(Qe)})};D.useEffect(()=>{if(!Xe)return;function Qe(wt){(wt.key==="Escape"||wt.key==="Esc")&&qe(wt)}return document.addEventListener("keydown",Qe),()=>{document.removeEventListener("keydown",Qe)}},[qe,Xe]);const Nn=Kr(ze.ref,ut,ae,n);!et&&et!==0&&(Xe=!1);const In=D.useRef(),or=Qe=>{const wt=ze.props;wt.onMouseMove&&wt.onMouseMove(Qe),R1={x:Qe.clientX,y:Qe.clientY},In.current&&In.current.update()},Kn={},Fr=typeof et=="string";H?(Kn.title=!Xe&&Fr&&!q?et:null,Kn["aria-describedby"]=Xe?St:null):(Kn["aria-label"]=Fr?et:null,Kn["aria-labelledby"]=Xe&&!Fr?St:null);const gr=X({},Kn,Te,ze.props,{className:At(Te.className,ze.props.className),onTouchStart:mn,ref:Nn},te?{onMouseMove:or}:{}),ui={};ie||(gr.onTouchStart=On,gr.onTouchEnd=un),q||(gr.onMouseOver=nb(ce,gr.onMouseOver),gr.onMouseLeave=nb(Ne,gr.onMouseLeave),Ze||(ui.onMouseOver=ce,ui.onMouseLeave=Ne)),Q||(gr.onFocus=nb(vn,gr.onFocus),gr.onBlur=nb(Xt,gr.onBlur),Ze||(ui.onFocus=vn,ui.onBlur=Xt));const ss=D.useMemo(()=>{var Qe;let wt=[{name:"arrow",enabled:!!G,options:{element:G,padding:4}}];return(Qe=je.popperOptions)!=null&&Qe.modifiers&&(wt=wt.concat(je.popperOptions.modifiers)),X({},je.popperOptions,{modifiers:wt})},[G,je]),Rr=X({},R,{isRtl:rt,arrow:P,disableInteractive:Ze,placement:pe,PopperComponentProp:Se,touch:$e.current}),ji=wae(Rr),Ei=(r=(i=xe.popper)!=null?i:O.Popper)!=null?r:Mae,di=(s=(o=(a=xe.transition)!=null?a:O.Transition)!=null?o:Re)!=null?s:NT,Gi=(l=(c=xe.tooltip)!=null?c:O.Tooltip)!=null?l:Eae,B=(f=(p=xe.arrow)!=null?p:O.Arrow)!=null?f:Cae,ne=tv(Ei,X({},je,(g=it.popper)!=null?g:I.popper,{className:At(ji.popper,je==null?void 0:je.className,(v=(x=it.popper)!=null?x:I.popper)==null?void 0:v.className)}),Rr),_e=tv(di,X({},Oe,(_=it.transition)!=null?_:I.transition),Rr),ye=tv(Gi,X({},(b=it.tooltip)!=null?b:I.tooltip,{className:At(ji.tooltip,(y=(S=it.tooltip)!=null?S:I.tooltip)==null?void 0:y.className)}),Rr),we=tv(B,X({},(w=it.arrow)!=null?w:I.arrow,{className:At(ji.arrow,(T=(L=it.arrow)!=null?L:I.arrow)==null?void 0:T.className)}),Rr);return C.jsxs(D.Fragment,{children:[D.cloneElement(ze,gr),C.jsx(Ei,X({as:Se??Hw,placement:pe,anchorEl:te?{getBoundingClientRect:()=>({top:R1.y,left:R1.x,right:R1.x,bottom:R1.y,width:0,height:0})}:tt,popperRef:In,open:tt?Xe:!1,id:St,transition:!0},ui,ne,{popperOptions:ss,children:({TransitionProps:Qe})=>C.jsx(di,X({timeout:ke.transitions.duration.shorter},Qe,_e,{children:C.jsxs(Gi,X({},ye,{children:[et,P?C.jsx(B,X({},we,{ref:be})):null]}))}))}))]})}),Au=Tae;function Aae(t){return bn("MuiSwitch",t)}const ao=pn("MuiSwitch",["root","edgeStart","edgeEnd","switchBase","colorPrimary","colorSecondary","sizeSmall","sizeMedium","checked","disabled","input","thumb","track"]),Rae=["className","color","edge","size","sx"],Pae=cR(),Iae=t=>{const{classes:e,edge:n,size:r,color:i,checked:s,disabled:o}=t,a={root:["root",n&&`edge${gt(n)}`,`size${gt(r)}`],switchBase:["switchBase",`color${gt(i)}`,s&&"checked",o&&"disabled"],thumb:["thumb"],track:["track"],input:["input"]},l=Sn(a,Aae,e);return X({},e,l)},Lae=lt("span",{name:"MuiSwitch",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.edge&&e[`edge${gt(n.edge)}`],e[`size${gt(n.size)}`]]}})({display:"inline-flex",width:34+12*2,height:14+12*2,overflow:"hidden",padding:12,boxSizing:"border-box",position:"relative",flexShrink:0,zIndex:0,verticalAlign:"middle","@media print":{colorAdjust:"exact"},variants:[{props:{edge:"start"},style:{marginLeft:-8}},{props:{edge:"end"},style:{marginRight:-8}},{props:{size:"small"},style:{width:40,height:24,padding:7,[`& .${ao.thumb}`]:{width:16,height:16},[`& .${ao.switchBase}`]:{padding:4,[`&.${ao.checked}`]:{transform:"translateX(16px)"}}}}]}),kae=lt(Are,{name:"MuiSwitch",slot:"SwitchBase",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.switchBase,{[`& .${ao.input}`]:e.input},n.color!=="default"&&e[`color${gt(n.color)}`]]}})(({theme:t})=>({position:"absolute",top:0,left:0,zIndex:1,color:t.vars?t.vars.palette.Switch.defaultColor:`${t.palette.mode==="light"?t.palette.common.white:t.palette.grey[300]}`,transition:t.transitions.create(["left","transform"],{duration:t.transitions.duration.shortest}),[`&.${ao.checked}`]:{transform:"translateX(20px)"},[`&.${ao.disabled}`]:{color:t.vars?t.vars.palette.Switch.defaultDisabledColor:`${t.palette.mode==="light"?t.palette.grey[100]:t.palette.grey[600]}`},[`&.${ao.checked} + .${ao.track}`]:{opacity:.5},[`&.${ao.disabled} + .${ao.track}`]:{opacity:t.vars?t.vars.opacity.switchTrackDisabled:`${t.palette.mode==="light"?.12:.2}`},[`& .${ao.input}`]:{left:"-100%",width:"300%"}}),({theme:t})=>({"&:hover":{backgroundColor:t.vars?`rgba(${t.vars.palette.action.activeChannel} / ${t.vars.palette.action.hoverOpacity})`:qn(t.palette.action.active,t.palette.action.hoverOpacity),"@media (hover: none)":{backgroundColor:"transparent"}},variants:[...Object.entries(t.palette).filter(([,e])=>e.main&&e.light).map(([e])=>({props:{color:e},style:{[`&.${ao.checked}`]:{color:(t.vars||t).palette[e].main,"&:hover":{backgroundColor:t.vars?`rgba(${t.vars.palette[e].mainChannel} / ${t.vars.palette.action.hoverOpacity})`:qn(t.palette[e].main,t.palette.action.hoverOpacity),"@media (hover: none)":{backgroundColor:"transparent"}},[`&.${ao.disabled}`]:{color:t.vars?t.vars.palette.Switch[`${e}DisabledColor`]:`${t.palette.mode==="light"?qv(t.palette[e].main,.62):Xv(t.palette[e].main,.55)}`}},[`&.${ao.checked} + .${ao.track}`]:{backgroundColor:(t.vars||t).palette[e].main}}}))]})),Oae=lt("span",{name:"MuiSwitch",slot:"Track",overridesResolver:(t,e)=>e.track})(({theme:t})=>({height:"100%",width:"100%",borderRadius:14/2,zIndex:-1,transition:t.transitions.create(["opacity","background-color"],{duration:t.transitions.duration.shortest}),backgroundColor:t.vars?t.vars.palette.common.onBackground:`${t.palette.mode==="light"?t.palette.common.black:t.palette.common.white}`,opacity:t.vars?t.vars.opacity.switchTrack:`${t.palette.mode==="light"?.38:.3}`})),Nae=lt("span",{name:"MuiSwitch",slot:"Thumb",overridesResolver:(t,e)=>e.thumb})(({theme:t})=>({boxShadow:(t.vars||t).shadows[1],backgroundColor:"currentColor",width:20,height:20,borderRadius:"50%"})),Dae=D.forwardRef(function(e,n){const r=Pae({props:e,name:"MuiSwitch"}),{className:i,color:s="primary",edge:o=!1,size:a="medium",sx:l}=r,c=Rt(r,Rae),f=X({},r,{color:s,edge:o,size:a}),p=Iae(f),g=C.jsx(Nae,{className:p.thumb,ownerState:f});return C.jsxs(Lae,{className:At(p.root,i),sx:l,ownerState:f,children:[C.jsx(kae,X({type:"checkbox",icon:g,checkedIcon:g,ref:n,ownerState:f},c,{classes:X({},p,{root:p.switchBase})})),C.jsx(Oae,{className:p.track,ownerState:f})]})}),kl=Dae;function Fae(t){return bn("MuiTab",t)}const Uae=pn("MuiTab",["root","labelIcon","textColorInherit","textColorPrimary","textColorSecondary","selected","disabled","fullWidth","wrapped","iconWrapper"]),eh=Uae,zae=["className","disabled","disableFocusRipple","fullWidth","icon","iconPosition","indicator","label","onChange","onClick","onFocus","selected","selectionFollowsFocus","textColor","value","wrapped"],Bae=t=>{const{classes:e,textColor:n,fullWidth:r,wrapped:i,icon:s,label:o,selected:a,disabled:l}=t,c={root:["root",s&&o&&"labelIcon",`textColor${gt(n)}`,r&&"fullWidth",i&&"wrapped",a&&"selected",l&&"disabled"],iconWrapper:["iconWrapper"]};return Sn(c,Fae,e)},Hae=lt(Nu,{name:"MuiTab",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.label&&n.icon&&e.labelIcon,e[`textColor${gt(n.textColor)}`],n.fullWidth&&e.fullWidth,n.wrapped&&e.wrapped]}})(({theme:t,ownerState:e})=>X({},t.typography.button,{maxWidth:360,minWidth:90,position:"relative",minHeight:48,flexShrink:0,padding:"12px 16px",overflow:"hidden",whiteSpace:"normal",textAlign:"center"},e.label&&{flexDirection:e.iconPosition==="top"||e.iconPosition==="bottom"?"column":"row"},{lineHeight:1.25},e.icon&&e.label&&{minHeight:72,paddingTop:9,paddingBottom:9,[`& > .${eh.iconWrapper}`]:X({},e.iconPosition==="top"&&{marginBottom:6},e.iconPosition==="bottom"&&{marginTop:6},e.iconPosition==="start"&&{marginRight:t.spacing(1)},e.iconPosition==="end"&&{marginLeft:t.spacing(1)})},e.textColor==="inherit"&&{color:"inherit",opacity:.6,[`&.${eh.selected}`]:{opacity:1},[`&.${eh.disabled}`]:{opacity:(t.vars||t).palette.action.disabledOpacity}},e.textColor==="primary"&&{color:(t.vars||t).palette.text.secondary,[`&.${eh.selected}`]:{color:(t.vars||t).palette.primary.main},[`&.${eh.disabled}`]:{color:(t.vars||t).palette.text.disabled}},e.textColor==="secondary"&&{color:(t.vars||t).palette.text.secondary,[`&.${eh.selected}`]:{color:(t.vars||t).palette.secondary.main},[`&.${eh.disabled}`]:{color:(t.vars||t).palette.text.disabled}},e.fullWidth&&{flexShrink:1,flexGrow:1,flexBasis:0,maxWidth:"none"},e.wrapped&&{fontSize:t.typography.pxToRem(12)})),$ae=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiTab"}),{className:i,disabled:s=!1,disableFocusRipple:o=!1,fullWidth:a,icon:l,iconPosition:c="top",indicator:f,label:p,onChange:g,onClick:v,onFocus:x,selected:_,selectionFollowsFocus:b,textColor:y="inherit",value:S,wrapped:w=!1}=r,T=Rt(r,zae),L=X({},r,{disabled:s,disableFocusRipple:o,selected:_,icon:!!l,iconPosition:c,label:!!p,fullWidth:a,textColor:y,wrapped:w}),R=Bae(L),P=l&&p&&D.isValidElement(l)?D.cloneElement(l,{className:At(R.iconWrapper,l.props.className)}):l,F=I=>{!_&&g&&g(I,S),v&&v(I)},O=I=>{b&&!_&&g&&g(I,S),x&&x(I)};return C.jsxs(Hae,X({focusRipple:!o,className:At(R.root,i),ref:n,role:"tab","aria-selected":_,disabled:s,onClick:F,onFocus:O,ownerState:L,tabIndex:_?0:-1},T,{children:[c==="top"||c==="start"?C.jsxs(D.Fragment,{children:[P,p]}):C.jsxs(D.Fragment,{children:[p,P]}),f]}))}),YE=$ae,Vae=D.createContext(),q7=Vae;function Wae(t){return bn("MuiTable",t)}pn("MuiTable",["root","stickyHeader"]);const jae=["className","component","padding","size","stickyHeader"],Gae=t=>{const{classes:e,stickyHeader:n}=t;return Sn({root:["root",n&&"stickyHeader"]},Wae,e)},Xae=lt("table",{name:"MuiTable",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.stickyHeader&&e.stickyHeader]}})(({theme:t,ownerState:e})=>X({display:"table",width:"100%",borderCollapse:"collapse",borderSpacing:0,"& caption":X({},t.typography.body2,{padding:t.spacing(2),color:(t.vars||t).palette.text.secondary,textAlign:"left",captionSide:"bottom"})},e.stickyHeader&&{borderCollapse:"separate"})),Ck="table",qae=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiTable"}),{className:i,component:s=Ck,padding:o="normal",size:a="medium",stickyHeader:l=!1}=r,c=Rt(r,jae),f=X({},r,{component:s,padding:o,size:a,stickyHeader:l}),p=Gae(f),g=D.useMemo(()=>({padding:o,size:a,stickyHeader:l}),[o,a,l]);return C.jsx(q7.Provider,{value:g,children:C.jsx(Xae,X({as:s,role:s===Ck?null:"table",ref:n,className:At(p.root,i),ownerState:f},c))})}),Zae=qae,Yae=D.createContext(),LR=Yae;function Kae(t){return bn("MuiTableBody",t)}pn("MuiTableBody",["root"]);const Qae=["className","component"],Jae=t=>{const{classes:e}=t;return Sn({root:["root"]},Kae,e)},ele=lt("tbody",{name:"MuiTableBody",slot:"Root",overridesResolver:(t,e)=>e.root})({display:"table-row-group"}),tle={variant:"body"},Tk="tbody",nle=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiTableBody"}),{className:i,component:s=Tk}=r,o=Rt(r,Qae),a=X({},r,{component:s}),l=Jae(a);return C.jsx(LR.Provider,{value:tle,children:C.jsx(ele,X({className:At(l.root,i),as:s,ref:n,role:s===Tk?null:"rowgroup",ownerState:a},o))})}),rle=nle;function ile(t){return bn("MuiTableCell",t)}const sle=pn("MuiTableCell",["root","head","body","footer","sizeSmall","sizeMedium","paddingCheckbox","paddingNone","alignLeft","alignCenter","alignRight","alignJustify","stickyHeader"]),ole=sle,ale=["align","className","component","padding","scope","size","sortDirection","variant"],lle=t=>{const{classes:e,variant:n,align:r,padding:i,size:s,stickyHeader:o}=t,a={root:["root",n,o&&"stickyHeader",r!=="inherit"&&`align${gt(r)}`,i!=="normal"&&`padding${gt(i)}`,`size${gt(s)}`]};return Sn(a,ile,e)},cle=lt("td",{name:"MuiTableCell",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,e[n.variant],e[`size${gt(n.size)}`],n.padding!=="normal"&&e[`padding${gt(n.padding)}`],n.align!=="inherit"&&e[`align${gt(n.align)}`],n.stickyHeader&&e.stickyHeader]}})(({theme:t,ownerState:e})=>X({},t.typography.body2,{display:"table-cell",verticalAlign:"inherit",borderBottom:t.vars?`1px solid ${t.vars.palette.TableCell.border}`:`1px solid
+ ${t.palette.mode==="light"?qv(qn(t.palette.divider,1),.88):Xv(qn(t.palette.divider,1),.68)}`,textAlign:"left",padding:16},e.variant==="head"&&{color:(t.vars||t).palette.text.primary,lineHeight:t.typography.pxToRem(24),fontWeight:t.typography.fontWeightMedium},e.variant==="body"&&{color:(t.vars||t).palette.text.primary},e.variant==="footer"&&{color:(t.vars||t).palette.text.secondary,lineHeight:t.typography.pxToRem(21),fontSize:t.typography.pxToRem(12)},e.size==="small"&&{padding:"6px 16px",[`&.${ole.paddingCheckbox}`]:{width:24,padding:"0 12px 0 16px","& > *":{padding:0}}},e.padding==="checkbox"&&{width:48,padding:"0 0 0 4px"},e.padding==="none"&&{padding:0},e.align==="left"&&{textAlign:"left"},e.align==="center"&&{textAlign:"center"},e.align==="right"&&{textAlign:"right",flexDirection:"row-reverse"},e.align==="justify"&&{textAlign:"justify"},e.stickyHeader&&{position:"sticky",top:0,zIndex:2,backgroundColor:(t.vars||t).palette.background.default})),ule=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiTableCell"}),{align:i="inherit",className:s,component:o,padding:a,scope:l,size:c,sortDirection:f,variant:p}=r,g=Rt(r,ale),v=D.useContext(q7),x=D.useContext(LR),_=x&&x.variant==="head";let b;o?b=o:b=_?"th":"td";let y=l;b==="td"?y=void 0:!y&&_&&(y="col");const S=p||x&&x.variant,w=X({},r,{align:i,component:b,padding:a||(v&&v.padding?v.padding:"normal"),size:c||(v&&v.size?v.size:"medium"),sortDirection:f,stickyHeader:S==="head"&&v&&v.stickyHeader,variant:S}),T=lle(w);let L=null;return f&&(L=f==="asc"?"ascending":"descending"),C.jsx(cle,X({as:b,ref:n,className:At(T.root,s),"aria-sort":L,scope:y,ownerState:w},g))}),dle=ule,fle=bt(C.jsx("path",{d:"M15.41 16.09l-4.58-4.59 4.58-4.59L14 5.5l-6 6 6 6z"}),"KeyboardArrowLeft"),hle=bt(C.jsx("path",{d:"M8.59 16.34l4.58-4.59-4.58-4.59L10 5.75l6 6-6 6z"}),"KeyboardArrowRight");function ple(t){return bn("MuiTableRow",t)}const mle=pn("MuiTableRow",["root","selected","hover","head","footer"]),Ak=mle,gle=["className","component","hover","selected"],vle=t=>{const{classes:e,selected:n,hover:r,head:i,footer:s}=t;return Sn({root:["root",n&&"selected",r&&"hover",i&&"head",s&&"footer"]},ple,e)},yle=lt("tr",{name:"MuiTableRow",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.head&&e.head,n.footer&&e.footer]}})(({theme:t})=>({color:"inherit",display:"table-row",verticalAlign:"middle",outline:0,[`&.${Ak.hover}:hover`]:{backgroundColor:(t.vars||t).palette.action.hover},[`&.${Ak.selected}`]:{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / ${t.vars.palette.action.selectedOpacity})`:qn(t.palette.primary.main,t.palette.action.selectedOpacity),"&:hover":{backgroundColor:t.vars?`rgba(${t.vars.palette.primary.mainChannel} / calc(${t.vars.palette.action.selectedOpacity} + ${t.vars.palette.action.hoverOpacity}))`:qn(t.palette.primary.main,t.palette.action.selectedOpacity+t.palette.action.hoverOpacity)}}})),Rk="tr",xle=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiTableRow"}),{className:i,component:s=Rk,hover:o=!1,selected:a=!1}=r,l=Rt(r,gle),c=D.useContext(LR),f=X({},r,{component:s,hover:o,selected:a,head:c&&c.variant==="head",footer:c&&c.variant==="footer"}),p=vle(f);return C.jsx(yle,X({as:s,ref:n,className:At(p.root,i),role:s===Rk?null:"row",ownerState:f},l))}),_le=xle;function ble(t){return(1+Math.sin(Math.PI*t-Math.PI/2))/2}function Sle(t,e,n,r={},i=()=>{}){const{ease:s=ble,duration:o=300}=r;let a=null;const l=e[t];let c=!1;const f=()=>{c=!0},p=g=>{if(c){i(new Error("Animation cancelled"));return}a===null&&(a=g);const v=Math.min(1,(g-a)/o);if(e[t]=s(v)*(n-l)+l,v>=1){requestAnimationFrame(()=>{i(null)});return}requestAnimationFrame(p)};return l===n?(i(new Error("Element already at target position")),f):(requestAnimationFrame(p),f)}const wle=["onChange"],Mle={width:99,height:99,position:"absolute",top:-9999,overflow:"scroll"};function Ele(t){const{onChange:e}=t,n=Rt(t,wle),r=D.useRef(),i=D.useRef(null),s=()=>{r.current=i.current.offsetHeight-i.current.clientHeight};return Xo(()=>{const o=Qy(()=>{const l=r.current;s(),l!==r.current&&e(r.current)}),a=Oc(i.current);return a.addEventListener("resize",o),()=>{o.clear(),a.removeEventListener("resize",o)}},[e]),D.useEffect(()=>{s(),e(r.current)},[e]),C.jsx("div",X({style:Mle,ref:i},n))}function Cle(t){return bn("MuiTabScrollButton",t)}const Tle=pn("MuiTabScrollButton",["root","vertical","horizontal","disabled"]),Ale=Tle,Rle=["className","slots","slotProps","direction","orientation","disabled"],Ple=t=>{const{classes:e,orientation:n,disabled:r}=t;return Sn({root:["root",n,r&&"disabled"]},Cle,e)},Ile=lt(Nu,{name:"MuiTabScrollButton",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.root,n.orientation&&e[n.orientation]]}})(({ownerState:t})=>X({width:40,flexShrink:0,opacity:.8,[`&.${Ale.disabled}`]:{opacity:0}},t.orientation==="vertical"&&{width:"100%",height:40,"& svg":{transform:`rotate(${t.isRtl?-90:90}deg)`}})),Lle=D.forwardRef(function(e,n){var r,i;const s=En({props:e,name:"MuiTabScrollButton"}),{className:o,slots:a={},slotProps:l={},direction:c}=s,f=Rt(s,Rle),p=ex(),g=X({isRtl:p},s),v=Ple(g),x=(r=a.StartScrollButtonIcon)!=null?r:fle,_=(i=a.EndScrollButtonIcon)!=null?i:hle,b=Qi({elementType:x,externalSlotProps:l.startScrollButtonIcon,additionalProps:{fontSize:"small"},ownerState:g}),y=Qi({elementType:_,externalSlotProps:l.endScrollButtonIcon,additionalProps:{fontSize:"small"},ownerState:g});return C.jsx(Ile,X({component:"div",className:At(v.root,o),ref:n,role:null,ownerState:g,tabIndex:null},f,{children:c==="left"?C.jsx(x,X({},b)):C.jsx(_,X({},y))}))}),kle=Lle;function Ole(t){return bn("MuiTabs",t)}const Nle=pn("MuiTabs",["root","vertical","flexContainer","flexContainerVertical","centered","scroller","fixed","scrollableX","scrollableY","hideScrollbar","scrollButtons","scrollButtonsHideMobile","indicator"]),KE=Nle,Dle=["aria-label","aria-labelledby","action","centered","children","className","component","allowScrollButtonsMobile","indicatorColor","onChange","orientation","ScrollButtonComponent","scrollButtons","selectionFollowsFocus","slots","slotProps","TabIndicatorProps","TabScrollButtonProps","textColor","value","variant","visibleScrollbar"],Pk=(t,e)=>t===e?t.firstChild:e&&e.nextElementSibling?e.nextElementSibling:t.firstChild,Ik=(t,e)=>t===e?t.lastChild:e&&e.previousElementSibling?e.previousElementSibling:t.lastChild,rb=(t,e,n)=>{let r=!1,i=n(t,e);for(;i;){if(i===t.firstChild){if(r)return;r=!0}const s=i.disabled||i.getAttribute("aria-disabled")==="true";if(!i.hasAttribute("tabindex")||s)i=n(t,i);else{i.focus();return}}},Fle=t=>{const{vertical:e,fixed:n,hideScrollbar:r,scrollableX:i,scrollableY:s,centered:o,scrollButtonsHideMobile:a,classes:l}=t;return Sn({root:["root",e&&"vertical"],scroller:["scroller",n&&"fixed",r&&"hideScrollbar",i&&"scrollableX",s&&"scrollableY"],flexContainer:["flexContainer",e&&"flexContainerVertical",o&&"centered"],indicator:["indicator"],scrollButtons:["scrollButtons",a&&"scrollButtonsHideMobile"],scrollableX:[i&&"scrollableX"],hideScrollbar:[r&&"hideScrollbar"]},Ole,l)},Ule=lt("div",{name:"MuiTabs",slot:"Root",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[{[`& .${KE.scrollButtons}`]:e.scrollButtons},{[`& .${KE.scrollButtons}`]:n.scrollButtonsHideMobile&&e.scrollButtonsHideMobile},e.root,n.vertical&&e.vertical]}})(({ownerState:t,theme:e})=>X({overflow:"hidden",minHeight:48,WebkitOverflowScrolling:"touch",display:"flex"},t.vertical&&{flexDirection:"column"},t.scrollButtonsHideMobile&&{[`& .${KE.scrollButtons}`]:{[e.breakpoints.down("sm")]:{display:"none"}}})),zle=lt("div",{name:"MuiTabs",slot:"Scroller",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.scroller,n.fixed&&e.fixed,n.hideScrollbar&&e.hideScrollbar,n.scrollableX&&e.scrollableX,n.scrollableY&&e.scrollableY]}})(({ownerState:t})=>X({position:"relative",display:"inline-block",flex:"1 1 auto",whiteSpace:"nowrap"},t.fixed&&{overflowX:"hidden",width:"100%"},t.hideScrollbar&&{scrollbarWidth:"none","&::-webkit-scrollbar":{display:"none"}},t.scrollableX&&{overflowX:"auto",overflowY:"hidden"},t.scrollableY&&{overflowY:"auto",overflowX:"hidden"})),Ble=lt("div",{name:"MuiTabs",slot:"FlexContainer",overridesResolver:(t,e)=>{const{ownerState:n}=t;return[e.flexContainer,n.vertical&&e.flexContainerVertical,n.centered&&e.centered]}})(({ownerState:t})=>X({display:"flex"},t.vertical&&{flexDirection:"column"},t.centered&&{justifyContent:"center"})),Hle=lt("span",{name:"MuiTabs",slot:"Indicator",overridesResolver:(t,e)=>e.indicator})(({ownerState:t,theme:e})=>X({position:"absolute",height:2,bottom:0,width:"100%",transition:e.transitions.create()},t.indicatorColor==="primary"&&{backgroundColor:(e.vars||e).palette.primary.main},t.indicatorColor==="secondary"&&{backgroundColor:(e.vars||e).palette.secondary.main},t.vertical&&{height:"100%",width:2,right:0})),$le=lt(Ele)({overflowX:"auto",overflowY:"hidden",scrollbarWidth:"none","&::-webkit-scrollbar":{display:"none"}}),Lk={},Vle=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiTabs"}),i=Bu(),s=ex(),{"aria-label":o,"aria-labelledby":a,action:l,centered:c=!1,children:f,className:p,component:g="div",allowScrollButtonsMobile:v=!1,indicatorColor:x="primary",onChange:_,orientation:b="horizontal",ScrollButtonComponent:y=kle,scrollButtons:S="auto",selectionFollowsFocus:w,slots:T={},slotProps:L={},TabIndicatorProps:R={},TabScrollButtonProps:P={},textColor:F="primary",value:O,variant:I="standard",visibleScrollbar:H=!1}=r,Q=Rt(r,Dle),q=I==="scrollable",le=b==="vertical",ie=le?"scrollTop":"scrollLeft",ee=le?"top":"left",ue=le?"bottom":"right",z=le?"clientHeight":"clientWidth",te=le?"height":"width",oe=X({},r,{component:g,allowScrollButtonsMobile:v,indicatorColor:x,orientation:b,vertical:le,scrollButtons:S,textColor:F,variant:I,visibleScrollbar:H,fixed:!q,hideScrollbar:q&&!H,scrollableX:q&&!le,scrollableY:q&&le,centered:c&&!q,scrollButtonsHideMobile:!v}),de=Fle(oe),Ce=Qi({elementType:T.StartScrollButtonIcon,externalSlotProps:L.startScrollButtonIcon,ownerState:oe}),Le=Qi({elementType:T.EndScrollButtonIcon,externalSlotProps:L.endScrollButtonIcon,ownerState:oe}),[V,me]=D.useState(!1),[pe,Se]=D.useState(Lk),[je,it]=D.useState(!1),[xe,et]=D.useState(!1),[Re,Oe]=D.useState(!1),[Te,ze]=D.useState({overflow:"hidden",scrollbarWidth:0}),ke=new Map,rt=D.useRef(null),tt=D.useRef(null),ae=()=>{const qe=rt.current;let ce;if(qe){const fe=qe.getBoundingClientRect();ce={clientWidth:qe.clientWidth,scrollLeft:qe.scrollLeft,scrollTop:qe.scrollTop,scrollLeftNormalized:vK(qe,s?"rtl":"ltr"),scrollWidth:qe.scrollWidth,top:fe.top,bottom:fe.bottom,left:fe.left,right:fe.right}}let Ne;if(qe&&O!==!1){const fe=tt.current.children;if(fe.length>0){const Fe=fe[ke.get(O)];Ne=Fe?Fe.getBoundingClientRect():null}}return{tabsMeta:ce,tabMeta:Ne}},G=ts(()=>{const{tabsMeta:qe,tabMeta:ce}=ae();let Ne=0,fe;if(le)fe="top",ce&&qe&&(Ne=ce.top-qe.top+qe.scrollTop);else if(fe=s?"right":"left",ce&&qe){const He=s?qe.scrollLeftNormalized+qe.clientWidth-qe.scrollWidth:qe.scrollLeft;Ne=(s?-1:1)*(ce[fe]-qe[fe]+He)}const Fe={[fe]:Ne,[te]:ce?ce[te]:0};if(isNaN(pe[fe])||isNaN(pe[te]))Se(Fe);else{const He=Math.abs(pe[fe]-Fe[fe]),ut=Math.abs(pe[te]-Fe[te]);(He>=1||ut>=1)&&Se(Fe)}}),be=(qe,{animation:ce=!0}={})=>{ce?Sle(ie,rt.current,qe,{duration:i.transitions.duration.standard}):rt.current[ie]=qe},$e=qe=>{let ce=rt.current[ie];le?ce+=qe:(ce+=qe*(s?-1:1),ce*=s&&$8()==="reverse"?-1:1),be(ce)},Ze=()=>{const qe=rt.current[z];let ce=0;const Ne=Array.from(tt.current.children);for(let fe=0;feqe){fe===0&&(ce=qe);break}ce+=Fe[z]}return ce},We=()=>{$e(-1*Ze())},Mt=()=>{$e(Ze())},pt=D.useCallback(qe=>{ze({overflow:null,scrollbarWidth:qe})},[]),at=()=>{const qe={};qe.scrollbarSizeListener=q?C.jsx($le,{onChange:pt,className:At(de.scrollableX,de.hideScrollbar)}):null;const Ne=q&&(S==="auto"&&(je||xe)||S===!0);return qe.scrollButtonStart=Ne?C.jsx(y,X({slots:{StartScrollButtonIcon:T.StartScrollButtonIcon},slotProps:{startScrollButtonIcon:Ce},orientation:b,direction:s?"right":"left",onClick:We,disabled:!je},P,{className:At(de.scrollButtons,P.className)})):null,qe.scrollButtonEnd=Ne?C.jsx(y,X({slots:{EndScrollButtonIcon:T.EndScrollButtonIcon},slotProps:{endScrollButtonIcon:Le},orientation:b,direction:s?"left":"right",onClick:Mt,disabled:!xe},P,{className:At(de.scrollButtons,P.className)})):null,qe},Ie=ts(qe=>{const{tabsMeta:ce,tabMeta:Ne}=ae();if(!(!Ne||!ce)){if(Ne[ee]ce[ue]){const fe=ce[ie]+(Ne[ue]-ce[ue]);be(fe,{animation:qe})}}}),ge=ts(()=>{q&&S!==!1&&Oe(!Re)});D.useEffect(()=>{const qe=Qy(()=>{rt.current&&G()});let ce;const Ne=He=>{He.forEach(ut=>{ut.removedNodes.forEach(xt=>{var Xt;(Xt=ce)==null||Xt.unobserve(xt)}),ut.addedNodes.forEach(xt=>{var Xt;(Xt=ce)==null||Xt.observe(xt)})}),qe(),ge()},fe=Oc(rt.current);fe.addEventListener("resize",qe);let Fe;return typeof ResizeObserver<"u"&&(ce=new ResizeObserver(qe),Array.from(tt.current.children).forEach(He=>{ce.observe(He)})),typeof MutationObserver<"u"&&(Fe=new MutationObserver(Ne),Fe.observe(tt.current,{childList:!0})),()=>{var He,ut;qe.clear(),fe.removeEventListener("resize",qe),(He=Fe)==null||He.disconnect(),(ut=ce)==null||ut.disconnect()}},[G,ge]),D.useEffect(()=>{const qe=Array.from(tt.current.children),ce=qe.length;if(typeof IntersectionObserver<"u"&&ce>0&&q&&S!==!1){const Ne=qe[0],fe=qe[ce-1],Fe={root:rt.current,threshold:.99},He=vn=>{it(!vn[0].isIntersecting)},ut=new IntersectionObserver(He,Fe);ut.observe(Ne);const xt=vn=>{et(!vn[0].isIntersecting)},Xt=new IntersectionObserver(xt,Fe);return Xt.observe(fe),()=>{ut.disconnect(),Xt.disconnect()}}},[q,S,Re,f==null?void 0:f.length]),D.useEffect(()=>{me(!0)},[]),D.useEffect(()=>{G()}),D.useEffect(()=>{Ie(Lk!==pe)},[Ie,pe]),D.useImperativeHandle(l,()=>({updateIndicator:G,updateScrollButtons:ge}),[G,ge]);const Xe=C.jsx(Hle,X({},R,{className:At(de.indicator,R.className),ownerState:oe,style:X({},pe,R.style)}));let St=0;const mt=D.Children.map(f,qe=>{if(!D.isValidElement(qe))return null;const ce=qe.props.value===void 0?St:qe.props.value;ke.set(ce,St);const Ne=ce===O;return St+=1,D.cloneElement(qe,X({fullWidth:I==="fullWidth",indicator:Ne&&!V&&Xe,selected:Ne,selectionFollowsFocus:w,onChange:_,textColor:F,value:ce},St===1&&O===!1&&!qe.props.tabIndex?{tabIndex:0}:{}))}),Be=qe=>{const ce=tt.current,Ne=Oi(ce).activeElement;if(Ne.getAttribute("role")!=="tab")return;let Fe=b==="horizontal"?"ArrowLeft":"ArrowUp",He=b==="horizontal"?"ArrowRight":"ArrowDown";switch(b==="horizontal"&&s&&(Fe="ArrowRight",He="ArrowLeft"),qe.key){case Fe:qe.preventDefault(),rb(ce,Ne,Ik);break;case He:qe.preventDefault(),rb(ce,Ne,Pk);break;case"Home":qe.preventDefault(),rb(ce,null,Pk);break;case"End":qe.preventDefault(),rb(ce,null,Ik);break}},vt=at();return C.jsxs(Ule,X({className:At(de.root,p),ownerState:oe,ref:n,as:g},Q,{children:[vt.scrollButtonStart,vt.scrollbarSizeListener,C.jsxs(zle,{className:de.scroller,ownerState:oe,style:{overflow:Te.overflow,[le?`margin${s?"Left":"Right"}`:"marginBottom"]:H?void 0:-Te.scrollbarWidth},ref:rt,children:[C.jsx(Ble,{"aria-label":o,"aria-labelledby":a,"aria-orientation":b==="vertical"?"vertical":null,className:de.flexContainer,ownerState:oe,onKeyDown:Be,ref:tt,role:"tablist",children:mt}),V&&Xe]}),vt.scrollButtonEnd]}))}),Wle=Vle;function jle(t){return bn("MuiTextField",t)}pn("MuiTextField",["root"]);const Gle=["autoComplete","autoFocus","children","className","color","defaultValue","disabled","error","FormHelperTextProps","fullWidth","helperText","id","InputLabelProps","inputProps","InputProps","inputRef","label","maxRows","minRows","multiline","name","onBlur","onChange","onFocus","placeholder","required","rows","select","SelectProps","type","value","variant"],Xle={standard:qw,filled:D7,outlined:RR},qle=t=>{const{classes:e}=t;return Sn({root:["root"]},jle,e)},Zle=lt(Xw,{name:"MuiTextField",slot:"Root",overridesResolver:(t,e)=>e.root})({}),Yle=D.forwardRef(function(e,n){const r=En({props:e,name:"MuiTextField"}),{autoComplete:i,autoFocus:s=!1,children:o,className:a,color:l="primary",defaultValue:c,disabled:f=!1,error:p=!1,FormHelperTextProps:g,fullWidth:v=!1,helperText:x,id:_,InputLabelProps:b,inputProps:y,InputProps:S,inputRef:w,label:T,maxRows:L,minRows:R,multiline:P=!1,name:F,onBlur:O,onChange:I,onFocus:H,placeholder:Q,required:q=!1,rows:le,select:ie=!1,SelectProps:ee,type:ue,value:z,variant:te="outlined"}=r,oe=Rt(r,Gle),de=X({},r,{autoFocus:s,color:l,disabled:f,error:p,fullWidth:v,multiline:P,required:q,select:ie,variant:te}),Ce=qle(de),Le={};te==="outlined"&&(b&&typeof b.shrink<"u"&&(Le.notched=b.shrink),Le.label=T),ie&&((!ee||!ee.native)&&(Le.id=void 0),Le["aria-describedby"]=void 0);const V=hg(_),me=x&&V?`${V}-helper-text`:void 0,pe=T&&V?`${V}-label`:void 0,Se=Xle[te],je=C.jsx(Se,X({"aria-describedby":me,autoComplete:i,autoFocus:s,defaultValue:c,fullWidth:v,multiline:P,name:F,rows:le,maxRows:L,minRows:R,type:ue,value:z,id:V,inputRef:w,onBlur:O,onChange:I,onFocus:H,placeholder:Q,inputProps:y},Le,S));return C.jsxs(Zle,X({className:At(Ce.root,a),disabled:f,error:p,fullWidth:v,ref:n,required:q,color:l,variant:te,ownerState:de},oe,{children:[T!=null&&T!==""&&C.jsx(mse,X({htmlFor:V,id:pe},b,{children:T})),ie?C.jsx(X7,X({"aria-describedby":me,id:V,labelId:pe,value:z,input:je},ee,{children:o})):je,x&&C.jsx(Oie,X({id:me},g,{children:x}))]}))}),yg=Yle,Kle=bt(C.jsx("path",{d:"M20 8h-2.81c-.45-.78-1.07-1.45-1.82-1.96L17 4.41 15.59 3l-2.17 2.17C12.96 5.06 12.49 5 12 5c-.49 0-.96.06-1.41.17L8.41 3 7 4.41l1.62 1.63C7.88 6.55 7.26 7.22 6.81 8H4v2h2.09c-.05.33-.09.66-.09 1v1H4v2h2v1c0 .34.04.67.09 1H4v2h2.81c1.04 1.79 2.97 3 5.19 3s4.15-1.21 5.19-3H20v-2h-2.09c.05-.33.09-.66.09-1v-1h2v-2h-2v-1c0-.34-.04-.67-.09-1H20zm-6 8h-4v-2h4zm0-4h-4v-2h4z"}),"BugReport"),Qle=bt(C.jsx("path",{d:"M15.41 7.41 14 6l-6 6 6 6 1.41-1.41L10.83 12z"}),"ChevronLeft"),Jle=bt(C.jsx("path",{d:"m13.7826 15.1719 2.1213-2.1213 5.9963 5.9962-2.1213 2.1213zM17.5 10c1.93 0 3.5-1.57 3.5-3.5 0-.58-.16-1.12-.41-1.6l-2.7 2.7-1.49-1.49 2.7-2.7c-.48-.25-1.02-.41-1.6-.41C15.57 3 14 4.57 14 6.5c0 .41.08.8.21 1.16l-1.85 1.85-1.78-1.78.71-.71-1.41-1.41L12 3.49c-1.17-1.17-3.07-1.17-4.24 0L4.22 7.03l1.41 1.41H2.81l-.71.71 3.54 3.54.71-.71V9.15l1.41 1.41.71-.71 1.78 1.78-7.41 7.41 2.12 2.12L16.34 9.79c.36.13.75.21 1.16.21"}),"Construction"),ece=bt(C.jsx("path",{d:"M20 2H4c-1.1 0-1.99.9-1.99 2L2 22l4-4h14c1.1 0 2-.9 2-2V4c0-1.1-.9-2-2-2m-7 12h-2v-2h2zm0-4h-2V6h2z"}),"Feedback"),tce=bt([C.jsx("path",{d:"M21 5c-1.11-.35-2.33-.5-3.5-.5-1.95 0-4.05.4-5.5 1.5-1.45-1.1-3.55-1.5-5.5-1.5S2.45 4.9 1 6v14.65c0 .25.25.5.5.5.1 0 .15-.05.25-.05C3.1 20.45 5.05 20 6.5 20c1.95 0 4.05.4 5.5 1.5 1.35-.85 3.8-1.5 5.5-1.5 1.65 0 3.35.3 4.75 1.05.1.05.15.05.25.05.25 0 .5-.25.5-.5V6c-.6-.45-1.25-.75-2-1m0 13.5c-1.1-.35-2.3-.5-3.5-.5-1.7 0-4.15.65-5.5 1.5V8c1.35-.85 3.8-1.5 5.5-1.5 1.2 0 2.4.15 3.5.5z"},"0"),C.jsx("path",{d:"M17.5 10.5c.88 0 1.73.09 2.5.26V9.24c-.79-.15-1.64-.24-2.5-.24-1.7 0-3.24.29-4.5.83v1.66c1.13-.64 2.7-.99 4.5-.99M13 12.49v1.66c1.13-.64 2.7-.99 4.5-.99.88 0 1.73.09 2.5.26V11.9c-.79-.15-1.64-.24-2.5-.24-1.7 0-3.24.3-4.5.83m4.5 1.84c-1.7 0-3.24.29-4.5.83v1.66c1.13-.64 2.7-.99 4.5-.99.88 0 1.73.09 2.5.26v-1.52c-.79-.16-1.64-.24-2.5-.24"},"1")],"MenuBook"),nce=bt(C.jsx("path",{d:"M20 3H4c-1.1 0-2 .9-2 2v11c0 1.1.9 2 2 2h3l-1 1v2h12v-2l-1-1h3c1.1 0 2-.9 2-2V5c0-1.1-.9-2-2-2m0 13H4V5h16z"}),"Monitor"),rce=bt(C.jsx("path",{d:"M11.07 12.85c.77-1.39 2.25-2.21 3.11-3.44.91-1.29.4-3.7-2.18-3.7-1.69 0-2.52 1.28-2.87 2.34L6.54 6.96C7.25 4.83 9.18 3 11.99 3c2.35 0 3.96 1.07 4.78 2.41.7 1.15 1.11 3.3.03 4.9-1.2 1.77-2.35 2.31-2.97 3.45-.25.46-.35.76-.35 2.24h-2.89c-.01-.78-.13-2.05.48-3.15M14 20c0 1.1-.9 2-2 2s-2-.9-2-2 .9-2 2-2 2 .9 2 2"}),"QuestionMark"),ice=bt(C.jsx("path",{d:"M19.14 12.94c.04-.3.06-.61.06-.94 0-.32-.02-.64-.07-.94l2.03-1.58c.18-.14.23-.41.12-.61l-1.92-3.32c-.12-.22-.37-.29-.59-.22l-2.39.96c-.5-.38-1.03-.7-1.62-.94l-.36-2.54c-.04-.24-.24-.41-.48-.41h-3.84c-.24 0-.43.17-.47.41l-.36 2.54c-.59.24-1.13.57-1.62.94l-2.39-.96c-.22-.08-.47 0-.59.22L2.74 8.87c-.12.21-.08.47.12.61l2.03 1.58c-.05.3-.09.63-.09.94s.02.64.07.94l-2.03 1.58c-.18.14-.23.41-.12.61l1.92 3.32c.12.22.37.29.59.22l2.39-.96c.5.38 1.03.7 1.62.94l.36 2.54c.05.24.24.41.48.41h3.84c.24 0 .44-.17.47-.41l.36-2.54c.59-.24 1.13-.56 1.62-.94l2.39.96c.22.08.47 0 .59-.22l1.92-3.32c.12-.22.07-.47-.12-.61zM12 15.6c-1.98 0-3.6-1.62-3.6-3.6s1.62-3.6 3.6-3.6 3.6 1.62 3.6 3.6-1.62 3.6-3.6 3.6"}),"Settings"),sce=bt(C.jsx("path",{d:"M2 20h20v-4H2zm2-3h2v2H4zM2 4v4h20V4zm4 3H4V5h2zm-4 7h20v-4H2zm2-3h2v2H4z"}),"Storage"),oce=bt(C.jsx("path",{d:"M3 17v2h6v-2zM3 5v2h10V5zm10 16v-2h8v-2h-8v-2h-2v6zM7 9v2H3v2h4v2h2V9zm14 4v-2H11v2zm-6-4h2V7h4V5h-4V3h-2z"}),"Tune");function Z7(t,e){return function(){return t.apply(e,arguments)}}const{toString:ace}=Object.prototype,{getPrototypeOf:kR}=Object,Zw=(t=>e=>{const n=ace.call(e);return t[n]||(t[n]=n.slice(8,-1).toLowerCase())})(Object.create(null)),zc=t=>(t=t.toLowerCase(),e=>Zw(e)===t),Yw=t=>e=>typeof e===t,{isArray:xg}=Array,ny=Yw("undefined");function lce(t){return t!==null&&!ny(t)&&t.constructor!==null&&!ny(t.constructor)&&al(t.constructor.isBuffer)&&t.constructor.isBuffer(t)}const Y7=zc("ArrayBuffer");function cce(t){let e;return typeof ArrayBuffer<"u"&&ArrayBuffer.isView?e=ArrayBuffer.isView(t):e=t&&t.buffer&&Y7(t.buffer),e}const uce=Yw("string"),al=Yw("function"),K7=Yw("number"),Kw=t=>t!==null&&typeof t=="object",dce=t=>t===!0||t===!1,CS=t=>{if(Zw(t)!=="object")return!1;const e=kR(t);return(e===null||e===Object.prototype||Object.getPrototypeOf(e)===null)&&!(Symbol.toStringTag in t)&&!(Symbol.iterator in t)},fce=zc("Date"),hce=zc("File"),pce=zc("Blob"),mce=zc("FileList"),gce=t=>Kw(t)&&al(t.pipe),vce=t=>{let e;return t&&(typeof FormData=="function"&&t instanceof FormData||al(t.append)&&((e=Zw(t))==="formdata"||e==="object"&&al(t.toString)&&t.toString()==="[object FormData]"))},yce=zc("URLSearchParams"),xce=t=>t.trim?t.trim():t.replace(/^[\s\uFEFF\xA0]+|[\s\uFEFF\xA0]+$/g,"");function sx(t,e,{allOwnKeys:n=!1}={}){if(t===null||typeof t>"u")return;let r,i;if(typeof t!="object"&&(t=[t]),xg(t))for(r=0,i=t.length;r0;)if(i=n[r],e===i.toLowerCase())return i;return null}const J7=typeof globalThis<"u"?globalThis:typeof self<"u"?self:typeof window<"u"?window:global,e9=t=>!ny(t)&&t!==J7;function DT(){const{caseless:t}=e9(this)&&this||{},e={},n=(r,i)=>{const s=t&&Q7(e,i)||i;CS(e[s])&&CS(r)?e[s]=DT(e[s],r):CS(r)?e[s]=DT({},r):xg(r)?e[s]=r.slice():e[s]=r};for(let r=0,i=arguments.length;r(sx(e,(i,s)=>{n&&al(i)?t[s]=Z7(i,n):t[s]=i},{allOwnKeys:r}),t),bce=t=>(t.charCodeAt(0)===65279&&(t=t.slice(1)),t),Sce=(t,e,n,r)=>{t.prototype=Object.create(e.prototype,r),t.prototype.constructor=t,Object.defineProperty(t,"super",{value:e.prototype}),n&&Object.assign(t.prototype,n)},wce=(t,e,n,r)=>{let i,s,o;const a={};if(e=e||{},t==null)return e;do{for(i=Object.getOwnPropertyNames(t),s=i.length;s-- >0;)o=i[s],(!r||r(o,t,e))&&!a[o]&&(e[o]=t[o],a[o]=!0);t=n!==!1&&kR(t)}while(t&&(!n||n(t,e))&&t!==Object.prototype);return e},Mce=(t,e,n)=>{t=String(t),(n===void 0||n>t.length)&&(n=t.length),n-=e.length;const r=t.indexOf(e,n);return r!==-1&&r===n},Ece=t=>{if(!t)return null;if(xg(t))return t;let e=t.length;if(!K7(e))return null;const n=new Array(e);for(;e-- >0;)n[e]=t[e];return n},Cce=(t=>e=>t&&e instanceof t)(typeof Uint8Array<"u"&&kR(Uint8Array)),Tce=(t,e)=>{const r=(t&&t[Symbol.iterator]).call(t);let i;for(;(i=r.next())&&!i.done;){const s=i.value;e.call(t,s[0],s[1])}},Ace=(t,e)=>{let n;const r=[];for(;(n=t.exec(e))!==null;)r.push(n);return r},Rce=zc("HTMLFormElement"),Pce=t=>t.toLowerCase().replace(/[-_\s]([a-z\d])(\w*)/g,function(n,r,i){return r.toUpperCase()+i}),kk=(({hasOwnProperty:t})=>(e,n)=>t.call(e,n))(Object.prototype),Ice=zc("RegExp"),t9=(t,e)=>{const n=Object.getOwnPropertyDescriptors(t),r={};sx(n,(i,s)=>{let o;(o=e(i,s,t))!==!1&&(r[s]=o||i)}),Object.defineProperties(t,r)},Lce=t=>{t9(t,(e,n)=>{if(al(t)&&["arguments","caller","callee"].indexOf(n)!==-1)return!1;const r=t[n];if(al(r)){if(e.enumerable=!1,"writable"in e){e.writable=!1;return}e.set||(e.set=()=>{throw Error("Can not rewrite read-only method '"+n+"'")})}})},kce=(t,e)=>{const n={},r=i=>{i.forEach(s=>{n[s]=!0})};return xg(t)?r(t):r(String(t).split(e)),n},Oce=()=>{},Nce=(t,e)=>(t=+t,Number.isFinite(t)?t:e),QE="abcdefghijklmnopqrstuvwxyz",Ok="0123456789",n9={DIGIT:Ok,ALPHA:QE,ALPHA_DIGIT:QE+QE.toUpperCase()+Ok},Dce=(t=16,e=n9.ALPHA_DIGIT)=>{let n="";const{length:r}=e;for(;t--;)n+=e[Math.random()*r|0];return n};function Fce(t){return!!(t&&al(t.append)&&t[Symbol.toStringTag]==="FormData"&&t[Symbol.iterator])}const Uce=t=>{const e=new Array(10),n=(r,i)=>{if(Kw(r)){if(e.indexOf(r)>=0)return;if(!("toJSON"in r)){e[i]=r;const s=xg(r)?[]:{};return sx(r,(o,a)=>{const l=n(o,i+1);!ny(l)&&(s[a]=l)}),e[i]=void 0,s}}return r};return n(t,0)},zce=zc("AsyncFunction"),Bce=t=>t&&(Kw(t)||al(t))&&al(t.then)&&al(t.catch),ht={isArray:xg,isArrayBuffer:Y7,isBuffer:lce,isFormData:vce,isArrayBufferView:cce,isString:uce,isNumber:K7,isBoolean:dce,isObject:Kw,isPlainObject:CS,isUndefined:ny,isDate:fce,isFile:hce,isBlob:pce,isRegExp:Ice,isFunction:al,isStream:gce,isURLSearchParams:yce,isTypedArray:Cce,isFileList:mce,forEach:sx,merge:DT,extend:_ce,trim:xce,stripBOM:bce,inherits:Sce,toFlatObject:wce,kindOf:Zw,kindOfTest:zc,endsWith:Mce,toArray:Ece,forEachEntry:Tce,matchAll:Ace,isHTMLForm:Rce,hasOwnProperty:kk,hasOwnProp:kk,reduceDescriptors:t9,freezeMethods:Lce,toObjectSet:kce,toCamelCase:Pce,noop:Oce,toFiniteNumber:Nce,findKey:Q7,global:J7,isContextDefined:e9,ALPHABET:n9,generateString:Dce,isSpecCompliantForm:Fce,toJSONObject:Uce,isAsyncFn:zce,isThenable:Bce};function ar(t,e,n,r,i){Error.call(this),Error.captureStackTrace?Error.captureStackTrace(this,this.constructor):this.stack=new Error().stack,this.message=t,this.name="AxiosError",e&&(this.code=e),n&&(this.config=n),r&&(this.request=r),i&&(this.response=i)}ht.inherits(ar,Error,{toJSON:function(){return{message:this.message,name:this.name,description:this.description,number:this.number,fileName:this.fileName,lineNumber:this.lineNumber,columnNumber:this.columnNumber,stack:this.stack,config:ht.toJSONObject(this.config),code:this.code,status:this.response&&this.response.status?this.response.status:null}}});const r9=ar.prototype,i9={};["ERR_BAD_OPTION_VALUE","ERR_BAD_OPTION","ECONNABORTED","ETIMEDOUT","ERR_NETWORK","ERR_FR_TOO_MANY_REDIRECTS","ERR_DEPRECATED","ERR_BAD_RESPONSE","ERR_BAD_REQUEST","ERR_CANCELED","ERR_NOT_SUPPORT","ERR_INVALID_URL"].forEach(t=>{i9[t]={value:t}});Object.defineProperties(ar,i9);Object.defineProperty(r9,"isAxiosError",{value:!0});ar.from=(t,e,n,r,i,s)=>{const o=Object.create(r9);return ht.toFlatObject(t,o,function(l){return l!==Error.prototype},a=>a!=="isAxiosError"),ar.call(o,t.message,e,n,r,i),o.cause=t,o.name=t.name,s&&Object.assign(o,s),o};const Hce=null;function FT(t){return ht.isPlainObject(t)||ht.isArray(t)}function s9(t){return ht.endsWith(t,"[]")?t.slice(0,-2):t}function Nk(t,e,n){return t?t.concat(e).map(function(i,s){return i=s9(i),!n&&s?"["+i+"]":i}).join(n?".":""):e}function $ce(t){return ht.isArray(t)&&!t.some(FT)}const Vce=ht.toFlatObject(ht,{},null,function(e){return/^is[A-Z]/.test(e)});function Qw(t,e,n){if(!ht.isObject(t))throw new TypeError("target must be an object");e=e||new FormData,n=ht.toFlatObject(n,{metaTokens:!0,dots:!1,indexes:!1},!1,function(_,b){return!ht.isUndefined(b[_])});const r=n.metaTokens,i=n.visitor||f,s=n.dots,o=n.indexes,l=(n.Blob||typeof Blob<"u"&&Blob)&&ht.isSpecCompliantForm(e);if(!ht.isFunction(i))throw new TypeError("visitor must be a function");function c(x){if(x===null)return"";if(ht.isDate(x))return x.toISOString();if(!l&&ht.isBlob(x))throw new ar("Blob is not supported. Use a Buffer instead.");return ht.isArrayBuffer(x)||ht.isTypedArray(x)?l&&typeof Blob=="function"?new Blob([x]):Buffer.from(x):x}function f(x,_,b){let y=x;if(x&&!b&&typeof x=="object"){if(ht.endsWith(_,"{}"))_=r?_:_.slice(0,-2),x=JSON.stringify(x);else if(ht.isArray(x)&&$ce(x)||(ht.isFileList(x)||ht.endsWith(_,"[]"))&&(y=ht.toArray(x)))return _=s9(_),y.forEach(function(w,T){!(ht.isUndefined(w)||w===null)&&e.append(o===!0?Nk([_],T,s):o===null?_:_+"[]",c(w))}),!1}return FT(x)?!0:(e.append(Nk(b,_,s),c(x)),!1)}const p=[],g=Object.assign(Vce,{defaultVisitor:f,convertValue:c,isVisitable:FT});function v(x,_){if(!ht.isUndefined(x)){if(p.indexOf(x)!==-1)throw Error("Circular reference detected in "+_.join("."));p.push(x),ht.forEach(x,function(y,S){(!(ht.isUndefined(y)||y===null)&&i.call(e,y,ht.isString(S)?S.trim():S,_,g))===!0&&v(y,_?_.concat(S):[S])}),p.pop()}}if(!ht.isObject(t))throw new TypeError("data must be an object");return v(t),e}function Dk(t){const e={"!":"%21","'":"%27","(":"%28",")":"%29","~":"%7E","%20":"+","%00":"\0"};return encodeURIComponent(t).replace(/[!'()~]|%20|%00/g,function(r){return e[r]})}function OR(t,e){this._pairs=[],t&&Qw(t,this,e)}const o9=OR.prototype;o9.append=function(e,n){this._pairs.push([e,n])};o9.toString=function(e){const n=e?function(r){return e.call(this,r,Dk)}:Dk;return this._pairs.map(function(i){return n(i[0])+"="+n(i[1])},"").join("&")};function Wce(t){return encodeURIComponent(t).replace(/%3A/gi,":").replace(/%24/g,"$").replace(/%2C/gi,",").replace(/%20/g,"+").replace(/%5B/gi,"[").replace(/%5D/gi,"]")}function a9(t,e,n){if(!e)return t;const r=n&&n.encode||Wce,i=n&&n.serialize;let s;if(i?s=i(e,n):s=ht.isURLSearchParams(e)?e.toString():new OR(e,n).toString(r),s){const o=t.indexOf("#");o!==-1&&(t=t.slice(0,o)),t+=(t.indexOf("?")===-1?"?":"&")+s}return t}class Fk{constructor(){this.handlers=[]}use(e,n,r){return this.handlers.push({fulfilled:e,rejected:n,synchronous:r?r.synchronous:!1,runWhen:r?r.runWhen:null}),this.handlers.length-1}eject(e){this.handlers[e]&&(this.handlers[e]=null)}clear(){this.handlers&&(this.handlers=[])}forEach(e){ht.forEach(this.handlers,function(r){r!==null&&e(r)})}}const l9={silentJSONParsing:!0,forcedJSONParsing:!0,clarifyTimeoutError:!1},jce=typeof URLSearchParams<"u"?URLSearchParams:OR,Gce=typeof FormData<"u"?FormData:null,Xce=typeof Blob<"u"?Blob:null,qce={isBrowser:!0,classes:{URLSearchParams:jce,FormData:Gce,Blob:Xce},protocols:["http","https","file","blob","url","data"]},c9=typeof window<"u"&&typeof document<"u",Zce=(t=>c9&&["ReactNative","NativeScript","NS"].indexOf(t)<0)(typeof navigator<"u"&&navigator.product),Yce=typeof WorkerGlobalScope<"u"&&self instanceof WorkerGlobalScope&&typeof self.importScripts=="function",Kce=Object.freeze(Object.defineProperty({__proto__:null,hasBrowserEnv:c9,hasStandardBrowserEnv:Zce,hasStandardBrowserWebWorkerEnv:Yce},Symbol.toStringTag,{value:"Module"})),Mc={...Kce,...qce};function Qce(t,e){return Qw(t,new Mc.classes.URLSearchParams,Object.assign({visitor:function(n,r,i,s){return Mc.isNode&&ht.isBuffer(n)?(this.append(r,n.toString("base64")),!1):s.defaultVisitor.apply(this,arguments)}},e))}function Jce(t){return ht.matchAll(/\w+|\[(\w*)]/g,t).map(e=>e[0]==="[]"?"":e[1]||e[0])}function eue(t){const e={},n=Object.keys(t);let r;const i=n.length;let s;for(r=0;r=n.length;return o=!o&&ht.isArray(i)?i.length:o,l?(ht.hasOwnProp(i,o)?i[o]=[i[o],r]:i[o]=r,!a):((!i[o]||!ht.isObject(i[o]))&&(i[o]=[]),e(n,r,i[o],s)&&ht.isArray(i[o])&&(i[o]=eue(i[o])),!a)}if(ht.isFormData(t)&&ht.isFunction(t.entries)){const n={};return ht.forEachEntry(t,(r,i)=>{e(Jce(r),i,n,0)}),n}return null}function tue(t,e,n){if(ht.isString(t))try{return(e||JSON.parse)(t),ht.trim(t)}catch(r){if(r.name!=="SyntaxError")throw r}return(n||JSON.stringify)(t)}const NR={transitional:l9,adapter:["xhr","http"],transformRequest:[function(e,n){const r=n.getContentType()||"",i=r.indexOf("application/json")>-1,s=ht.isObject(e);if(s&&ht.isHTMLForm(e)&&(e=new FormData(e)),ht.isFormData(e))return i?JSON.stringify(u9(e)):e;if(ht.isArrayBuffer(e)||ht.isBuffer(e)||ht.isStream(e)||ht.isFile(e)||ht.isBlob(e))return e;if(ht.isArrayBufferView(e))return e.buffer;if(ht.isURLSearchParams(e))return n.setContentType("application/x-www-form-urlencoded;charset=utf-8",!1),e.toString();let a;if(s){if(r.indexOf("application/x-www-form-urlencoded")>-1)return Qce(e,this.formSerializer).toString();if((a=ht.isFileList(e))||r.indexOf("multipart/form-data")>-1){const l=this.env&&this.env.FormData;return Qw(a?{"files[]":e}:e,l&&new l,this.formSerializer)}}return s||i?(n.setContentType("application/json",!1),tue(e)):e}],transformResponse:[function(e){const n=this.transitional||NR.transitional,r=n&&n.forcedJSONParsing,i=this.responseType==="json";if(e&&ht.isString(e)&&(r&&!this.responseType||i)){const o=!(n&&n.silentJSONParsing)&&i;try{return JSON.parse(e)}catch(a){if(o)throw a.name==="SyntaxError"?ar.from(a,ar.ERR_BAD_RESPONSE,this,null,this.response):a}}return e}],timeout:0,xsrfCookieName:"XSRF-TOKEN",xsrfHeaderName:"X-XSRF-TOKEN",maxContentLength:-1,maxBodyLength:-1,env:{FormData:Mc.classes.FormData,Blob:Mc.classes.Blob},validateStatus:function(e){return e>=200&&e<300},headers:{common:{Accept:"application/json, text/plain, */*","Content-Type":void 0}}};ht.forEach(["delete","get","head","post","put","patch"],t=>{NR.headers[t]={}});const DR=NR,nue=ht.toObjectSet(["age","authorization","content-length","content-type","etag","expires","from","host","if-modified-since","if-unmodified-since","last-modified","location","max-forwards","proxy-authorization","referer","retry-after","user-agent"]),rue=t=>{const e={};let n,r,i;return t&&t.split(`
+`).forEach(function(o){i=o.indexOf(":"),n=o.substring(0,i).trim().toLowerCase(),r=o.substring(i+1).trim(),!(!n||e[n]&&nue[n])&&(n==="set-cookie"?e[n]?e[n].push(r):e[n]=[r]:e[n]=e[n]?e[n]+", "+r:r)}),e},Uk=Symbol("internals");function P1(t){return t&&String(t).trim().toLowerCase()}function TS(t){return t===!1||t==null?t:ht.isArray(t)?t.map(TS):String(t)}function iue(t){const e=Object.create(null),n=/([^\s,;=]+)\s*(?:=\s*([^,;]+))?/g;let r;for(;r=n.exec(t);)e[r[1]]=r[2];return e}const sue=t=>/^[-_a-zA-Z0-9^`|~,!#$%&'*+.]+$/.test(t.trim());function JE(t,e,n,r,i){if(ht.isFunction(r))return r.call(this,e,n);if(i&&(e=n),!!ht.isString(e)){if(ht.isString(r))return e.indexOf(r)!==-1;if(ht.isRegExp(r))return r.test(e)}}function oue(t){return t.trim().toLowerCase().replace(/([a-z\d])(\w*)/g,(e,n,r)=>n.toUpperCase()+r)}function aue(t,e){const n=ht.toCamelCase(" "+e);["get","set","has"].forEach(r=>{Object.defineProperty(t,r+n,{value:function(i,s,o){return this[r].call(this,e,i,s,o)},configurable:!0})})}let Jw=class{constructor(e){e&&this.set(e)}set(e,n,r){const i=this;function s(a,l,c){const f=P1(l);if(!f)throw new Error("header name must be a non-empty string");const p=ht.findKey(i,f);(!p||i[p]===void 0||c===!0||c===void 0&&i[p]!==!1)&&(i[p||l]=TS(a))}const o=(a,l)=>ht.forEach(a,(c,f)=>s(c,f,l));return ht.isPlainObject(e)||e instanceof this.constructor?o(e,n):ht.isString(e)&&(e=e.trim())&&!sue(e)?o(rue(e),n):e!=null&&s(n,e,r),this}get(e,n){if(e=P1(e),e){const r=ht.findKey(this,e);if(r){const i=this[r];if(!n)return i;if(n===!0)return iue(i);if(ht.isFunction(n))return n.call(this,i,r);if(ht.isRegExp(n))return n.exec(i);throw new TypeError("parser must be boolean|regexp|function")}}}has(e,n){if(e=P1(e),e){const r=ht.findKey(this,e);return!!(r&&this[r]!==void 0&&(!n||JE(this,this[r],r,n)))}return!1}delete(e,n){const r=this;let i=!1;function s(o){if(o=P1(o),o){const a=ht.findKey(r,o);a&&(!n||JE(r,r[a],a,n))&&(delete r[a],i=!0)}}return ht.isArray(e)?e.forEach(s):s(e),i}clear(e){const n=Object.keys(this);let r=n.length,i=!1;for(;r--;){const s=n[r];(!e||JE(this,this[s],s,e,!0))&&(delete this[s],i=!0)}return i}normalize(e){const n=this,r={};return ht.forEach(this,(i,s)=>{const o=ht.findKey(r,s);if(o){n[o]=TS(i),delete n[s];return}const a=e?oue(s):String(s).trim();a!==s&&delete n[s],n[a]=TS(i),r[a]=!0}),this}concat(...e){return this.constructor.concat(this,...e)}toJSON(e){const n=Object.create(null);return ht.forEach(this,(r,i)=>{r!=null&&r!==!1&&(n[i]=e&&ht.isArray(r)?r.join(", "):r)}),n}[Symbol.iterator](){return Object.entries(this.toJSON())[Symbol.iterator]()}toString(){return Object.entries(this.toJSON()).map(([e,n])=>e+": "+n).join(`
+`)}get[Symbol.toStringTag](){return"AxiosHeaders"}static from(e){return e instanceof this?e:new this(e)}static concat(e,...n){const r=new this(e);return n.forEach(i=>r.set(i)),r}static accessor(e){const r=(this[Uk]=this[Uk]={accessors:{}}).accessors,i=this.prototype;function s(o){const a=P1(o);r[a]||(aue(i,o),r[a]=!0)}return ht.isArray(e)?e.forEach(s):s(e),this}};Jw.accessor(["Content-Type","Content-Length","Accept","Accept-Encoding","User-Agent","Authorization"]);ht.reduceDescriptors(Jw.prototype,({value:t},e)=>{let n=e[0].toUpperCase()+e.slice(1);return{get:()=>t,set(r){this[n]=r}}});ht.freezeMethods(Jw);const Ru=Jw;function e5(t,e){const n=this||DR,r=e||n,i=Ru.from(r.headers);let s=r.data;return ht.forEach(t,function(a){s=a.call(n,s,i.normalize(),e?e.status:void 0)}),i.normalize(),s}function d9(t){return!!(t&&t.__CANCEL__)}function ox(t,e,n){ar.call(this,t??"canceled",ar.ERR_CANCELED,e,n),this.name="CanceledError"}ht.inherits(ox,ar,{__CANCEL__:!0});function lue(t,e,n){const r=n.config.validateStatus;!n.status||!r||r(n.status)?t(n):e(new ar("Request failed with status code "+n.status,[ar.ERR_BAD_REQUEST,ar.ERR_BAD_RESPONSE][Math.floor(n.status/100)-4],n.config,n.request,n))}const cue=Mc.hasStandardBrowserEnv?{write(t,e,n,r,i,s){const o=[t+"="+encodeURIComponent(e)];ht.isNumber(n)&&o.push("expires="+new Date(n).toGMTString()),ht.isString(r)&&o.push("path="+r),ht.isString(i)&&o.push("domain="+i),s===!0&&o.push("secure"),document.cookie=o.join("; ")},read(t){const e=document.cookie.match(new RegExp("(^|;\\s*)("+t+")=([^;]*)"));return e?decodeURIComponent(e[3]):null},remove(t){this.write(t,"",Date.now()-864e5)}}:{write(){},read(){return null},remove(){}};function uue(t){return/^([a-z][a-z\d+\-.]*:)?\/\//i.test(t)}function due(t,e){return e?t.replace(/\/?\/$/,"")+"/"+e.replace(/^\/+/,""):t}function f9(t,e){return t&&!uue(e)?due(t,e):e}const fue=Mc.hasStandardBrowserEnv?function(){const e=/(msie|trident)/i.test(navigator.userAgent),n=document.createElement("a");let r;function i(s){let o=s;return e&&(n.setAttribute("href",o),o=n.href),n.setAttribute("href",o),{href:n.href,protocol:n.protocol?n.protocol.replace(/:$/,""):"",host:n.host,search:n.search?n.search.replace(/^\?/,""):"",hash:n.hash?n.hash.replace(/^#/,""):"",hostname:n.hostname,port:n.port,pathname:n.pathname.charAt(0)==="/"?n.pathname:"/"+n.pathname}}return r=i(window.location.href),function(o){const a=ht.isString(o)?i(o):o;return a.protocol===r.protocol&&a.host===r.host}}():function(){return function(){return!0}}();function hue(t){const e=/^([-+\w]{1,25})(:?\/\/|:)/.exec(t);return e&&e[1]||""}function pue(t,e){t=t||10;const n=new Array(t),r=new Array(t);let i=0,s=0,o;return e=e!==void 0?e:1e3,function(l){const c=Date.now(),f=r[s];o||(o=c),n[i]=l,r[i]=c;let p=s,g=0;for(;p!==i;)g+=n[p++],p=p%t;if(i=(i+1)%t,i===s&&(s=(s+1)%t),c-o{const s=i.loaded,o=i.lengthComputable?i.total:void 0,a=s-n,l=r(a),c=s<=o;n=s;const f={loaded:s,total:o,progress:o?s/o:void 0,bytes:a,rate:l||void 0,estimated:l&&o&&c?(o-s)/l:void 0,event:i};f[e?"download":"upload"]=!0,t(f)}}const mue=typeof XMLHttpRequest<"u",gue=mue&&function(t){return new Promise(function(n,r){let i=t.data;const s=Ru.from(t.headers).normalize();let{responseType:o,withXSRFToken:a}=t,l;function c(){t.cancelToken&&t.cancelToken.unsubscribe(l),t.signal&&t.signal.removeEventListener("abort",l)}let f;if(ht.isFormData(i)){if(Mc.hasStandardBrowserEnv||Mc.hasStandardBrowserWebWorkerEnv)s.setContentType(!1);else if((f=s.getContentType())!==!1){const[_,...b]=f?f.split(";").map(y=>y.trim()).filter(Boolean):[];s.setContentType([_||"multipart/form-data",...b].join("; "))}}let p=new XMLHttpRequest;if(t.auth){const _=t.auth.username||"",b=t.auth.password?unescape(encodeURIComponent(t.auth.password)):"";s.set("Authorization","Basic "+btoa(_+":"+b))}const g=f9(t.baseURL,t.url);p.open(t.method.toUpperCase(),a9(g,t.params,t.paramsSerializer),!0),p.timeout=t.timeout;function v(){if(!p)return;const _=Ru.from("getAllResponseHeaders"in p&&p.getAllResponseHeaders()),y={data:!o||o==="text"||o==="json"?p.responseText:p.response,status:p.status,statusText:p.statusText,headers:_,config:t,request:p};lue(function(w){n(w),c()},function(w){r(w),c()},y),p=null}if("onloadend"in p?p.onloadend=v:p.onreadystatechange=function(){!p||p.readyState!==4||p.status===0&&!(p.responseURL&&p.responseURL.indexOf("file:")===0)||setTimeout(v)},p.onabort=function(){p&&(r(new ar("Request aborted",ar.ECONNABORTED,t,p)),p=null)},p.onerror=function(){r(new ar("Network Error",ar.ERR_NETWORK,t,p)),p=null},p.ontimeout=function(){let b=t.timeout?"timeout of "+t.timeout+"ms exceeded":"timeout exceeded";const y=t.transitional||l9;t.timeoutErrorMessage&&(b=t.timeoutErrorMessage),r(new ar(b,y.clarifyTimeoutError?ar.ETIMEDOUT:ar.ECONNABORTED,t,p)),p=null},Mc.hasStandardBrowserEnv&&(a&&ht.isFunction(a)&&(a=a(t)),a||a!==!1&&fue(g))){const _=t.xsrfHeaderName&&t.xsrfCookieName&&cue.read(t.xsrfCookieName);_&&s.set(t.xsrfHeaderName,_)}i===void 0&&s.setContentType(null),"setRequestHeader"in p&&ht.forEach(s.toJSON(),function(b,y){p.setRequestHeader(y,b)}),ht.isUndefined(t.withCredentials)||(p.withCredentials=!!t.withCredentials),o&&o!=="json"&&(p.responseType=t.responseType),typeof t.onDownloadProgress=="function"&&p.addEventListener("progress",zk(t.onDownloadProgress,!0)),typeof t.onUploadProgress=="function"&&p.upload&&p.upload.addEventListener("progress",zk(t.onUploadProgress)),(t.cancelToken||t.signal)&&(l=_=>{p&&(r(!_||_.type?new ox(null,t,p):_),p.abort(),p=null)},t.cancelToken&&t.cancelToken.subscribe(l),t.signal&&(t.signal.aborted?l():t.signal.addEventListener("abort",l)));const x=hue(g);if(x&&Mc.protocols.indexOf(x)===-1){r(new ar("Unsupported protocol "+x+":",ar.ERR_BAD_REQUEST,t));return}p.send(i||null)})},UT={http:Hce,xhr:gue};ht.forEach(UT,(t,e)=>{if(t){try{Object.defineProperty(t,"name",{value:e})}catch{}Object.defineProperty(t,"adapterName",{value:e})}});const Bk=t=>`- ${t}`,vue=t=>ht.isFunction(t)||t===null||t===!1,h9={getAdapter:t=>{t=ht.isArray(t)?t:[t];const{length:e}=t;let n,r;const i={};for(let s=0;s`adapter ${a} `+(l===!1?"is not supported by the environment":"is not available in the build"));let o=e?s.length>1?`since :
+`+s.map(Bk).join(`
+`):" "+Bk(s[0]):"as no adapter specified";throw new ar("There is no suitable adapter to dispatch the request "+o,"ERR_NOT_SUPPORT")}return r},adapters:UT};function t5(t){if(t.cancelToken&&t.cancelToken.throwIfRequested(),t.signal&&t.signal.aborted)throw new ox(null,t)}function Hk(t){return t5(t),t.headers=Ru.from(t.headers),t.data=e5.call(t,t.transformRequest),["post","put","patch"].indexOf(t.method)!==-1&&t.headers.setContentType("application/x-www-form-urlencoded",!1),h9.getAdapter(t.adapter||DR.adapter)(t).then(function(r){return t5(t),r.data=e5.call(t,t.transformResponse,r),r.headers=Ru.from(r.headers),r},function(r){return d9(r)||(t5(t),r&&r.response&&(r.response.data=e5.call(t,t.transformResponse,r.response),r.response.headers=Ru.from(r.response.headers))),Promise.reject(r)})}const $k=t=>t instanceof Ru?{...t}:t;function Y0(t,e){e=e||{};const n={};function r(c,f,p){return ht.isPlainObject(c)&&ht.isPlainObject(f)?ht.merge.call({caseless:p},c,f):ht.isPlainObject(f)?ht.merge({},f):ht.isArray(f)?f.slice():f}function i(c,f,p){if(ht.isUndefined(f)){if(!ht.isUndefined(c))return r(void 0,c,p)}else return r(c,f,p)}function s(c,f){if(!ht.isUndefined(f))return r(void 0,f)}function o(c,f){if(ht.isUndefined(f)){if(!ht.isUndefined(c))return r(void 0,c)}else return r(void 0,f)}function a(c,f,p){if(p in e)return r(c,f);if(p in t)return r(void 0,c)}const l={url:s,method:s,data:s,baseURL:o,transformRequest:o,transformResponse:o,paramsSerializer:o,timeout:o,timeoutMessage:o,withCredentials:o,withXSRFToken:o,adapter:o,responseType:o,xsrfCookieName:o,xsrfHeaderName:o,onUploadProgress:o,onDownloadProgress:o,decompress:o,maxContentLength:o,maxBodyLength:o,beforeRedirect:o,transport:o,httpAgent:o,httpsAgent:o,cancelToken:o,socketPath:o,responseEncoding:o,validateStatus:a,headers:(c,f)=>i($k(c),$k(f),!0)};return ht.forEach(Object.keys(Object.assign({},t,e)),function(f){const p=l[f]||i,g=p(t[f],e[f],f);ht.isUndefined(g)&&p!==a||(n[f]=g)}),n}const p9="1.6.8",FR={};["object","boolean","number","function","string","symbol"].forEach((t,e)=>{FR[t]=function(r){return typeof r===t||"a"+(e<1?"n ":" ")+t}});const Vk={};FR.transitional=function(e,n,r){function i(s,o){return"[Axios v"+p9+"] Transitional option '"+s+"'"+o+(r?". "+r:"")}return(s,o,a)=>{if(e===!1)throw new ar(i(o," has been removed"+(n?" in "+n:"")),ar.ERR_DEPRECATED);return n&&!Vk[o]&&(Vk[o]=!0,console.warn(i(o," has been deprecated since v"+n+" and will be removed in the near future"))),e?e(s,o,a):!0}};function yue(t,e,n){if(typeof t!="object")throw new ar("options must be an object",ar.ERR_BAD_OPTION_VALUE);const r=Object.keys(t);let i=r.length;for(;i-- >0;){const s=r[i],o=e[s];if(o){const a=t[s],l=a===void 0||o(a,s,t);if(l!==!0)throw new ar("option "+s+" must be "+l,ar.ERR_BAD_OPTION_VALUE);continue}if(n!==!0)throw new ar("Unknown option "+s,ar.ERR_BAD_OPTION)}}const zT={assertOptions:yue,validators:FR},wd=zT.validators;let v2=class{constructor(e){this.defaults=e,this.interceptors={request:new Fk,response:new Fk}}async request(e,n){try{return await this._request(e,n)}catch(r){if(r instanceof Error){let i;Error.captureStackTrace?Error.captureStackTrace(i={}):i=new Error;const s=i.stack?i.stack.replace(/^.+\n/,""):"";r.stack?s&&!String(r.stack).endsWith(s.replace(/^.+\n.+\n/,""))&&(r.stack+=`
+`+s):r.stack=s}throw r}}_request(e,n){typeof e=="string"?(n=n||{},n.url=e):n=e||{},n=Y0(this.defaults,n);const{transitional:r,paramsSerializer:i,headers:s}=n;r!==void 0&&zT.assertOptions(r,{silentJSONParsing:wd.transitional(wd.boolean),forcedJSONParsing:wd.transitional(wd.boolean),clarifyTimeoutError:wd.transitional(wd.boolean)},!1),i!=null&&(ht.isFunction(i)?n.paramsSerializer={serialize:i}:zT.assertOptions(i,{encode:wd.function,serialize:wd.function},!0)),n.method=(n.method||this.defaults.method||"get").toLowerCase();let o=s&&ht.merge(s.common,s[n.method]);s&&ht.forEach(["delete","get","head","post","put","patch","common"],x=>{delete s[x]}),n.headers=Ru.concat(o,s);const a=[];let l=!0;this.interceptors.request.forEach(function(_){typeof _.runWhen=="function"&&_.runWhen(n)===!1||(l=l&&_.synchronous,a.unshift(_.fulfilled,_.rejected))});const c=[];this.interceptors.response.forEach(function(_){c.push(_.fulfilled,_.rejected)});let f,p=0,g;if(!l){const x=[Hk.bind(this),void 0];for(x.unshift.apply(x,a),x.push.apply(x,c),g=x.length,f=Promise.resolve(n);p{if(!r._listeners)return;let s=r._listeners.length;for(;s-- >0;)r._listeners[s](i);r._listeners=null}),this.promise.then=i=>{let s;const o=new Promise(a=>{r.subscribe(a),s=a}).then(i);return o.cancel=function(){r.unsubscribe(s)},o},e(function(s,o,a){r.reason||(r.reason=new ox(s,o,a),n(r.reason))})}throwIfRequested(){if(this.reason)throw this.reason}subscribe(e){if(this.reason){e(this.reason);return}this._listeners?this._listeners.push(e):this._listeners=[e]}unsubscribe(e){if(!this._listeners)return;const n=this._listeners.indexOf(e);n!==-1&&this._listeners.splice(n,1)}static source(){let e;return{token:new m9(function(i){e=i}),cancel:e}}};const _ue=xue;function bue(t){return function(n){return t.apply(null,n)}}function Sue(t){return ht.isObject(t)&&t.isAxiosError===!0}const BT={Continue:100,SwitchingProtocols:101,Processing:102,EarlyHints:103,Ok:200,Created:201,Accepted:202,NonAuthoritativeInformation:203,NoContent:204,ResetContent:205,PartialContent:206,MultiStatus:207,AlreadyReported:208,ImUsed:226,MultipleChoices:300,MovedPermanently:301,Found:302,SeeOther:303,NotModified:304,UseProxy:305,Unused:306,TemporaryRedirect:307,PermanentRedirect:308,BadRequest:400,Unauthorized:401,PaymentRequired:402,Forbidden:403,NotFound:404,MethodNotAllowed:405,NotAcceptable:406,ProxyAuthenticationRequired:407,RequestTimeout:408,Conflict:409,Gone:410,LengthRequired:411,PreconditionFailed:412,PayloadTooLarge:413,UriTooLong:414,UnsupportedMediaType:415,RangeNotSatisfiable:416,ExpectationFailed:417,ImATeapot:418,MisdirectedRequest:421,UnprocessableEntity:422,Locked:423,FailedDependency:424,TooEarly:425,UpgradeRequired:426,PreconditionRequired:428,TooManyRequests:429,RequestHeaderFieldsTooLarge:431,UnavailableForLegalReasons:451,InternalServerError:500,NotImplemented:501,BadGateway:502,ServiceUnavailable:503,GatewayTimeout:504,HttpVersionNotSupported:505,VariantAlsoNegotiates:506,InsufficientStorage:507,LoopDetected:508,NotExtended:510,NetworkAuthenticationRequired:511};Object.entries(BT).forEach(([t,e])=>{BT[e]=t});const wue=BT;function g9(t){const e=new AS(t),n=Z7(AS.prototype.request,e);return ht.extend(n,AS.prototype,e,{allOwnKeys:!0}),ht.extend(n,e,null,{allOwnKeys:!0}),n.create=function(i){return g9(Y0(t,i))},n}const Yn=g9(DR);Yn.Axios=AS;Yn.CanceledError=ox;Yn.CancelToken=_ue;Yn.isCancel=d9;Yn.VERSION=p9;Yn.toFormData=Qw;Yn.AxiosError=ar;Yn.Cancel=Yn.CanceledError;Yn.all=function(e){return Promise.all(e)};Yn.spread=bue;Yn.isAxiosError=Sue;Yn.mergeConfig=Y0;Yn.AxiosHeaders=Ru;Yn.formToJSON=t=>u9(ht.isHTMLForm(t)?new FormData(t):t);Yn.getAdapter=h9.getAdapter;Yn.HttpStatusCode=wue;Yn.default=Yn;const{Axios:ube,AxiosError:Mue,CanceledError:dbe,isCancel:fbe,CancelToken:hbe,VERSION:pbe,all:mbe,Cancel:gbe,isAxiosError:vbe,spread:ybe,toFormData:xbe,AxiosHeaders:_be,HttpStatusCode:bbe,formToJSON:Sbe,getAdapter:wbe,mergeConfig:Mbe}=Yn;function v9(t){var e,n,r="";if(typeof t=="string"||typeof t=="number")r+=t;else if(typeof t=="object")if(Array.isArray(t))for(e=0;etypeof window=="object"?((t?t.querySelector("#_goober"):window._goober)||Object.assign((t||document.head).appendChild(document.createElement("style")),{innerHTML:" ",id:"_goober"})).firstChild:t||Eue,Tue=/(?:([\u0080-\uFFFF\w-%@]+) *:? *([^{;]+?);|([^;}{]*?) *{)|(}\s*)/g,Aue=/\/\*[^]*?\*\/| +/g,Wk=/\n+/g,wh=(t,e)=>{let n="",r="",i="";for(let s in t){let o=t[s];s[0]=="@"?s[1]=="i"?n=s+" "+o+";":r+=s[1]=="f"?wh(o,s):s+"{"+wh(o,s[1]=="k"?"":e)+"}":typeof o=="object"?r+=wh(o,e?e.replace(/([^,])+/g,a=>s.replace(/(^:.*)|([^,])+/g,l=>/&/.test(l)?l.replace(/&/g,a):a?a+" "+l:l)):s):o!=null&&(s=/^--/.test(s)?s:s.replace(/[A-Z]/g,"-$&").toLowerCase(),i+=wh.p?wh.p(s,o):s+":"+o+";")}return n+(e&&i?e+"{"+i+"}":i)+r},su={},y9=t=>{if(typeof t=="object"){let e="";for(let n in t)e+=n+y9(t[n]);return e}return t},Rue=(t,e,n,r,i)=>{let s=y9(t),o=su[s]||(su[s]=(l=>{let c=0,f=11;for(;c>>0;return"go"+f})(s));if(!su[o]){let l=s!==t?t:(c=>{let f,p,g=[{}];for(;f=Tue.exec(c.replace(Aue,""));)f[4]?g.shift():f[3]?(p=f[3].replace(Wk," ").trim(),g.unshift(g[0][p]=g[0][p]||{})):g[0][f[1]]=f[2].replace(Wk," ").trim();return g[0]})(t);su[o]=wh(i?{["@keyframes "+o]:l}:l,n?"":"."+o)}let a=n&&su.g?su.g:null;return n&&(su.g=su[o]),((l,c,f,p)=>{p?c.data=c.data.replace(p,l):c.data.indexOf(l)===-1&&(c.data=f?l+c.data:c.data+l)})(su[o],e,r,a),o},Pue=(t,e,n)=>t.reduce((r,i,s)=>{let o=e[s];if(o&&o.call){let a=o(n),l=a&&a.props&&a.props.className||/^go/.test(a)&&a;o=l?"."+l:a&&typeof a=="object"?a.props?"":wh(a,""):a===!1?"":a}return r+i+(o??"")},"");function UR(t){let e=this||{},n=t.call?t(e.p):t;return Rue(n.unshift?n.raw?Pue(n,[].slice.call(arguments,1),e.p):n.reduce((r,i)=>Object.assign(r,i&&i.call?i(e.p):i),{}):n,Cue(e.target),e.g,e.o,e.k)}UR.bind({g:1});UR.bind({k:1});function jk(t,e){for(var n=0;n=0)&&(n[i]=t[i]);return n}function Gk(t){if(t===void 0)throw new ReferenceError("this hasn't been initialised - super() hasn't been called");return t}var Xk=function(){return""},b9=Zt.createContext({enqueueSnackbar:Xk,closeSnackbar:Xk}),vh={downXs:"@media (max-width:599.95px)",upSm:"@media (min-width:600px)"},qk=function(e){return e.charAt(0).toUpperCase()+e.slice(1)},zR=function(e){return""+qk(e.vertical)+qk(e.horizontal)},ib=function(e){return!!e||e===0},sb="unmounted",mm="exited",gm="entering",I1="entered",Zk="exiting",BR=function(t){_9(e,t);function e(r){var i;i=t.call(this,r)||this;var s=r.appear,o;return i.appearStatus=null,r.in?s?(o=mm,i.appearStatus=gm):o=I1:r.unmountOnExit||r.mountOnEnter?o=sb:o=mm,i.state={status:o},i.nextCallback=null,i}e.getDerivedStateFromProps=function(i,s){var o=i.in;return o&&s.status===sb?{status:mm}:null};var n=e.prototype;return n.componentDidMount=function(){this.updateStatus(!0,this.appearStatus)},n.componentDidUpdate=function(i){var s=null;if(i!==this.props){var o=this.state.status;this.props.in?o!==gm&&o!==I1&&(s=gm):(o===gm||o===I1)&&(s=Zk)}this.updateStatus(!1,s)},n.componentWillUnmount=function(){this.cancelNextCallback()},n.getTimeouts=function(){var i=this.props.timeout,s=i,o=i;return i!=null&&typeof i!="number"&&typeof i!="string"&&(o=i.exit,s=i.enter),{exit:o,enter:s}},n.updateStatus=function(i,s){i===void 0&&(i=!1),s!==null?(this.cancelNextCallback(),s===gm?this.performEnter(i):this.performExit()):this.props.unmountOnExit&&this.state.status===mm&&this.setState({status:sb})},n.performEnter=function(i){var s=this,o=this.props.enter,a=i,l=this.getTimeouts();if(!i&&!o){this.safeSetState({status:I1},function(){s.props.onEntered&&s.props.onEntered(s.node,a)});return}this.props.onEnter&&this.props.onEnter(this.node,a),this.safeSetState({status:gm},function(){s.props.onEntering&&s.props.onEntering(s.node,a),s.onTransitionEnd(l.enter,function(){s.safeSetState({status:I1},function(){s.props.onEntered&&s.props.onEntered(s.node,a)})})})},n.performExit=function(){var i=this,s=this.props.exit,o=this.getTimeouts();if(!s){this.safeSetState({status:mm},function(){i.props.onExited&&i.props.onExited(i.node)});return}this.props.onExit&&this.props.onExit(this.node),this.safeSetState({status:Zk},function(){i.props.onExiting&&i.props.onExiting(i.node),i.onTransitionEnd(o.exit,function(){i.safeSetState({status:mm},function(){i.props.onExited&&i.props.onExited(i.node)})})})},n.cancelNextCallback=function(){this.nextCallback!==null&&this.nextCallback.cancel&&(this.nextCallback.cancel(),this.nextCallback=null)},n.safeSetState=function(i,s){s=this.setNextCallback(s),this.setState(i,s)},n.setNextCallback=function(i){var s=this,o=!0;return this.nextCallback=function(){o&&(o=!1,s.nextCallback=null,i())},this.nextCallback.cancel=function(){o=!1},this.nextCallback},n.onTransitionEnd=function(i,s){this.setNextCallback(s);var o=i==null&&!this.props.addEndListener;if(!this.node||o){setTimeout(this.nextCallback,0);return}this.props.addEndListener&&this.props.addEndListener(this.node,this.nextCallback),i!=null&&setTimeout(this.nextCallback,i)},n.render=function(){var i=this.state.status;if(i===sb)return null;var s=this.props,o=s.children,a=ax(s,["children","in","mountOnEnter","unmountOnExit","appear","enter","exit","timeout","addEndListener","onEnter","onEntering","onEntered","onExit","onExiting","onExited","nodeRef"]);return o(i,a)},x9(e,[{key:"node",get:function(){var i,s=(i=this.props.nodeRef)===null||i===void 0?void 0:i.current;if(!s)throw new Error("notistack - Custom snackbar is not refForwarding");return s}}]),e}(Zt.Component);function vm(){}BR.defaultProps={in:!1,mountOnEnter:!1,unmountOnExit:!1,appear:!1,enter:!0,exit:!0,onEnter:vm,onEntering:vm,onEntered:vm,onExit:vm,onExiting:vm,onExited:vm};function Yk(t,e){typeof t=="function"?t(e):t&&(t.current=e)}function HT(t,e){return D.useMemo(function(){return t==null&&e==null?null:function(n){Yk(t,n),Yk(e,n)}},[t,e])}function y2(t){var e=t.timeout,n=t.style,r=n===void 0?{}:n,i=t.mode;return{duration:typeof e=="object"?e[i]||0:e,easing:r.transitionTimingFunction,delay:r.transitionDelay}}var $T={easeInOut:"cubic-bezier(0.4, 0, 0.2, 1)",easeOut:"cubic-bezier(0.0, 0, 0.2, 1)",easeIn:"cubic-bezier(0.4, 0, 1, 1)",sharp:"cubic-bezier(0.4, 0, 0.6, 1)"},S9=function(e){e.scrollTop=e.scrollTop},Kk=function(e){return Math.round(e)+"ms"};function o0(t,e){t===void 0&&(t=["all"]);var n=e||{},r=n.duration,i=r===void 0?300:r,s=n.easing,o=s===void 0?$T.easeInOut:s,a=n.delay,l=a===void 0?0:a,c=Array.isArray(t)?t:[t];return c.map(function(f){var p=typeof i=="string"?i:Kk(i),g=typeof l=="string"?l:Kk(l);return f+" "+p+" "+o+" "+g}).join(",")}function Iue(t){return t&&t.ownerDocument||document}function w9(t){var e=Iue(t);return e.defaultView||window}function Lue(t,e){e===void 0&&(e=166);var n;function r(){for(var i=this,s=arguments.length,o=new Array(s),a=0;a-1,w=b.snacks.findIndex(y)>-1;if(S||w)return b}return i.handleDisplaySnack(Tr({},b,{queue:[].concat(b.queue,[_])}))}),v},i.handleDisplaySnack=function(s){var o=s.snacks;return o.length>=i.maxSnack?i.handleDismissOldest(s):i.processQueue(s)},i.processQueue=function(s){var o=s.queue,a=s.snacks;return o.length>0?Tr({},s,{snacks:[].concat(a,[o[0]]),queue:o.slice(1,o.length)}):s},i.handleDismissOldest=function(s){if(s.snacks.some(function(f){return!f.open||f.requestClose}))return s;var o=!1,a=!1,l=s.snacks.reduce(function(f,p){return f+(p.open&&p.persist?1:0)},0);l===i.maxSnack&&(a=!0);var c=s.snacks.map(function(f){return!o&&(!f.persist||a)?(o=!0,f.entered?(f.onClose&&f.onClose(null,"maxsnack",f.id),i.props.onClose&&i.props.onClose(null,"maxsnack",f.id),Tr({},f,{open:!1})):Tr({},f,{requestClose:!0})):Tr({},f)});return Tr({},s,{snacks:c})},i.handleEnteredSnack=function(s,o,a){if(!ib(a))throw new Error("handleEnteredSnack Cannot be called with undefined key");i.setState(function(l){var c=l.snacks;return{snacks:c.map(function(f){return f.id===a?Tr({},f,{entered:!0}):Tr({},f)})}})},i.handleCloseSnack=function(s,o,a){i.props.onClose&&i.props.onClose(s,o,a);var l=a===void 0;i.setState(function(c){var f=c.snacks,p=c.queue;return{snacks:f.map(function(g){return!l&&g.id!==a?Tr({},g):g.entered?Tr({},g,{open:!1}):Tr({},g,{requestClose:!0})}),queue:p.filter(function(g){return g.id!==a})}})},i.closeSnackbar=function(s){var o=i.state.snacks.find(function(a){return a.id===s});ib(s)&&o&&o.onClose&&o.onClose(null,"instructed",s),i.handleCloseSnack(null,"instructed",s)},i.handleExitedSnack=function(s,o){if(!ib(o))throw new Error("handleExitedSnack Cannot be called with undefined key");i.setState(function(a){var l=i.processQueue(Tr({},a,{snacks:a.snacks.filter(function(c){return c.id!==o})}));return l.queue.length===0?l:i.handleDismissOldest(l)})},i.enqueueSnackbar,i.closeSnackbar,i.state={snacks:[],queue:[],contextValue:{enqueueSnackbar:i.enqueueSnackbar.bind(Gk(i)),closeSnackbar:i.closeSnackbar.bind(Gk(i))}},i}var n=e.prototype;return n.render=function(){var i=this,s=this.state.contextValue,o=this.props,a=o.domRoot,l=o.children,c=o.dense,f=c===void 0?!1:c,p=o.Components,g=p===void 0?{}:p,v=o.classes,x=this.state.snacks.reduce(function(b,y){var S,w=zR(y.anchorOrigin),T=b[w]||[];return Tr({},b,(S={},S[w]=[].concat(T,[y]),S))},{}),_=Object.keys(x).map(function(b){var y=x[b],S=y[0];return Zt.createElement(Kue,{key:b,dense:f,anchorOrigin:S.anchorOrigin,classes:v},y.map(function(w){return Zt.createElement(Zue,{key:w.id,snack:w,classes:v,Component:g[w.variant],onClose:i.handleCloseSnack,onEnter:i.props.onEnter,onExit:i.props.onExit,onExited:bv([i.handleExitedSnack,i.props.onExited],w.id),onEntered:bv([i.handleEnteredSnack,i.props.onEntered],w.id)})}))});return Zt.createElement(b9.Provider,{value:s},l,a?X2.createPortal(_,a):_)},x9(e,[{key:"maxSnack",get:function(){return this.props.maxSnack||Zh.maxSnack}}]),e}(D.Component),wo=function(){return D.useContext(b9)},Jue={VITE_MODULAR_BASE_PATH:"",VITE_MODULAR_BASE_MESH_PATH:"",BASE_URL:"/",MODE:"production",DEV:!1,PROD:!0,SSR:!1};const iO=t=>{let e;const n=new Set,r=(f,p)=>{const g=typeof f=="function"?f(e):f;if(!Object.is(g,e)){const v=e;e=p??(typeof g!="object"||g===null)?g:Object.assign({},e,g),n.forEach(x=>x(e,v))}},i=()=>e,l={setState:r,getState:i,getInitialState:()=>c,subscribe:f=>(n.add(f),()=>n.delete(f)),destroy:()=>{(Jue?"production":void 0)!=="production"&&console.warn("[DEPRECATED] The `destroy` method will be unsupported in a future version. Instead use unsubscribe function returned by subscribe. Everything will be garbage-collected if store is garbage-collected."),n.clear()}},c=e=t(r,i,l);return l},ede=t=>t?iO(t):iO;var P9={exports:{}},I9={},L9={exports:{}},k9={};/**
+ * @license React
+ * use-sync-external-store-shim.production.min.js
+ *
+ * Copyright (c) Facebook, Inc. and its affiliates.
+ *
+ * This source code is licensed under the MIT license found in the
+ * LICENSE file in the root directory of this source tree.
+ */var Q0=D;function tde(t,e){return t===e&&(t!==0||1/t===1/e)||t!==t&&e!==e}var nde=typeof Object.is=="function"?Object.is:tde,rde=Q0.useState,ide=Q0.useEffect,sde=Q0.useLayoutEffect,ode=Q0.useDebugValue;function ade(t,e){var n=e(),r=rde({inst:{value:n,getSnapshot:e}}),i=r[0].inst,s=r[1];return sde(function(){i.value=n,i.getSnapshot=e,l5(i)&&s({inst:i})},[t,n,e]),ide(function(){return l5(i)&&s({inst:i}),t(function(){l5(i)&&s({inst:i})})},[t]),ode(n),n}function l5(t){var e=t.getSnapshot;t=t.value;try{var n=e();return!nde(t,n)}catch{return!0}}function lde(t,e){return e()}var cde=typeof window>"u"||typeof window.document>"u"||typeof window.document.createElement>"u"?lde:ade;k9.useSyncExternalStore=Q0.useSyncExternalStore!==void 0?Q0.useSyncExternalStore:cde;L9.exports=k9;var ude=L9.exports;/**
+ * @license React
+ * use-sync-external-store-shim/with-selector.production.min.js
+ *
+ * Copyright (c) Facebook, Inc. and its affiliates.
+ *
+ * This source code is licensed under the MIT license found in the
+ * LICENSE file in the root directory of this source tree.
+ */var tM=D,dde=ude;function fde(t,e){return t===e&&(t!==0||1/t===1/e)||t!==t&&e!==e}var hde=typeof Object.is=="function"?Object.is:fde,pde=dde.useSyncExternalStore,mde=tM.useRef,gde=tM.useEffect,vde=tM.useMemo,yde=tM.useDebugValue;I9.useSyncExternalStoreWithSelector=function(t,e,n,r,i){var s=mde(null);if(s.current===null){var o={hasValue:!1,value:null};s.current=o}else o=s.current;s=vde(function(){function l(v){if(!c){if(c=!0,f=v,v=r(v),i!==void 0&&o.hasValue){var x=o.value;if(i(x,v))return p=x}return p=v}if(x=p,hde(f,v))return x;var _=r(v);return i!==void 0&&i(x,_)?x:(f=v,p=_)}var c=!1,f,p,g=n===void 0?null:n;return[function(){return l(e())},g===null?void 0:function(){return l(g())}]},[e,n,r,i]);var a=pde(t,s[0],s[1]);return gde(function(){o.hasValue=!0,o.value=a},[a]),yde(a),a};P9.exports=I9;var xde=P9.exports;const _de=By(xde);var O9={VITE_MODULAR_BASE_PATH:"",VITE_MODULAR_BASE_MESH_PATH:"",BASE_URL:"/",MODE:"production",DEV:!1,PROD:!0,SSR:!1};const{useDebugValue:bde}=Zt,{useSyncExternalStoreWithSelector:Sde}=_de;let sO=!1;const wde=t=>t;function Mde(t,e=wde,n){(O9?"production":void 0)!=="production"&&n&&!sO&&(console.warn("[DEPRECATED] Use `createWithEqualityFn` instead of `create` or use `useStoreWithEqualityFn` instead of `useStore`. They can be imported from 'zustand/traditional'. https://github.com/pmndrs/zustand/discussions/1937"),sO=!0);const r=Sde(t.subscribe,t.getState,t.getServerState||t.getInitialState,e,n);return bde(r),r}const oO=t=>{(O9?"production":void 0)!=="production"&&typeof t!="function"&&console.warn("[DEPRECATED] Passing a vanilla store will be unsupported in a future version. Instead use `import { useStore } from 'zustand'`.");const e=typeof t=="function"?ede(t):t,n=(r,i)=>Mde(e,r,i);return Object.assign(n,e),n},N9=t=>t?oO(t):oO;var x2={exports:{}};/**
+ * @license
+ * Lodash
+ * Copyright OpenJS Foundation and other contributors
+ * Released under MIT license
+ * Based on Underscore.js 1.8.3
+ * Copyright Jeremy Ashkenas, DocumentCloud and Investigative Reporters & Editors
+ */x2.exports;(function(t,e){(function(){var n,r="4.17.21",i=200,s="Unsupported core-js use. Try https://npms.io/search?q=ponyfill.",o="Expected a function",a="Invalid `variable` option passed into `_.template`",l="__lodash_hash_undefined__",c=500,f="__lodash_placeholder__",p=1,g=2,v=4,x=1,_=2,b=1,y=2,S=4,w=8,T=16,L=32,R=64,P=128,F=256,O=512,I=30,H="...",Q=800,q=16,le=1,ie=2,ee=3,ue=1/0,z=9007199254740991,te=17976931348623157e292,oe=NaN,de=4294967295,Ce=de-1,Le=de>>>1,V=[["ary",P],["bind",b],["bindKey",y],["curry",w],["curryRight",T],["flip",O],["partial",L],["partialRight",R],["rearg",F]],me="[object Arguments]",pe="[object Array]",Se="[object AsyncFunction]",je="[object Boolean]",it="[object Date]",xe="[object DOMException]",et="[object Error]",Re="[object Function]",Oe="[object GeneratorFunction]",Te="[object Map]",ze="[object Number]",ke="[object Null]",rt="[object Object]",tt="[object Promise]",ae="[object Proxy]",G="[object RegExp]",be="[object Set]",$e="[object String]",Ze="[object Symbol]",We="[object Undefined]",Mt="[object WeakMap]",pt="[object WeakSet]",at="[object ArrayBuffer]",Ie="[object DataView]",ge="[object Float32Array]",Xe="[object Float64Array]",St="[object Int8Array]",mt="[object Int16Array]",Be="[object Int32Array]",vt="[object Uint8Array]",qe="[object Uint8ClampedArray]",ce="[object Uint16Array]",Ne="[object Uint32Array]",fe=/\b__p \+= '';/g,Fe=/\b(__p \+=) '' \+/g,He=/(__e\(.*?\)|\b__t\)) \+\n'';/g,ut=/&(?:amp|lt|gt|quot|#39);/g,xt=/[&<>"']/g,Xt=RegExp(ut.source),vn=RegExp(xt.source),mn=/<%-([\s\S]+?)%>/g,On=/<%([\s\S]+?)%>/g,un=/<%=([\s\S]+?)%>/g,Nn=/\.|\[(?:[^[\]]*|(["'])(?:(?!\1)[^\\]|\\.)*?\1)\]/,In=/^\w*$/,or=/[^.[\]]+|\[(?:(-?\d+(?:\.\d+)?)|(["'])((?:(?!\2)[^\\]|\\.)*?)\2)\]|(?=(?:\.|\[\])(?:\.|\[\]|$))/g,Kn=/[\\^$.*+?()[\]{}|]/g,Fr=RegExp(Kn.source),gr=/^\s+/,ui=/\s/,ss=/\{(?:\n\/\* \[wrapped with .+\] \*\/)?\n?/,Rr=/\{\n\/\* \[wrapped with (.+)\] \*/,ji=/,? & /,Ei=/[^\x00-\x2f\x3a-\x40\x5b-\x60\x7b-\x7f]+/g,di=/[()=,{}\[\]\/\s]/,Gi=/\\(\\)?/g,B=/\$\{([^\\}]*(?:\\.[^\\}]*)*)\}/g,ne=/\w*$/,_e=/^[-+]0x[0-9a-f]+$/i,ye=/^0b[01]+$/i,we=/^\[object .+?Constructor\]$/,Qe=/^0o[0-7]+$/i,wt=/^(?:0|[1-9]\d*)$/,Ft=/[\xc0-\xd6\xd8-\xf6\xf8-\xff\u0100-\u017f]/g,zt=/($^)/,dn=/['\n\r\u2028\u2029\\]/g,fn="\\ud800-\\udfff",wn="\\u0300-\\u036f",Cr="\\ufe20-\\ufe2f",Wr="\\u20d0-\\u20ff",Fi=wn+Cr+Wr,os="\\u2700-\\u27bf",Dn="a-z\\xdf-\\xf6\\xf8-\\xff",an="\\xac\\xb1\\xd7\\xf7",tr="\\x00-\\x2f\\x3a-\\x40\\x5b-\\x60\\x7b-\\xbf",en="\\u2000-\\u206f",Ui=" \\t\\x0b\\f\\xa0\\ufeff\\n\\r\\u2028\\u2029\\u1680\\u180e\\u2000\\u2001\\u2002\\u2003\\u2004\\u2005\\u2006\\u2007\\u2008\\u2009\\u200a\\u202f\\u205f\\u3000",jr="A-Z\\xc0-\\xd6\\xd8-\\xde",Gr="\\ufe0e\\ufe0f",Cs=an+tr+en+Ui,xr="['’]",Pr="["+fn+"]",qo="["+Cs+"]",ti="["+Fi+"]",_r="\\d+",Oa="["+os+"]",Zl="["+Dn+"]",Ts="[^"+fn+Cs+_r+os+Dn+jr+"]",ju="\\ud83c[\\udffb-\\udfff]",bf="(?:"+ti+"|"+ju+")",Hc="[^"+fn+"]",Zo="(?:\\ud83c[\\udde6-\\uddff]){2}",yl="[\\ud800-\\udbff][\\udc00-\\udfff]",Mo="["+jr+"]",sn="\\u200d",$c="(?:"+Zl+"|"+Ts+")",W="(?:"+Mo+"|"+Ts+")",$="(?:"+xr+"(?:d|ll|m|re|s|t|ve))?",J="(?:"+xr+"(?:D|LL|M|RE|S|T|VE))?",Z=bf+"?",re="["+Gr+"]?",Ye="(?:"+sn+"(?:"+[Hc,Zo,yl].join("|")+")"+re+Z+")*",Ge="\\d*(?:1st|2nd|3rd|(?![123])\\dth)(?=\\b|[A-Z_])",Bt="\\d*(?:1ST|2ND|3RD|(?![123])\\dTH)(?=\\b|[a-z_])",Tt=re+Z+Ye,Lt="(?:"+[Oa,Zo,yl].join("|")+")"+Tt,qt="(?:"+[Hc+ti+"?",ti,Zo,yl,Pr].join("|")+")",_t=RegExp(xr,"g"),Pt=RegExp(ti,"g"),Ht=RegExp(ju+"(?="+ju+")|"+qt+Tt,"g"),ln=RegExp([Mo+"?"+Zl+"+"+$+"(?="+[qo,Mo,"$"].join("|")+")",W+"+"+J+"(?="+[qo,Mo+$c,"$"].join("|")+")",Mo+"?"+$c+"+"+$,Mo+"+"+J,Bt,Ge,_r,Lt].join("|"),"g"),Yt=RegExp("["+sn+fn+Fi+Gr+"]"),Ir=/[a-z][A-Z]|[A-Z]{2}[a-z]|[0-9][a-zA-Z]|[a-zA-Z][0-9]|[^a-zA-Z0-9 ]/,nr=["Array","Buffer","DataView","Date","Error","Float32Array","Float64Array","Function","Int8Array","Int16Array","Int32Array","Map","Math","Object","Promise","RegExp","Set","String","Symbol","TypeError","Uint8Array","Uint8ClampedArray","Uint16Array","Uint32Array","WeakMap","_","clearTimeout","isFinite","parseInt","setTimeout"],Rn=-1,tn={};tn[ge]=tn[Xe]=tn[St]=tn[mt]=tn[Be]=tn[vt]=tn[qe]=tn[ce]=tn[Ne]=!0,tn[me]=tn[pe]=tn[at]=tn[je]=tn[Ie]=tn[it]=tn[et]=tn[Re]=tn[Te]=tn[ze]=tn[rt]=tn[G]=tn[be]=tn[$e]=tn[Mt]=!1;var Zn={};Zn[me]=Zn[pe]=Zn[at]=Zn[Ie]=Zn[je]=Zn[it]=Zn[ge]=Zn[Xe]=Zn[St]=Zn[mt]=Zn[Be]=Zn[Te]=Zn[ze]=Zn[rt]=Zn[G]=Zn[be]=Zn[$e]=Zn[Ze]=Zn[vt]=Zn[qe]=Zn[ce]=Zn[Ne]=!0,Zn[et]=Zn[Re]=Zn[Mt]=!1;var Lr={À:"A",Á:"A",Â:"A",Ã:"A",Ä:"A",Å:"A",à:"a",á:"a",â:"a",ã:"a",ä:"a",å:"a",Ç:"C",ç:"c",Ð:"D",ð:"d",È:"E",É:"E",Ê:"E",Ë:"E",è:"e",é:"e",ê:"e",ë:"e",Ì:"I",Í:"I",Î:"I",Ï:"I",ì:"i",í:"i",î:"i",ï:"i",Ñ:"N",ñ:"n",Ò:"O",Ó:"O",Ô:"O",Õ:"O",Ö:"O",Ø:"O",ò:"o",ó:"o",ô:"o",õ:"o",ö:"o",ø:"o",Ù:"U",Ú:"U",Û:"U",Ü:"U",ù:"u",ú:"u",û:"u",ü:"u",Ý:"Y",ý:"y",ÿ:"y",Æ:"Ae",æ:"ae",Þ:"Th",þ:"th",ß:"ss",Ā:"A",Ă:"A",Ą:"A",ā:"a",ă:"a",ą:"a",Ć:"C",Ĉ:"C",Ċ:"C",Č:"C",ć:"c",ĉ:"c",ċ:"c",č:"c",Ď:"D",Đ:"D",ď:"d",đ:"d",Ē:"E",Ĕ:"E",Ė:"E",Ę:"E",Ě:"E",ē:"e",ĕ:"e",ė:"e",ę:"e",ě:"e",Ĝ:"G",Ğ:"G",Ġ:"G",Ģ:"G",ĝ:"g",ğ:"g",ġ:"g",ģ:"g",Ĥ:"H",Ħ:"H",ĥ:"h",ħ:"h",Ĩ:"I",Ī:"I",Ĭ:"I",Į:"I",İ:"I",ĩ:"i",ī:"i",ĭ:"i",į:"i",ı:"i",Ĵ:"J",ĵ:"j",Ķ:"K",ķ:"k",ĸ:"k",Ĺ:"L",Ļ:"L",Ľ:"L",Ŀ:"L",Ł:"L",ĺ:"l",ļ:"l",ľ:"l",ŀ:"l",ł:"l",Ń:"N",Ņ:"N",Ň:"N",Ŋ:"N",ń:"n",ņ:"n",ň:"n",ŋ:"n",Ō:"O",Ŏ:"O",Ő:"O",ō:"o",ŏ:"o",ő:"o",Ŕ:"R",Ŗ:"R",Ř:"R",ŕ:"r",ŗ:"r",ř:"r",Ś:"S",Ŝ:"S",Ş:"S",Š:"S",ś:"s",ŝ:"s",ş:"s",š:"s",Ţ:"T",Ť:"T",Ŧ:"T",ţ:"t",ť:"t",ŧ:"t",Ũ:"U",Ū:"U",Ŭ:"U",Ů:"U",Ű:"U",Ų:"U",ũ:"u",ū:"u",ŭ:"u",ů:"u",ű:"u",ų:"u",Ŵ:"W",ŵ:"w",Ŷ:"Y",ŷ:"y",Ÿ:"Y",Ź:"Z",Ż:"Z",Ž:"Z",ź:"z",ż:"z",ž:"z",IJ:"IJ",ij:"ij",Œ:"Oe",œ:"oe",ʼn:"'n",ſ:"s"},as={"&":"&","<":"<",">":">",'"':""","'":"'"},Gu={"&":"&","<":"<",">":">",""":'"',"'":"'"},Xu={"\\":"\\","'":"'","\n":"n","\r":"r","\u2028":"u2028","\u2029":"u2029"},_x=parseFloat,IM=parseInt,Yo=typeof h1=="object"&&h1&&h1.Object===Object&&h1,LM=typeof self=="object"&&self&&self.Object===Object&&self,fi=Yo||LM||Function("return this")(),Cg=e&&!e.nodeType&&e,Xi=Cg&&!0&&t&&!t.nodeType&&t,Sf=Xi&&Xi.exports===Cg,qu=Sf&&Yo.process,qi=function(){try{var Ee=Xi&&Xi.require&&Xi.require("util").types;return Ee||qu&&qu.binding&&qu.binding("util")}catch{}}(),Rp=qi&&qi.isArrayBuffer,Pp=qi&&qi.isDate,Tg=qi&&qi.isMap,Ip=qi&&qi.isRegExp,Lp=qi&&qi.isSet,Vc=qi&&qi.isTypedArray;function Ur(Ee,st,Ke){switch(Ke.length){case 0:return Ee.call(st);case 1:return Ee.call(st,Ke[0]);case 2:return Ee.call(st,Ke[0],Ke[1]);case 3:return Ee.call(st,Ke[0],Ke[1],Ke[2])}return Ee.apply(st,Ke)}function Na(Ee,st,Ke,$t){for(var Mn=-1,Ln=Ee==null?0:Ee.length;++Mn-1}function Zu(Ee,st,Ke){for(var $t=-1,Mn=Ee==null?0:Ee.length;++$t-1;);return Ke}function Qu(Ee,st){for(var Ke=Ee.length;Ke--&&Jo(st,Ee[Ke],0)>-1;);return Ke}function ta(Ee,st){for(var Ke=Ee.length,$t=0;Ke--;)Ee[Ke]===st&&++$t;return $t}var Ex=Us(Lr),Cx=Us(as);function Ig(Ee){return"\\"+Xu[Ee]}function Lg(Ee,st){return Ee==null?n:Ee[st]}function Wc(Ee){return Yt.test(Ee)}function Cf(Ee){return Ir.test(Ee)}function Ju(Ee){for(var st,Ke=[];!(st=Ee.next()).done;)Ke.push(st.value);return Ke}function Tf(Ee){var st=-1,Ke=Array(Ee.size);return Ee.forEach(function($t,Mn){Ke[++st]=[Mn,$t]}),Ke}function ed(Ee,st){return function(Ke){return Ee(st(Ke))}}function na(Ee,st){for(var Ke=-1,$t=Ee.length,Mn=0,Ln=[];++Ke<$t;){var zr=Ee[Ke];(zr===st||zr===f)&&(Ee[Ke]=f,Ln[Mn++]=Ke)}return Ln}function Af(Ee){var st=-1,Ke=Array(Ee.size);return Ee.forEach(function($t){Ke[++st]=$t}),Ke}function Tx(Ee){var st=-1,Ke=Array(Ee.size);return Ee.forEach(function($t){Ke[++st]=[$t,$t]}),Ke}function td(Ee,st,Ke){for(var $t=Ke-1,Mn=Ee.length;++$t-1}function Bp(u,m){var E=this.__data__,N=nc(E,u);return N<0?(++this.size,E.push([u,m])):E[N][1]=m,this}ra.prototype.clear=Gx,ra.prototype.delete=Hg,ra.prototype.get=Xx,ra.prototype.has=qx,ra.prototype.set=Bp;function Eo(u){var m=-1,E=u==null?0:u.length;for(this.clear();++m=m?u:m)),u}function Ks(u,m,E,N,j,se){var ve,Me=m&p,Ue=m&g,dt=m&v;if(E&&(ve=j?E(u,N,j,se):E(u)),ve!==n)return ve;if(!si(u))return u;var ft=kn(u);if(ft){if(ve=BB(u),!Me)return ms(u,ve)}else{var yt=zs(u),Nt=yt==Re||yt==Oe;if(_d(u))return a1(u,Me);if(yt==rt||yt==me||Nt&&!j){if(ve=Ue||Nt?{}:QP(u),!Me)return Ue?u_(u,e_(ve,u)):$M(u,Xg(ve,u))}else{if(!Zn[yt])return j?u:{};ve=HB(u,yt,Me)}}se||(se=new Ri);var nn=se.get(u);if(nn)return nn;se.set(u,ve),T4(u)?u.forEach(function(_n){ve.add(Ks(_n,m,E,_n,u,se))}):E4(u)&&u.forEach(function(_n,Qn){ve.set(Qn,Ks(_n,m,E,Qn,u,se))});var xn=dt?Ue?rr:mi:Ue?Po:vs,Wn=ft?n:xn(u);return Ci(Wn||u,function(_n,Qn){Wn&&(Qn=_n,_n=u[Qn]),ia(ve,Qn,Ks(_n,m,E,Qn,u,se))}),ve}function qg(u){var m=vs(u);return function(E){return Wp(E,u,m)}}function Wp(u,m,E){var N=E.length;if(u==null)return!N;for(u=yn(u);N--;){var j=E[N],se=m[j],ve=u[j];if(ve===n&&!(j in u)||!se(ve))return!1}return!0}function Zg(u,m,E){if(typeof u!="function")throw new Ps(o);return d1(function(){u.apply(n,E)},m)}function Yc(u,m,E,N){var j=-1,se=Ko,ve=!0,Me=u.length,Ue=[],dt=m.length;if(!Me)return Ue;E&&(m=kr(m,As(E))),N?(se=Zu,ve=!1):m.length>=i&&(se=Zi,ve=!1,m=new tc(m));e:for(;++jj?0:j+E),N=N===n||N>j?j:$n(N),N<0&&(N+=j),N=E>N?0:R4(N);E0&&E(Me)?m>1?Hi(Me,m-1,E,N,j):Qo(j,Me):N||(j[j.length]=Me)}return j}var dd=nm(),$f=nm(!0);function Qs(u,m){return u&&dd(u,m,vs)}function fd(u,m){return u&&$f(u,m,vs)}function Kc(u,m){return ls(m,function(E){return nu(u[E])})}function oa(u,m){m=lc(m,u);for(var E=0,N=m.length;u!=null&&Em}function r_(u,m){return u!=null&&lr.call(u,m)}function Kg(u,m){return u!=null&&m in yn(u)}function BM(u,m,E){return u>=cs(m,E)&&u=120&&ft.length>=120)?new tc(ve&&ft):n}ft=u[0];var yt=-1,Nt=Me[0];e:for(;++yt-1;)Me!==u&&Jl.call(Me,Ue,1),Jl.call(u,Ue,1);return u}function fs(u,m){for(var E=u?m.length:0,N=E-1;E--;){var j=m[E];if(E==N||j!==se){var se=j;tu(j)?Jl.call(u,j,1):i1(u,j)}}return u}function $a(u,m){return u+Nf(zg()*(m-u+1))}function Co(u,m,E,N){for(var j=-1,se=Ai(Of((m-u)/(E||1)),0),ve=Ke(se);se--;)ve[N?se:++j]=u,u+=E;return ve}function xd(u,m){var E="";if(!u||m<1||m>z)return E;do m%2&&(E+=u),m=Nf(m/2),m&&(u+=u);while(m);return E}function cn(u,m){return ZM(t4(u,m,Io),u+"")}function i_(u){return Bf(om(u))}function t1(u,m){var E=om(u);return h_(E,rc(m,0,E.length))}function Jc(u,m,E,N){if(!si(u))return u;m=lc(m,u);for(var j=-1,se=m.length,ve=se-1,Me=u;Me!=null&&++jj?0:j+m),E=E>j?j:E,E<0&&(E+=j),j=m>E?0:E-m>>>0,m>>>=0;for(var se=Ke(j);++N>>1,ve=u[se];ve!==null&&!la(ve)&&(E?ve<=m:ve=i){var dt=m?null:gs(u);if(dt)return Af(dt);ve=!1,j=Zi,Ue=new tc}else Ue=m?[]:Me;e:for(;++N=N?u:eo(u,m,E)}var l_=kf||function(u){return fi.clearTimeout(u)};function a1(u,m){if(m)return u.slice();var E=u.length,N=Ng?Ng(E):new u.constructor(E);return u.copy(N),N}function em(u){var m=new u.constructor(u.byteLength);return new If(m).set(new If(u)),m}function HM(u,m){var E=m?em(u.buffer):u.buffer;return new u.constructor(E,u.byteOffset,u.byteLength)}function To(u){var m=new u.constructor(u.source,ne.exec(u));return m.lastIndex=u.lastIndex,m}function l1(u){return Sl?yn(Sl.call(u)):{}}function c_(u,m){var E=m?em(u.buffer):u.buffer;return new u.constructor(E,u.byteOffset,u.length)}function El(u,m){if(u!==m){var E=u!==n,N=u===null,j=u===u,se=la(u),ve=m!==n,Me=m===null,Ue=m===m,dt=la(m);if(!Me&&!dt&&!se&&u>m||se&&ve&&Ue&&!Me&&!dt||N&&ve&&Ue||!E&&Ue||!j)return 1;if(!N&&!se&&!dt&&u=Me)return Ue;var dt=E[N];return Ue*(dt=="desc"?-1:1)}}return u.index-m.index}function uc(u,m,E,N){for(var j=-1,se=u.length,ve=E.length,Me=-1,Ue=m.length,dt=Ai(se-ve,0),ft=Ke(Ue+dt),yt=!N;++Me1?E[j-1]:n,ve=j>2?E[2]:n;for(se=u.length>3&&typeof se=="function"?(j--,se):n,ve&&no(E[0],E[1],ve)&&(se=j<3?n:se,j=1),m=yn(m);++N-1?j[se?m[ve]:ve]:n}}function k(u){return zn(function(m){var E=m.length,N=E,j=us.prototype.thru;for(u&&m.reverse();N--;){var se=m[N];if(typeof se!="function")throw new Ps(o);if(j&&!ve&&rm(se)=="wrapper")var ve=new us([],!0)}for(N=ve?N:E;++N1&&ir.reverse(),ft&&UeMe))return!1;var dt=se.get(u),ft=se.get(m);if(dt&&ft)return dt==m&&ft==u;var yt=-1,Nt=!0,nn=E&_?new tc:n;for(se.set(u,m),se.set(m,u);++yt1?"& ":"")+m[N],m=m.join(E>2?", ":" "),u.replace(ss,`{
+/* [wrapped with `+m+`] */
+`)}function VB(u){return kn(u)||Jf(u)||!!(Fg&&u&&u[Fg])}function tu(u,m){var E=typeof u;return m=m??z,!!m&&(E=="number"||E!="symbol"&&wt.test(u))&&u>-1&&u%1==0&&u0){if(++m>=Q)return arguments[0]}else m=0;return u.apply(n,arguments)}}function h_(u,m){var E=-1,N=u.length,j=N-1;for(m=m===n?N:m;++E1?u[m-1]:n;return E=typeof E=="function"?(u.pop(),E):n,h4(u,E)});function p4(u){var m=Y(u);return m.__chain__=!0,m}function e$(u,m){return m(u),u}function p_(u,m){return m(u)}var t$=zn(function(u){var m=u.length,E=m?u[0]:0,N=this.__wrapped__,j=function(se){return Vp(se,u)};return m>1||this.__actions__.length||!(N instanceof hn)||!tu(E)?this.thru(j):(N=N.slice(E,+E+(m?1:0)),N.__actions__.push({func:p_,args:[j],thisArg:n}),new us(N,this.__chain__).thru(function(se){return m&&!se.length&&se.push(n),se}))});function n$(){return p4(this)}function r$(){return new us(this.value(),this.__chain__)}function i$(){this.__values__===n&&(this.__values__=A4(this.value()));var u=this.__index__>=this.__values__.length,m=u?n:this.__values__[this.__index__++];return{done:u,value:m}}function s$(){return this}function o$(u){for(var m,E=this;E instanceof zf;){var N=a4(E);N.__index__=0,N.__values__=n,m?j.__wrapped__=N:m=N;var j=N;E=E.__wrapped__}return j.__wrapped__=u,m}function a$(){var u=this.__wrapped__;if(u instanceof hn){var m=u;return this.__actions__.length&&(m=new hn(this)),m=m.reverse(),m.__actions__.push({func:p_,args:[YM],thisArg:n}),new us(m,this.__chain__)}return this.thru(YM)}function l$(){return oc(this.__wrapped__,this.__actions__)}var c$=Yf(function(u,m,E){lr.call(u,E)?++u[E]:Ha(u,E,1)});function u$(u,m,E){var N=kn(u)?Rg:zM;return E&&no(u,m,E)&&(m=n),N(u,gn(m,3))}function d$(u,m){var E=kn(u)?ls:Yg;return E(u,gn(m,3))}var f$=A(l4),h$=A(c4);function p$(u,m){return Hi(m_(u,m),1)}function m$(u,m){return Hi(m_(u,m),ue)}function g$(u,m,E){return E=E===n?1:$n(E),Hi(m_(u,m),E)}function m4(u,m){var E=kn(u)?Ci:sa;return E(u,gn(m,3))}function g4(u,m){var E=kn(u)?Ag:t_;return E(u,gn(m,3))}var v$=Yf(function(u,m,E){lr.call(u,E)?u[E].push(m):Ha(u,E,[m])});function y$(u,m,E,N){u=Ro(u)?u:om(u),E=E&&!N?$n(E):0;var j=u.length;return E<0&&(E=Ai(j+E,0)),__(u)?E<=j&&u.indexOf(m,E)>-1:!!j&&Jo(u,m,E)>-1}var x$=cn(function(u,m,E){var N=-1,j=typeof m=="function",se=Ro(u)?Ke(u.length):[];return sa(u,function(ve){se[++N]=j?Ur(m,ve,E):Nr(ve,m,E)}),se}),_$=Yf(function(u,m,E){Ha(u,E,m)});function m_(u,m){var E=kn(u)?kr:Qc;return E(u,gn(m,3))}function b$(u,m,E,N){return u==null?[]:(kn(m)||(m=m==null?[]:[m]),E=N?n:E,kn(E)||(E=E==null?[]:[E]),Gf(u,m,E))}var S$=Yf(function(u,m,E){u[E?0:1].push(m)},function(){return[[],[]]});function w$(u,m,E){var N=kn(u)?kp:Yl,j=arguments.length<3;return N(u,gn(m,4),E,j,sa)}function M$(u,m,E){var N=kn(u)?bx:Yl,j=arguments.length<3;return N(u,gn(m,4),E,j,t_)}function E$(u,m){var E=kn(u)?ls:Yg;return E(u,y_(gn(m,3)))}function C$(u){var m=kn(u)?Bf:i_;return m(u)}function T$(u,m,E){(E?no(u,m,E):m===n)?m=1:m=$n(m);var N=kn(u)?Wg:t1;return N(u,m)}function A$(u){var m=kn(u)?Jx:o_;return m(u)}function R$(u){if(u==null)return 0;if(Ro(u))return __(u)?Da(u):u.length;var m=zs(u);return m==Te||m==be?u.size:ds(u).length}function P$(u,m,E){var N=kn(u)?wf:n1;return E&&no(u,m,E)&&(m=n),N(u,gn(m,3))}var I$=cn(function(u,m){if(u==null)return[];var E=m.length;return E>1&&no(u,m[0],m[1])?m=[]:E>2&&no(m[0],m[1],m[2])&&(m=[m[0]]),Gf(u,Hi(m,1),[])}),g_=Px||function(){return fi.Date.now()};function L$(u,m){if(typeof m!="function")throw new Ps(o);return u=$n(u),function(){if(--u<1)return m.apply(this,arguments)}}function v4(u,m,E){return m=E?n:m,m=u&&m==null?u.length:m,Ve(u,P,n,n,n,n,m)}function y4(u,m){var E;if(typeof m!="function")throw new Ps(o);return u=$n(u),function(){return--u>0&&(E=m.apply(this,arguments)),u<=1&&(m=n),E}}var QM=cn(function(u,m,E){var N=b;if(E.length){var j=na(E,im(QM));N|=L}return Ve(u,N,m,E,j)}),x4=cn(function(u,m,E){var N=b|y;if(E.length){var j=na(E,im(x4));N|=L}return Ve(m,N,u,E,j)});function _4(u,m,E){m=E?n:m;var N=Ve(u,w,n,n,n,n,n,m);return N.placeholder=_4.placeholder,N}function b4(u,m,E){m=E?n:m;var N=Ve(u,T,n,n,n,n,n,m);return N.placeholder=b4.placeholder,N}function S4(u,m,E){var N,j,se,ve,Me,Ue,dt=0,ft=!1,yt=!1,Nt=!0;if(typeof u!="function")throw new Ps(o);m=Ga(m)||0,si(E)&&(ft=!!E.leading,yt="maxWait"in E,se=yt?Ai(Ga(E.maxWait)||0,m):se,Nt="trailing"in E?!!E.trailing:Nt);function nn(Ii){var Tl=N,iu=j;return N=j=n,dt=Ii,ve=u.apply(iu,Tl),ve}function xn(Ii){return dt=Ii,Me=d1(Qn,m),ft?nn(Ii):ve}function Wn(Ii){var Tl=Ii-Ue,iu=Ii-dt,H4=m-Tl;return yt?cs(H4,se-iu):H4}function _n(Ii){var Tl=Ii-Ue,iu=Ii-dt;return Ue===n||Tl>=m||Tl<0||yt&&iu>=se}function Qn(){var Ii=g_();if(_n(Ii))return ir(Ii);Me=d1(Qn,Wn(Ii))}function ir(Ii){return Me=n,Nt&&N?nn(Ii):(N=j=n,ve)}function ca(){Me!==n&&l_(Me),dt=0,N=Ue=j=Me=n}function ro(){return Me===n?ve:ir(g_())}function ua(){var Ii=g_(),Tl=_n(Ii);if(N=arguments,j=this,Ue=Ii,Tl){if(Me===n)return xn(Ue);if(yt)return l_(Me),Me=d1(Qn,m),nn(Ue)}return Me===n&&(Me=d1(Qn,m)),ve}return ua.cancel=ca,ua.flush=ro,ua}var k$=cn(function(u,m){return Zg(u,1,m)}),O$=cn(function(u,m,E){return Zg(u,Ga(m)||0,E)});function N$(u){return Ve(u,O)}function v_(u,m){if(typeof u!="function"||m!=null&&typeof m!="function")throw new Ps(o);var E=function(){var N=arguments,j=m?m.apply(this,N):N[0],se=E.cache;if(se.has(j))return se.get(j);var ve=u.apply(this,N);return E.cache=se.set(j,ve)||se,ve};return E.cache=new(v_.Cache||Eo),E}v_.Cache=Eo;function y_(u){if(typeof u!="function")throw new Ps(o);return function(){var m=arguments;switch(m.length){case 0:return!u.call(this);case 1:return!u.call(this,m[0]);case 2:return!u.call(this,m[0],m[1]);case 3:return!u.call(this,m[0],m[1],m[2])}return!u.apply(this,m)}}function D$(u){return y4(2,u)}var F$=a_(function(u,m){m=m.length==1&&kn(m[0])?kr(m[0],As(gn())):kr(Hi(m,1),As(gn()));var E=m.length;return cn(function(N){for(var j=-1,se=cs(N.length,E);++j=m}),Jf=Fn(function(){return arguments}())?Fn:function(u){return gi(u)&&lr.call(u,"callee")&&!Up.call(u,"callee")},kn=Ke.isArray,Q$=Rp?As(Rp):hi;function Ro(u){return u!=null&&x_(u.length)&&!nu(u)}function Pi(u){return gi(u)&&Ro(u)}function J$(u){return u===!0||u===!1||gi(u)&&Yi(u)==je}var _d=Lx||uE,eV=Pp?As(Pp):pi;function tV(u){return gi(u)&&u.nodeType===1&&!f1(u)}function nV(u){if(u==null)return!0;if(Ro(u)&&(kn(u)||typeof u=="string"||typeof u.splice=="function"||_d(u)||sm(u)||Jf(u)))return!u.length;var m=zs(u);if(m==Te||m==be)return!u.size;if(u1(u))return!ds(u).length;for(var E in u)if(lr.call(u,E))return!1;return!0}function rV(u,m){return ri(u,m)}function iV(u,m,E){E=typeof E=="function"?E:n;var N=E?E(u,m):n;return N===n?ri(u,m,n,E):!!N}function eE(u){if(!gi(u))return!1;var m=Yi(u);return m==et||m==xe||typeof u.message=="string"&&typeof u.name=="string"&&!f1(u)}function sV(u){return typeof u=="number"&&Ug(u)}function nu(u){if(!si(u))return!1;var m=Yi(u);return m==Re||m==Oe||m==Se||m==ae}function M4(u){return typeof u=="number"&&u==$n(u)}function x_(u){return typeof u=="number"&&u>-1&&u%1==0&&u<=z}function si(u){var m=typeof u;return u!=null&&(m=="object"||m=="function")}function gi(u){return u!=null&&typeof u=="object"}var E4=Tg?As(Tg):pd;function oV(u,m){return u===m||ii(u,m,WM(m))}function aV(u,m,E){return E=typeof E=="function"?E:n,ii(u,m,WM(m),E)}function lV(u){return C4(u)&&u!=+u}function cV(u){if(GB(u))throw new Mn(s);return md(u)}function uV(u){return u===null}function dV(u){return u==null}function C4(u){return typeof u=="number"||gi(u)&&Yi(u)==ze}function f1(u){if(!gi(u)||Yi(u)!=rt)return!1;var m=Lf(u);if(m===null)return!0;var E=lr.call(m,"constructor")&&m.constructor;return typeof E=="function"&&E instanceof E&&od.call(E)==jc}var tE=Ip?As(Ip):gd;function fV(u){return M4(u)&&u>=-z&&u<=z}var T4=Lp?As(Lp):Gp;function __(u){return typeof u=="string"||!kn(u)&&gi(u)&&Yi(u)==$e}function la(u){return typeof u=="symbol"||gi(u)&&Yi(u)==Ze}var sm=Vc?As(Vc):Jg;function hV(u){return u===n}function pV(u){return gi(u)&&zs(u)==Mt}function mV(u){return gi(u)&&Yi(u)==pt}var gV=on(Wf),vV=on(function(u,m){return u<=m});function A4(u){if(!u)return[];if(Ro(u))return __(u)?Qr(u):ms(u);if(ec&&u[ec])return Ju(u[ec]());var m=zs(u),E=m==Te?Tf:m==be?Af:om;return E(u)}function ru(u){if(!u)return u===0?u:0;if(u=Ga(u),u===ue||u===-ue){var m=u<0?-1:1;return m*te}return u===u?u:0}function $n(u){var m=ru(u),E=m%1;return m===m?E?m-E:m:0}function R4(u){return u?rc($n(u),0,de):0}function Ga(u){if(typeof u=="number")return u;if(la(u))return oe;if(si(u)){var m=typeof u.valueOf=="function"?u.valueOf():u;u=si(m)?m+"":m}if(typeof u!="string")return u===0?u:+u;u=Np(u);var E=ye.test(u);return E||Qe.test(u)?IM(u.slice(2),E?2:8):_e.test(u)?oe:+u}function P4(u){return Ao(u,Po(u))}function yV(u){return u?rc($n(u),-z,z):u===0?u:0}function yr(u){return u==null?"":hs(u)}var xV=eu(function(u,m){if(u1(m)||Ro(m)){Ao(m,vs(m),u);return}for(var E in m)lr.call(m,E)&&ia(u,E,m[E])}),I4=eu(function(u,m){Ao(m,Po(m),u)}),b_=eu(function(u,m,E,N){Ao(m,Po(m),u,N)}),_V=eu(function(u,m,E,N){Ao(m,vs(m),u,N)}),bV=zn(Vp);function SV(u,m){var E=wl(u);return m==null?E:Xg(E,m)}var wV=cn(function(u,m){u=yn(u);var E=-1,N=m.length,j=N>2?m[2]:n;for(j&&no(m[0],m[1],j)&&(N=1);++E1),se}),Ao(u,rr(u),E),N&&(E=Ks(E,p|g|v,Dt));for(var j=m.length;j--;)i1(E,m[j]);return E});function HV(u,m){return k4(u,y_(gn(m)))}var $V=zn(function(u,m){return u==null?{}:Xf(u,m)});function k4(u,m){if(u==null)return{};var E=kr(rr(u),function(N){return[N]});return m=gn(m),Zp(u,E,function(N,j){return m(N,j[0])})}function VV(u,m,E){m=lc(m,u);var N=-1,j=m.length;for(j||(j=1,u=n);++Nm){var N=u;u=m,m=N}if(E||u%1||m%1){var j=zg();return cs(u+j*(m-u+_x("1e-"+((j+"").length-1))),m)}return $a(u,m)}var eW=d(function(u,m,E){return m=m.toLowerCase(),u+(E?D4(m):m)});function D4(u){return iE(yr(u).toLowerCase())}function F4(u){return u=yr(u),u&&u.replace(Ft,Ex).replace(Pt,"")}function tW(u,m,E){u=yr(u),m=hs(m);var N=u.length;E=E===n?N:rc($n(E),0,N);var j=E;return E-=m.length,E>=0&&u.slice(E,j)==m}function nW(u){return u=yr(u),u&&vn.test(u)?u.replace(xt,Cx):u}function rW(u){return u=yr(u),u&&Fr.test(u)?u.replace(Kn,"\\$&"):u}var iW=d(function(u,m,E){return u+(E?"-":"")+m.toLowerCase()}),sW=d(function(u,m,E){return u+(E?" ":"")+m.toLowerCase()}),oW=d_("toLowerCase");function aW(u,m,E){u=yr(u),m=$n(m);var N=m?Da(u):0;if(!m||N>=m)return u;var j=(m-N)/2;return Et(Nf(j),E)+u+Et(Of(j),E)}function lW(u,m,E){u=yr(u),m=$n(m);var N=m?Da(u):0;return m&&N>>0,E?(u=yr(u),u&&(typeof m=="string"||m!=null&&!tE(m))&&(m=hs(m),!m&&Wc(u))?cc(Qr(u),0,E):u.split(m,E)):[]}var mW=d(function(u,m,E){return u+(E?" ":"")+iE(m)});function gW(u,m,E){return u=yr(u),E=E==null?0:rc($n(E),0,u.length),m=hs(m),u.slice(E,E+m.length)==m}function vW(u,m,E){var N=Y.templateSettings;E&&no(u,m,E)&&(m=n),u=yr(u),m=b_({},m,N,De);var j=b_({},m.imports,N.imports,De),se=vs(j),ve=Rs(j,se),Me,Ue,dt=0,ft=m.interpolate||zt,yt="__p += '",Nt=zi((m.escape||zt).source+"|"+ft.source+"|"+(ft===un?B:zt).source+"|"+(m.evaluate||zt).source+"|$","g"),nn="//# sourceURL="+(lr.call(m,"sourceURL")?(m.sourceURL+"").replace(/\s/g," "):"lodash.templateSources["+ ++Rn+"]")+`
+`;u.replace(Nt,function(_n,Qn,ir,ca,ro,ua){return ir||(ir=ca),yt+=u.slice(dt,ua).replace(dn,Ig),Qn&&(Me=!0,yt+=`' +
+__e(`+Qn+`) +
+'`),ro&&(Ue=!0,yt+=`';
+`+ro+`;
+__p += '`),ir&&(yt+=`' +
+((__t = (`+ir+`)) == null ? '' : __t) +
+'`),dt=ua+_n.length,_n}),yt+=`';
+`;var xn=lr.call(m,"variable")&&m.variable;if(!xn)yt=`with (obj) {
+`+yt+`
+}
+`;else if(di.test(xn))throw new Mn(a);yt=(Ue?yt.replace(fe,""):yt).replace(Fe,"$1").replace(He,"$1;"),yt="function("+(xn||"obj")+`) {
+`+(xn?"":`obj || (obj = {});
+`)+"var __t, __p = ''"+(Me?", __e = _.escape":"")+(Ue?`, __j = Array.prototype.join;
+function print() { __p += __j.call(arguments, '') }
+`:`;
+`)+yt+`return __p
+}`;var Wn=z4(function(){return Ln(se,nn+"return "+yt).apply(n,ve)});if(Wn.source=yt,eE(Wn))throw Wn;return Wn}function yW(u){return yr(u).toLowerCase()}function xW(u){return yr(u).toUpperCase()}function _W(u,m,E){if(u=yr(u),u&&(E||m===n))return Np(u);if(!u||!(m=hs(m)))return u;var N=Qr(u),j=Qr(m),se=Or(N,j),ve=Qu(N,j)+1;return cc(N,se,ve).join("")}function bW(u,m,E){if(u=yr(u),u&&(E||m===n))return u.slice(0,nd(u)+1);if(!u||!(m=hs(m)))return u;var N=Qr(u),j=Qu(N,Qr(m))+1;return cc(N,0,j).join("")}function SW(u,m,E){if(u=yr(u),u&&(E||m===n))return u.replace(gr,"");if(!u||!(m=hs(m)))return u;var N=Qr(u),j=Or(N,Qr(m));return cc(N,j).join("")}function wW(u,m){var E=I,N=H;if(si(m)){var j="separator"in m?m.separator:j;E="length"in m?$n(m.length):E,N="omission"in m?hs(m.omission):N}u=yr(u);var se=u.length;if(Wc(u)){var ve=Qr(u);se=ve.length}if(E>=se)return u;var Me=E-Da(N);if(Me<1)return N;var Ue=ve?cc(ve,0,Me).join(""):u.slice(0,Me);if(j===n)return Ue+N;if(ve&&(Me+=Ue.length-Me),tE(j)){if(u.slice(Me).search(j)){var dt,ft=Ue;for(j.global||(j=zi(j.source,yr(ne.exec(j))+"g")),j.lastIndex=0;dt=j.exec(ft);)var yt=dt.index;Ue=Ue.slice(0,yt===n?Me:yt)}}else if(u.indexOf(hs(j),Me)!=Me){var Nt=Ue.lastIndexOf(j);Nt>-1&&(Ue=Ue.slice(0,Nt))}return Ue+N}function MW(u){return u=yr(u),u&&Xt.test(u)?u.replace(ut,rd):u}var EW=d(function(u,m,E){return u+(E?" ":"")+m.toUpperCase()}),iE=d_("toUpperCase");function U4(u,m,E){return u=yr(u),m=E?n:m,m===n?Cf(u)?id(u):wx(u):u.match(m)||[]}var z4=cn(function(u,m){try{return Ur(u,n,m)}catch(E){return eE(E)?E:new Mn(E)}}),CW=zn(function(u,m){return Ci(m,function(E){E=dc(E),Ha(u,E,QM(u[E],u))}),u});function TW(u){var m=u==null?0:u.length,E=gn();return u=m?kr(u,function(N){if(typeof N[1]!="function")throw new Ps(o);return[E(N[0]),N[1]]}):[],cn(function(N){for(var j=-1;++jz)return[];var E=de,N=cs(u,de);m=gn(m),u-=de;for(var j=_l(N,m);++E0||m<0)?new hn(E):(u<0?E=E.takeRight(-u):u&&(E=E.drop(u)),m!==n&&(m=$n(m),E=m<0?E.dropRight(-m):E.take(m-u)),E)},hn.prototype.takeRightWhile=function(u){return this.reverse().takeWhile(u).reverse()},hn.prototype.toArray=function(){return this.take(de)},Qs(hn.prototype,function(u,m){var E=/^(?:filter|find|map|reject)|While$/.test(m),N=/^(?:head|last)$/.test(m),j=Y[N?"take"+(m=="last"?"Right":""):m],se=N||/^find/.test(m);j&&(Y.prototype[m]=function(){var ve=this.__wrapped__,Me=N?[1]:arguments,Ue=ve instanceof hn,dt=Me[0],ft=Ue||kn(ve),yt=function(Qn){var ir=j.apply(Y,Qo([Qn],Me));return N&&Nt?ir[0]:ir};ft&&E&&typeof dt=="function"&&dt.length!=1&&(Ue=ft=!1);var Nt=this.__chain__,nn=!!this.__actions__.length,xn=se&&!Nt,Wn=Ue&&!nn;if(!se&&ft){ve=Wn?ve:new hn(this);var _n=u.apply(ve,Me);return _n.__actions__.push({func:p_,args:[yt],thisArg:n}),new us(_n,Nt)}return xn&&Wn?u.apply(this,Me):(_n=this.thru(yt),xn?N?_n.value()[0]:_n.value():_n)})}),Ci(["pop","push","shift","sort","splice","unshift"],function(u){var m=Ql[u],E=/^(?:push|sort|unshift)$/.test(u)?"tap":"thru",N=/^(?:pop|shift)$/.test(u);Y.prototype[u]=function(){var j=arguments;if(N&&!this.__chain__){var se=this.value();return m.apply(kn(se)?se:[],j)}return this[E](function(ve){return m.apply(kn(ve)?ve:[],j)})}}),Qs(hn.prototype,function(u,m){var E=Y[m];if(E){var N=E.name+"";lr.call(qc,N)||(qc[N]=[]),qc[N].push({name:m,func:E})}}),qc[U(n,y).name]=[{name:"wrapper",func:n}],hn.prototype.clone=OM,hn.prototype.reverse=NM,hn.prototype.value=Ys,Y.prototype.at=t$,Y.prototype.chain=n$,Y.prototype.commit=r$,Y.prototype.next=i$,Y.prototype.plant=o$,Y.prototype.reverse=a$,Y.prototype.toJSON=Y.prototype.valueOf=Y.prototype.value=l$,Y.prototype.first=Y.prototype.head,ec&&(Y.prototype[ec]=s$),Y},Kl=Rx();Xi?((Xi.exports=Kl)._=Kl,Cg._=Kl):fi._=Kl}).call(h1)})(x2,x2.exports);var ry=x2.exports;let aO=(t=21)=>crypto.getRandomValues(new Uint8Array(t)).reduce((e,n)=>(n&=63,n<36?e+=n.toString(36):n<62?e+=(n-26).toString(36).toUpperCase():n>62?e+="-":e+="_",e),"");const Es="",Ede=["x","y","z","roll","pitch","yaw"];function Cde(t){return Ede.includes(t)}function D9(t){const e={};return Object.entries(t).forEach(([n,r])=>{if(!Cde(n))throw TypeError(`invalid key '${n}'found for ModuleOffsetDescription object`);e[n]=r.map(i=>typeof i=="number"?{value:i,label:i.toFixed(2)}:i)}),e}function F9(t){if(t.notation==="rpy")return{x:t.px,y:t.py,z:t.pz,roll:t.rx,pitch:t.ry,yaw:t.rz};if(t.notation==="quaternion")return{x:t.px,y:t.py,z:t.pz,rx:t.rx,ry:t.ry,rz:t.rz,rw:t.rw};throw new Error("invalid notation type for 'offset'")}const Tde=["application/zip","application/vnd.rar","application/x-rar-compressed","application/octet-stream","application/octet-stream","application/x-zip-compressed","multipart/x-zip"];function Ade(){const t=mf(),{enqueueSnackbar:e}=wo(),{setMeshId:n}=Dr();return gg({mutationFn:async(r,i)=>{const{data:s}=await Yn.post(`${Es}/model/urdf`,r,{responseType:"blob",...i});return s},onSuccess:(r,i)=>{if(r instanceof Blob&&Tde.includes(r.type)){const s=r.name??`${i.name??"modularbot"}.zip`,o=URL.createObjectURL(r),a=document.createElement("a");a.download=s,a.href=o,document.body.appendChild(a),console.info(`${s} downloadable at link ${a.href}`),a.click(),document.body.removeChild(a)}e("Deployment Succesful",{variant:"success"}),t.invalidateQueries({queryKey:["modular","model","urdf","modules","map"]}),t.invalidateQueries({queryKey:["modular","model","stats"]}),n()},onError:async r=>{var s,o,a;const i=JSON.parse(await((s=r.response)==null?void 0:s.data.text())??"{}");e(i.message??`The request to deploy the robot was made but no response received.
+Error: ${(o=r.response)==null?void 0:o.status} ${(a=r.response)==null?void 0:a.statusText}.`,{style:{whiteSpace:"pre-line"},variant:"error"})}})}function Rde(){const t=mf(),{enqueueSnackbar:e}=wo(),{setMeshId:n,setSelected:r}=Dr();return gg({mutationFn:async i=>(await Yn.put(`${Es}/model/urdf`,i)).data,onSuccess:i=>{e("Generated model",{variant:"success"}),e("Passive end-effector must be added manually",{variant:"info"}),r(i),n()},onError:i=>{var s,o;console.error(i),e(i.response&&typeof i.response.data.message<"u"?`${i.response.data.message}`:`The request to generate the model was made but no response received.
+Error: ${(s=i.response)==null?void 0:s.status} ${(o=i.response)==null?void 0:o.statusText}.`,{variant:"error",style:{whiteSpace:"pre-line"}})},onSettled:()=>{t.invalidateQueries({queryKey:["modular","model","urdf","modules","map"]}),t.invalidateQueries({queryKey:["modular","model","stats"]})}})}const Pde=async t=>(await Yn.get(`${Es}/model/urdf/joints/map`,t)).data;function U9(t){let e=["modular","model","urdf","modules","map"],n={};return typeof t.id<"u"&&(e.push(t.id),n.ids=[t.id]),wo(),Hu({queryKey:e,queryFn:async r=>{const i=await Yn.get(`${Es}/model/urdf/modules/map`,{...r,params:{...r==null?void 0:r.params,...n}}),s={};return Object.entries(i.data).forEach(([o,a])=>{s[o]={...a,offsets:typeof a.offsets<"u"?D9(a.offsets):void 0}}),s},enabled:t.enabled,refetchOnWindowFocus:!1})}function Ide(){const t=mf(),{enqueueSnackbar:e}=wo(),{setMeshId:n,setSelected:r}=Dr();return gg({mutationFn:async({offset:i,...s},o)=>(await Yn.post(`${Es}/model/urdf/modules`,{...s,offsets_requested:F9(i)},o)).data,onSuccess:i=>{r(i),n()},onError:i=>{var s,o;console.error(i),e(i.response&&typeof i.response.data.message<"u"?`${i.response.data.message}`:`The request to add a module was made but no response received.
+Error: ${(s=i.response)==null?void 0:s.status} ${(o=i.response)==null?void 0:o.statusText}.`,{variant:"error",style:{whiteSpace:"pre-line"}})},onSettled:()=>{t.invalidateQueries({queryKey:["modular","model","urdf","modules","map"]}),t.invalidateQueries({queryKey:["modular","model","stats"]})}})}function Lde(){const t=mf(),{enqueueSnackbar:e}=wo(),{setMeshId:n}=Dr();return gg({mutationFn:async({payload:r,options:i})=>{const{offset:s,...o}=r;return await Yn.put(`${Es}/model/urdf/modules`,{...o,offsets_requested:F9(s)},i)},onSuccess:()=>{n()},onError:r=>{var i,s;console.error(r),e(r.response&&typeof r.response.data.message<"u"?`${r.response.data.message}`:`The request to edit a module was made but no response received.
+Error: ${(i=r.response)==null?void 0:i.status} ${(s=r.response)==null?void 0:s.statusText}.`,{variant:"error",style:{whiteSpace:"pre-line"}})},onSettled(){t.invalidateQueries({queryKey:["modular","resources","modules","allowed"]}),t.invalidateQueries({queryKey:["modular","model","urdf","modules","map"]}),t.invalidateQueries({queryKey:["modular","model","stats"]})}})}function kde(){const t=mf(),{enqueueSnackbar:e}=wo(),{setMeshId:n,setSelected:r}=Dr();return gg({mutationFn:async i=>(await Yn.delete(`${Es}/model/urdf/modules`,i)).data,onSuccess:(i,s)=>{var o;e(typeof(s==null?void 0:s.params.ids)>"u"?"Deleted last module":`Deleted ${(o=s==null?void 0:s.params.ids)==null?void 0:o.length} modules`,{variant:"success"}),r(i),n()},onError:i=>{var s,o;console.error(i),e(i.response&&typeof i.response.data.message<"u"?`${i.response.data.message}`:`The request to delete a module was made but no response received.
+Error: ${(s=i.response)==null?void 0:s.status} ${(o=i.response)==null?void 0:o.statusText}.`,{variant:"error",style:{whiteSpace:"pre-line"}})},onSettled:()=>{t.invalidateQueries({queryKey:["modular","model","urdf","modules","map"]}),t.invalidateQueries({queryKey:["modular","model","stats"]})}})}function Ode(t=!0){return Hu({queryKey:["modular","model","stats"],queryFn:async n=>(await Yn.get(`${Es}/model/stats`,n)).data,enabled:t,refetchOnWindowFocus:!1})}const Nde=async t=>await Yn.get(`${Es}/model/urdf/modules/meshes`,t);function Dde(){return Hu({queryKey:["modular","resources","families"],queryFn:async t=>(await Yn.get(`${Es}/resources/families`,t)).data.families,refetchOnWindowFocus:!1})}function Fde(t,e){let n=["modular","resources","modules"],r={};return e&&(n.push(e),r.families=[e]),Hu({queryKey:n,queryFn:async i=>(await Yn.get(`${Es}/resources/modules`,{...i,params:{...i==null?void 0:i.params,...r}})).data.modules.map(a=>({...a,offsets:typeof a.offsets<"u"?D9(a.offsets):void 0})),enabled:t,refetchOnWindowFocus:!1})}function Ude(t,e){let n=["modular","resources","addons"],r={};return e&&(n.push(e),r.families=[e]),Hu({queryKey:n,queryFn:async i=>(await Yn.get(`${Es}/resources/addons`,{...i,params:{...i==null?void 0:i.params,...r}})).data.addons,enabled:t,refetchOnWindowFocus:!1})}function zde(t,e){let n=["modular","resources","modules","allowed"],r={};return e&&(n.push(e),r.ids=[e]),Hu({queryKey:n,queryFn:async i=>(await Yn.get(`${Es}/resources/modules/allowed`,{...i,params:{...i==null?void 0:i.params,...r}})).data,enabled:t,refetchOnWindowFocus:!1})}const Dr=N9(t=>({meshId:aO(4),setMeshId:async()=>{var e,n;try{const r=await Pde();t(i=>{var s;for(const[o,a]of Object.entries(r))a.value=((s=i.jointMap[o])==null?void 0:s.value)??0;return{...i,meshId:aO(4),jointMap:r}})}catch(r){if(r instanceof Mue)wo().enqueueSnackbar(r.response&&typeof r.response.data.message<"u"?`${r.response.data.message}`:`The request for the updated joint map was made but no response received.
+Error: ${(e=r.response)==null?void 0:e.status} ${(n=r.response)==null?void 0:n.statusText}.`,{variant:"error",style:{whiteSpace:"pre-line"}});else throw r}},selected:void 0,setSelected:e=>t(n=>({...n,selected:e})),jointMap:{},setJointMap:e=>t(n=>({...n,jointMap:e})),setJoint:(e,n,r,i,s)=>t(o=>({...o,jointMap:{...o.jointMap,[e]:{type:n,min:r===-1/0?-Math.PI*2:r,max:i===1/0?Math.PI*2:i,value:s??0}}})),setJointValue:(e,n)=>t(r=>({...r,jointMap:{...r.jointMap,[e]:{type:r.jointMap[e].type,min:r.jointMap[e].min,max:r.jointMap[e].max,value:n}}})),removeJoint:e=>t(n=>({...n,jointMap:ry.omit(n.jointMap,e)})),removeAllJoints:()=>t(e=>({...e,jointMap:{}}))}));function nM(){return Hu({queryKey:["modular","workspace","mode"],queryFn:async t=>(await Yn.get(`${Es}/mode`,t)).data.mode,refetchOnWindowFocus:!1})}function Bde(){const t=mf(),{enqueueSnackbar:e}=wo(),n=Dr(i=>i.setMeshId),r=Dr(i=>i.setSelected);return gg({mutationFn:async(i,s)=>await Yn.post(`${Es}/mode`,{mode:i},s),onMutate:async i=>{await t.cancelQueries({queryKey:["modular","workspace","mode"]});const s=t.getQueryData([["modular","workspace","mode"]]);return s&&t.setQueryData([["modular","workspace","mode"]],i),{previousState:s}},onError:(i,s,o)=>{var a,l;console.error(i),e(i.response&&typeof i.response.data.message<"u"?`${i.response.data.message}`:`The request to change worspace mode was made but no response received.
+Error: ${(a=i.response)==null?void 0:a.status} ${(l=i.response)==null?void 0:l.statusText}.`,{variant:"error",style:{whiteSpace:"pre-line"}}),o!=null&&o.previousState&&t.setQueryData(["modular","workspace","mode"],o.previousState)},onSuccess:(i,s)=>{e(`Switched mode to ${s}`,{variant:"success"}),r(),n()},onSettled:()=>{t.invalidateQueries({queryKey:["modular","workspace","mode"]}),t.invalidateQueries({queryKey:["modular","resources","modules","allowed"]})}})}function Hde(){return Hu({queryKey:["modular","workspace","mode","discovery"],queryFn:async t=>(await Yn.get(`${Es}/mode/discovery`,t)).data.available,refetchOnWindowFocus:!1})}function $de(){return Hu({queryKey:["modular","workspace","info"],queryFn:async t=>(await Yn.get(`${Es}/info`,t)).data,refetchOnWindowFocus:!1})}function Vde(t,e){return t.type===e.type?t.name{var o;const{enqueueSnackbar:e}=wo(),n=Ude();Zt.useEffect(()=>{var a,l,c;if(n.status==="error"){const f=n.error.response&&typeof n.error.response.data.message<"u"?`Failed to get the list of the available addons.
+Error ${(a=n.error.response)==null?void 0:a.status}: ${n.error.response.data.message}`:`Failed to get the list of the available addons.
+Error ${(l=n.error.response)==null?void 0:l.status}: ${(c=n.error.response)==null?void 0:c.statusText}.`;e(f,{variant:"error",style:{whiteSpace:"pre-line"}})}});const r=((o=n.data)==null?void 0:o.filter(a=>{var l;return(l=t.validAddons)==null?void 0:l.includes(a.type)}))??[],i=r.length===0,s={};return r.forEach(a=>s[a.name]=a.label),C.jsxs("div",{"aria-label":"addon-selector",children:[C.jsx(mr,{variant:"h3",id:"addons-select-title","aria-label":"addons-select-title",color:i?"text.disabled":void 0,sx:{mt:1,mb:1},children:"Addons"}),C.jsx(Xw,{fullWidth:!0,size:"small",sx:{mb:1},children:C.jsx(X7,{multiple:!0,fullWidth:!0,displayEmpty:!0,id:"addons-select","aria-label":"addons-select",value:t.selected,onChange:t.setAddons,disabled:i,input:t.outlined?C.jsx(qw,{}):C.jsx(RR,{}),renderValue:a=>a.length===0?C.jsx(mr,{component:"em",color:"text.disabled",children:"None"}):a.map(l=>s[l]).join(", "),children:r.sort(Vde).map(a=>C.jsx(ty,{value:a.name,disabled:a.disabled,children:a.label},a.name))})})]})},Wde=({value:t,onChange:e,label:n="Family",ariaLabel:r="modules-family-selector"})=>{const[i,s]=Zt.useState(!1),{enqueueSnackbar:o}=wo(),a=Dde();return Zt.useEffect(()=>{if(a.status==="error"){const l=a.error.response?`(${a.error.response.status}) ${a.error.response.data.message}`:"The request for the list of available families of modules was made but no response was received";o(l,{variant:"error",style:{whiteSpace:"pre-line"}})}}),C.jsx(Kne,{freeSolo:!0,id:r,"aria-label":r,value:t,open:i,onOpen:()=>s(!0),onClose:()=>s(!1),onChange:(l,c)=>{e(c===null||typeof c=="string"?{id:c??"",label:c??"",group:""}:c)},isOptionEqualToValue:(l,c)=>l.id===c.id,getOptionLabel:l=>typeof l=="string"?l:l.label,getOptionDisabled:l=>l.disabled??!1,groupBy:l=>l.group,options:(a.data??[]).sort((l,c)=>-c.group.localeCompare(l.group)),loading:a.status==="pending",renderInput:l=>C.jsx(yg,{...l,label:n,InputProps:{...l.InputProps,endAdornment:C.jsxs(Zt.Fragment,{children:[a.isFetching?C.jsx(ka,{color:"inherit",size:20}):null,l.InputProps.endAdornment]})}})})},jde=lt(dp)(({theme:t})=>({background:t.palette.background.paper,borderColor:t.palette.grey[700]})),Gde=({module:t,disabled:e,...n})=>C.jsx(jde,{color:"inherit",variant:"outlined",size:"small",name:t.name,"aria-label":t.name,disabled:e||t.disabled,...n,children:t.label??t.name});var HR={},c5={};const Xde=Uu(YQ);var lO;function _g(){return lO||(lO=1,function(t){"use client";Object.defineProperty(t,"__esModule",{value:!0}),Object.defineProperty(t,"default",{enumerable:!0,get:function(){return e.createSvgIcon}});var e=Xde}(c5)),c5}var qde=pf;Object.defineProperty(HR,"__esModule",{value:!0});var B9=HR.default=void 0,Zde=qde(_g()),Yde=C;B9=HR.default=(0,Zde.default)((0,Yde.jsx)("path",{d:"M6 19c0 1.1.9 2 2 2h8c1.1 0 2-.9 2-2V7H6zM19 4h-3.5l-1-1h-5l-1 1H5v2h14z"}),"Delete");const Kde=t=>{const e=kde(),{data:n}=U9({enabled:!t.disabled}),r=Dr(i=>{var s;return(s=i.selected)==null?void 0:s.id});return C.jsxs(C.Fragment,{children:[C.jsx(Au,{title:"Delete last module",children:C.jsx("span",{children:C.jsx(Vu,{...t,disabled:t.disabled||Object.keys(n??{}).length===0,onClick:()=>e.mutate(r?{params:{ids:[r]}}:void 0),"aria-label":"delete-button",disableRipple:!0,children:C.jsx(B9,{})})})}),e.isPending&&C.jsx(Uc,{open:!0,"aria-label":"loading-screen",children:C.jsx(ka,{})})]})};var $R={},Qde=pf;Object.defineProperty($R,"__esModule",{value:!0});var H9=$R.default=void 0,Jde=Qde(_g()),efe=C;H9=$R.default=(0,Jde.default)((0,efe.jsx)("path",{d:"M9.19 6.35c-2.04 2.29-3.44 5.58-3.57 5.89L2 10.69l4.05-4.05c.47-.47 1.15-.68 1.81-.55zM11.17 17s3.74-1.55 5.89-3.7c5.4-5.4 4.5-9.62 4.21-10.57-.95-.3-5.17-1.19-10.57 4.21C8.55 9.09 7 12.83 7 12.83zm6.48-2.19c-2.29 2.04-5.58 3.44-5.89 3.57L13.31 22l4.05-4.05c.47-.47.68-1.15.55-1.81zM9 18c0 .83-.34 1.58-.88 2.12C6.94 21.3 2 22 2 22s.7-4.94 1.88-6.12C4.42 15.34 5.17 15 6 15c1.66 0 3 1.34 3 3m4-9c0-1.1.9-2 2-2s2 .9 2 2-.9 2-2 2-2-.9-2-2"}),"RocketLaunch");const tfe=lt(wR)(()=>({minHeight:"30vh",minWidth:"30vw","& .MuiDialog-paper":{}})),nfe=({open:t,onClose:e,module:n})=>{const{enqueueSnackbar:r}=wo(),i=Ide(),s=Dr(g=>{var v;return(v=g.selected)==null?void 0:v.id}),[o,a]=Zt.useState({...n,offset:{notation:"rpy",ref_frame:""},parent:s,addons:[]}),l=(g,v)=>{a({...o,offset:{...o.offset,[g]:v}})},c=g=>{a({...o,reverse:g.target.checked})},f=g=>{const{target:{value:v}}=g;a({...o,addons:typeof v=="string"?v.split(","):v})},p=()=>i.mutate(o,{onSuccess:()=>{r(`Added ${o.label}`,{variant:"success"}),e(!0)}});return t&&i.isPending?C.jsx(Uc,{open:!0,"aria-label":"loading-screen",children:C.jsx(ka,{})}):C.jsxs(tfe,{open:t,onClose:()=>e(!1),"aria-labelledby":"title-add-module-dialog","aria-describedby":"cofig-add-module-dialog",onKeyUp:g=>g.key==="Enter"&&p(),children:[C.jsx(CR,{id:"title-add-module-dialog",sx:{alignItems:"center",borderBottom:1,borderColor:"divider",marginBottom:"10px"},children:C.jsxs(mr,{variant:"h1",component:"div",children:["Add ",o.label," Module"]})}),C.jsxs(ER,{children:[n.offsets&&Object.keys(n.offsets).length>0&&C.jsx(IB,{offsetValues:o.offset,offsetsRanges:n.offsets,setOffsetEntry:l}),C.jsx(z9,{setAddons:f,selected:o.addons,validAddons:n.addons,outlined:!0}),n.reversible&&C.jsxs(bp,{direction:"row",children:[C.jsx(mr,{variant:"h3",id:"reverse-select-title","aria-label":"reverse-select-title",sx:{mt:1,mb:1},children:"Reverse"}),C.jsx(kl,{color:"primary",checked:o.reverse,onChange:c})]})]}),C.jsxs(MR,{children:[C.jsx(dp,{onClick:()=>e(!1),"aria-label":"cancel-button",children:"Cancel"}),C.jsx(dp,{onClick:p,"aria-label":"add-button",children:"Add Module"})]})]})},rfe=lt(wR)(()=>({minHeight:"30vh",minWidth:"30vw","& .MuiDialog-paper":{}})),ife=({open:t,onClose:e,module:n})=>{const{enqueueSnackbar:r}=wo(),i=Lde(),s=Dr(v=>{var x;return(x=v.selected)==null?void 0:x.id}),o=Dr(v=>v.setMeshId),[a,l]=Zt.useState({...n,offset:{notation:"rpy",ref_frame:""},addons:[]}),c=(v,x)=>{l({...a,offset:{...a.offset,[v]:x}})},f=v=>{l({...a,reverse:v.target.checked})},p=v=>{const{target:{value:x}}=v;l({...a,addons:typeof x=="string"?x.split(","):x})},g=()=>{i.mutate({payload:a,options:s?{params:{ids:[s]}}:void 0},{onSuccess:()=>{r(`Updated ${a.label}`,{variant:"success"}),e(!0)}}),o()};return t&&i.isPending?C.jsx(Uc,{open:!0,"aria-label":"loading-screen",children:C.jsx(ka,{})}):C.jsxs(rfe,{open:t,onClose:()=>e(!1),"aria-labelledby":"title-add-module-dialog","aria-describedby":"cofig-add-module-dialog",onKeyUp:v=>v.key==="Enter"&&g(),children:[C.jsxs(CR,{id:"title-add-module-dialog",sx:{alignItems:"center",borderBottom:1,borderColor:"divider",marginBottom:"10px"},children:[C.jsxs(mr,{variant:"h1",component:"div",children:[a.label," Module"]}),C.jsx(mr,{variant:"subtitle1",component:"div",color:"text.disabled",children:s})]}),C.jsxs(ER,{children:[n.offsets&&Object.keys(n.offsets).length>0&&C.jsx(IB,{offsetValues:a.offset,offsetsRanges:n.offsets,setOffsetEntry:c}),C.jsx(z9,{setAddons:p,selected:a.addons,validAddons:n.addons,outlined:!0}),n.reversible&&C.jsxs(bp,{direction:"row",children:[C.jsx(mr,{variant:"h3",id:"reverse-select-title","aria-label":"reverse-select-title",sx:{mt:1,mb:1},children:"Reverse"}),C.jsx(kl,{color:"primary",checked:a.reverse,onChange:f})]})]}),C.jsxs(MR,{children:[C.jsx(dp,{onClick:()=>e(!1),"aria-label":"cancel-button",children:"Cancel"}),C.jsx(dp,{onClick:g,"aria-label":"save-button",children:"Save"})]})]})},sfe=({onClose:t,...e})=>{const{enqueueSnackbar:n}=wo(),r=Dr(c=>{var f;return(f=c.selected)==null?void 0:f.id}),i=Dr(c=>c.setMeshId),{data:s,...o}=U9({enabled:!!r,id:r});Zt.useEffect(()=>{var c,f,p;if(o.status==="error"){const g=o.error.response&&typeof o.error.response.data.message<"u"?`Failed to get the list of the model's modules.
+Error ${(c=o.error.response)==null?void 0:c.status}: ${o.error.response.data.message}`:`Failed to get the list of the model's modules.
+Error ${(f=o.error.response)==null?void 0:f.status}: ${(p=o.error.response)==null?void 0:p.statusText}.`;n(g,{variant:"error",style:{whiteSpace:"pre-line"}})}});const a=c=>{c&&i(),t()};if(typeof r>"u"||o.isLoading||typeof s>"u")return C.jsx(Uc,{open:!0,"aria-label":"loading-screen",children:C.jsx(ka,{})});const l=s[r];return C.jsx(ife,{...e,module:l,onClose:a})},ofe=lt(wR)(()=>({minHeight:"30vh",minWidth:"30vw"})),afe=({open:t,onClose:e})=>{const[n,r]=Zt.useState("modularbot"),i=l=>r(l.target.value),s=Ade(),o=Dr(l=>l.jointMap),a={};return Object.entries(o).forEach(([l,c])=>a[l]=c.value),s.isPending?C.jsx(Uc,{open:!0,"aria-label":"loading-screen",children:C.jsx(ka,{})}):C.jsxs(ofe,{open:t,onClose:()=>e(!1),"aria-labelledby":"title-add-module-dialog","aria-describedby":"cofig-add-module-dialog",children:[C.jsx(CR,{id:"title-add-module-dialog",sx:{alignItems:"center",borderBottom:1,borderColor:"divider",marginBottom:"10px"},children:C.jsx(mr,{variant:"h1",component:"div",children:"Deploy Robot"})}),C.jsx(ER,{children:C.jsx(yg,{fullWidth:!0,id:"title-input",label:"Robot Name",variant:"standard",value:n,inputProps:{"aria-label":"mission-title-input"},onChange:i,sx:{mb:1.5}})}),C.jsxs(MR,{children:[C.jsx(dp,{onClick:()=>e(!1),"aria-label":"cancel-button",children:"Cancel"}),C.jsx(dp,{onClick:()=>{s.mutate({name:n,jointMap:a},{onSuccess:()=>e(!0)})},"aria-label":"deploy-button",children:"Deploy"})]})]})};/**
+ * @license
+ * Copyright 2010-2024 Three.js Authors
+ * SPDX-License-Identifier: MIT
+ */const rM="164",yh={LEFT:0,MIDDLE:1,RIGHT:2,ROTATE:0,DOLLY:1,PAN:2},xh={ROTATE:0,PAN:1,DOLLY_PAN:2,DOLLY_ROTATE:3},$9=0,VT=1,V9=2,lfe=3,W9=0,iM=1,Sv=2,Ol=3,Dc=0,yo=1,Do=2,Pu=0,Yh=1,WT=2,jT=3,GT=4,j9=5,Ud=100,G9=101,X9=102,q9=103,Z9=104,Y9=200,K9=201,Q9=202,J9=203,_2=204,b2=205,eU=206,tU=207,nU=208,rU=209,iU=210,sU=211,oU=212,aU=213,lU=214,cU=0,uU=1,dU=2,iy=3,fU=4,hU=5,pU=6,mU=7,cx=0,gU=1,vU=2,Ic=0,yU=1,xU=2,_U=3,VR=4,bU=5,SU=6,wU=7,XT="attached",MU="detached",sM=300,Fu=301,uf=302,sy=303,oy=304,bg=306,wu=1e3,Uo=1001,ay=1002,bs=1003,WR=1004,cfe=1004,a0=1005,ufe=1005,Mi=1006,wv=1007,dfe=1007,Bl=1008,ffe=1008,Fc=1009,EU=1010,CU=1011,jR=1012,GR=1013,fp=1014,ba=1015,Sg=1016,XR=1017,qR=1018,wg=1020,TU=35902,AU=1021,RU=1022,zo=1023,PU=1024,IU=1025,Kh=1026,J0=1027,ZR=1028,YR=1029,LU=1030,KR=1031,QR=1033,RS=33776,PS=33777,IS=33778,LS=33779,qT=35840,ZT=35841,YT=35842,KT=35843,QT=36196,JT=37492,eA=37496,tA=37808,nA=37809,rA=37810,iA=37811,sA=37812,oA=37813,aA=37814,lA=37815,cA=37816,uA=37817,dA=37818,fA=37819,hA=37820,pA=37821,kS=36492,mA=36494,gA=36495,kU=36283,vA=36284,yA=36285,xA=36286,OU=2200,NU=2201,DU=2202,ly=2300,cy=2301,OS=2302,Ph=2400,Ih=2401,uy=2402,oM=2500,JR=2501,hfe=0,pfe=1,mfe=2,FU=3200,UU=3201,vf=0,zU=1,xu="",ho="srgb",Wu="srgb-linear",aM="display-p3",ux="display-p3-linear",dy="linear",Hr="srgb",fy="rec709",hy="p3",gfe=0,_h=7680,vfe=7681,yfe=7682,xfe=7683,_fe=34055,bfe=34056,Sfe=5386,wfe=512,Mfe=513,Efe=514,Cfe=515,Tfe=516,Afe=517,Rfe=518,_A=519,BU=512,HU=513,$U=514,eP=515,VU=516,WU=517,jU=518,GU=519,py=35044,Pfe=35048,Ife=35040,Lfe=35045,kfe=35049,Ofe=35041,Nfe=35046,Dfe=35050,Ffe=35042,Ufe="100",bA="300 es",Ec=2e3,my=2001;class Bc{addEventListener(e,n){this._listeners===void 0&&(this._listeners={});const r=this._listeners;r[e]===void 0&&(r[e]=[]),r[e].indexOf(n)===-1&&r[e].push(n)}hasEventListener(e,n){if(this._listeners===void 0)return!1;const r=this._listeners;return r[e]!==void 0&&r[e].indexOf(n)!==-1}removeEventListener(e,n){if(this._listeners===void 0)return;const i=this._listeners[e];if(i!==void 0){const s=i.indexOf(n);s!==-1&&i.splice(s,1)}}dispatchEvent(e){if(this._listeners===void 0)return;const r=this._listeners[e.type];if(r!==void 0){e.target=this;const i=r.slice(0);for(let s=0,o=i.length;s>8&255]+$s[t>>16&255]+$s[t>>24&255]+"-"+$s[e&255]+$s[e>>8&255]+"-"+$s[e>>16&15|64]+$s[e>>24&255]+"-"+$s[n&63|128]+$s[n>>8&255]+"-"+$s[n>>16&255]+$s[n>>24&255]+$s[r&255]+$s[r>>8&255]+$s[r>>16&255]+$s[r>>24&255]).toLowerCase()}function wi(t,e,n){return Math.max(e,Math.min(n,t))}function tP(t,e){return(t%e+e)%e}function zfe(t,e,n,r,i){return r+(t-e)*(i-r)/(n-e)}function Bfe(t,e,n){return t!==e?(n-t)/(e-t):0}function Mv(t,e,n){return(1-n)*t+n*e}function Hfe(t,e,n,r){return Mv(t,e,1-Math.exp(-n*r))}function $fe(t,e=1){return e-Math.abs(tP(t,e*2)-e)}function Vfe(t,e,n){return t<=e?0:t>=n?1:(t=(t-e)/(n-e),t*t*(3-2*t))}function Wfe(t,e,n){return t<=e?0:t>=n?1:(t=(t-e)/(n-e),t*t*t*(t*(t*6-15)+10))}function jfe(t,e){return t+Math.floor(Math.random()*(e-t+1))}function Gfe(t,e){return t+Math.random()*(e-t)}function Xfe(t){return t*(.5-Math.random())}function qfe(t){t!==void 0&&(cO=t);let e=cO+=1831565813;return e=Math.imul(e^e>>>15,e|1),e^=e+Math.imul(e^e>>>7,e|61),((e^e>>>14)>>>0)/4294967296}function Zfe(t){return t*Qh}function Yfe(t){return t*eg}function Kfe(t){return(t&t-1)===0&&t!==0}function Qfe(t){return Math.pow(2,Math.ceil(Math.log(t)/Math.LN2))}function Jfe(t){return Math.pow(2,Math.floor(Math.log(t)/Math.LN2))}function ehe(t,e,n,r,i){const s=Math.cos,o=Math.sin,a=s(n/2),l=o(n/2),c=s((e+r)/2),f=o((e+r)/2),p=s((e-r)/2),g=o((e-r)/2),v=s((r-e)/2),x=o((r-e)/2);switch(i){case"XYX":t.set(a*f,l*p,l*g,a*c);break;case"YZY":t.set(l*g,a*f,l*p,a*c);break;case"ZXZ":t.set(l*p,l*g,a*f,a*c);break;case"XZX":t.set(a*f,l*x,l*v,a*c);break;case"YXY":t.set(l*v,a*f,l*x,a*c);break;case"ZYZ":t.set(l*x,l*v,a*f,a*c);break;default:console.warn("THREE.MathUtils: .setQuaternionFromProperEuler() encountered an unknown order: "+i)}}function mo(t,e){switch(e.constructor){case Float32Array:return t;case Uint32Array:return t/4294967295;case Uint16Array:return t/65535;case Uint8Array:return t/255;case Int32Array:return Math.max(t/2147483647,-1);case Int16Array:return Math.max(t/32767,-1);case Int8Array:return Math.max(t/127,-1);default:throw new Error("Invalid component type.")}}function Hn(t,e){switch(e.constructor){case Float32Array:return t;case Uint32Array:return Math.round(t*4294967295);case Uint16Array:return Math.round(t*65535);case Uint8Array:return Math.round(t*255);case Int32Array:return Math.round(t*2147483647);case Int16Array:return Math.round(t*32767);case Int8Array:return Math.round(t*127);default:throw new Error("Invalid component type.")}}const jm={DEG2RAD:Qh,RAD2DEG:eg,generateUUID:Ma,clamp:wi,euclideanModulo:tP,mapLinear:zfe,inverseLerp:Bfe,lerp:Mv,damp:Hfe,pingpong:$fe,smoothstep:Vfe,smootherstep:Wfe,randInt:jfe,randFloat:Gfe,randFloatSpread:Xfe,seededRandom:qfe,degToRad:Zfe,radToDeg:Yfe,isPowerOfTwo:Kfe,ceilPowerOfTwo:Qfe,floorPowerOfTwo:Jfe,setQuaternionFromProperEuler:ehe,normalize:Hn,denormalize:mo};class ct{constructor(e=0,n=0){ct.prototype.isVector2=!0,this.x=e,this.y=n}get width(){return this.x}set width(e){this.x=e}get height(){return this.y}set height(e){this.y=e}set(e,n){return this.x=e,this.y=n,this}setScalar(e){return this.x=e,this.y=e,this}setX(e){return this.x=e,this}setY(e){return this.y=e,this}setComponent(e,n){switch(e){case 0:this.x=n;break;case 1:this.y=n;break;default:throw new Error("index is out of range: "+e)}return this}getComponent(e){switch(e){case 0:return this.x;case 1:return this.y;default:throw new Error("index is out of range: "+e)}}clone(){return new this.constructor(this.x,this.y)}copy(e){return this.x=e.x,this.y=e.y,this}add(e){return this.x+=e.x,this.y+=e.y,this}addScalar(e){return this.x+=e,this.y+=e,this}addVectors(e,n){return this.x=e.x+n.x,this.y=e.y+n.y,this}addScaledVector(e,n){return this.x+=e.x*n,this.y+=e.y*n,this}sub(e){return this.x-=e.x,this.y-=e.y,this}subScalar(e){return this.x-=e,this.y-=e,this}subVectors(e,n){return this.x=e.x-n.x,this.y=e.y-n.y,this}multiply(e){return this.x*=e.x,this.y*=e.y,this}multiplyScalar(e){return this.x*=e,this.y*=e,this}divide(e){return this.x/=e.x,this.y/=e.y,this}divideScalar(e){return this.multiplyScalar(1/e)}applyMatrix3(e){const n=this.x,r=this.y,i=e.elements;return this.x=i[0]*n+i[3]*r+i[6],this.y=i[1]*n+i[4]*r+i[7],this}min(e){return this.x=Math.min(this.x,e.x),this.y=Math.min(this.y,e.y),this}max(e){return this.x=Math.max(this.x,e.x),this.y=Math.max(this.y,e.y),this}clamp(e,n){return this.x=Math.max(e.x,Math.min(n.x,this.x)),this.y=Math.max(e.y,Math.min(n.y,this.y)),this}clampScalar(e,n){return this.x=Math.max(e,Math.min(n,this.x)),this.y=Math.max(e,Math.min(n,this.y)),this}clampLength(e,n){const r=this.length();return this.divideScalar(r||1).multiplyScalar(Math.max(e,Math.min(n,r)))}floor(){return this.x=Math.floor(this.x),this.y=Math.floor(this.y),this}ceil(){return this.x=Math.ceil(this.x),this.y=Math.ceil(this.y),this}round(){return this.x=Math.round(this.x),this.y=Math.round(this.y),this}roundToZero(){return this.x=Math.trunc(this.x),this.y=Math.trunc(this.y),this}negate(){return this.x=-this.x,this.y=-this.y,this}dot(e){return this.x*e.x+this.y*e.y}cross(e){return this.x*e.y-this.y*e.x}lengthSq(){return this.x*this.x+this.y*this.y}length(){return Math.sqrt(this.x*this.x+this.y*this.y)}manhattanLength(){return Math.abs(this.x)+Math.abs(this.y)}normalize(){return this.divideScalar(this.length()||1)}angle(){return Math.atan2(-this.y,-this.x)+Math.PI}angleTo(e){const n=Math.sqrt(this.lengthSq()*e.lengthSq());if(n===0)return Math.PI/2;const r=this.dot(e)/n;return Math.acos(wi(r,-1,1))}distanceTo(e){return Math.sqrt(this.distanceToSquared(e))}distanceToSquared(e){const n=this.x-e.x,r=this.y-e.y;return n*n+r*r}manhattanDistanceTo(e){return Math.abs(this.x-e.x)+Math.abs(this.y-e.y)}setLength(e){return this.normalize().multiplyScalar(e)}lerp(e,n){return this.x+=(e.x-this.x)*n,this.y+=(e.y-this.y)*n,this}lerpVectors(e,n,r){return this.x=e.x+(n.x-e.x)*r,this.y=e.y+(n.y-e.y)*r,this}equals(e){return e.x===this.x&&e.y===this.y}fromArray(e,n=0){return this.x=e[n],this.y=e[n+1],this}toArray(e=[],n=0){return e[n]=this.x,e[n+1]=this.y,e}fromBufferAttribute(e,n){return this.x=e.getX(n),this.y=e.getY(n),this}rotateAround(e,n){const r=Math.cos(n),i=Math.sin(n),s=this.x-e.x,o=this.y-e.y;return this.x=s*r-o*i+e.x,this.y=s*i+o*r+e.y,this}random(){return this.x=Math.random(),this.y=Math.random(),this}*[Symbol.iterator](){yield this.x,yield this.y}}class Bn{constructor(e,n,r,i,s,o,a,l,c){Bn.prototype.isMatrix3=!0,this.elements=[1,0,0,0,1,0,0,0,1],e!==void 0&&this.set(e,n,r,i,s,o,a,l,c)}set(e,n,r,i,s,o,a,l,c){const f=this.elements;return f[0]=e,f[1]=i,f[2]=a,f[3]=n,f[4]=s,f[5]=l,f[6]=r,f[7]=o,f[8]=c,this}identity(){return this.set(1,0,0,0,1,0,0,0,1),this}copy(e){const n=this.elements,r=e.elements;return n[0]=r[0],n[1]=r[1],n[2]=r[2],n[3]=r[3],n[4]=r[4],n[5]=r[5],n[6]=r[6],n[7]=r[7],n[8]=r[8],this}extractBasis(e,n,r){return e.setFromMatrix3Column(this,0),n.setFromMatrix3Column(this,1),r.setFromMatrix3Column(this,2),this}setFromMatrix4(e){const n=e.elements;return this.set(n[0],n[4],n[8],n[1],n[5],n[9],n[2],n[6],n[10]),this}multiply(e){return this.multiplyMatrices(this,e)}premultiply(e){return this.multiplyMatrices(e,this)}multiplyMatrices(e,n){const r=e.elements,i=n.elements,s=this.elements,o=r[0],a=r[3],l=r[6],c=r[1],f=r[4],p=r[7],g=r[2],v=r[5],x=r[8],_=i[0],b=i[3],y=i[6],S=i[1],w=i[4],T=i[7],L=i[2],R=i[5],P=i[8];return s[0]=o*_+a*S+l*L,s[3]=o*b+a*w+l*R,s[6]=o*y+a*T+l*P,s[1]=c*_+f*S+p*L,s[4]=c*b+f*w+p*R,s[7]=c*y+f*T+p*P,s[2]=g*_+v*S+x*L,s[5]=g*b+v*w+x*R,s[8]=g*y+v*T+x*P,this}multiplyScalar(e){const n=this.elements;return n[0]*=e,n[3]*=e,n[6]*=e,n[1]*=e,n[4]*=e,n[7]*=e,n[2]*=e,n[5]*=e,n[8]*=e,this}determinant(){const e=this.elements,n=e[0],r=e[1],i=e[2],s=e[3],o=e[4],a=e[5],l=e[6],c=e[7],f=e[8];return n*o*f-n*a*c-r*s*f+r*a*l+i*s*c-i*o*l}invert(){const e=this.elements,n=e[0],r=e[1],i=e[2],s=e[3],o=e[4],a=e[5],l=e[6],c=e[7],f=e[8],p=f*o-a*c,g=a*l-f*s,v=c*s-o*l,x=n*p+r*g+i*v;if(x===0)return this.set(0,0,0,0,0,0,0,0,0);const _=1/x;return e[0]=p*_,e[1]=(i*c-f*r)*_,e[2]=(a*r-i*o)*_,e[3]=g*_,e[4]=(f*n-i*l)*_,e[5]=(i*s-a*n)*_,e[6]=v*_,e[7]=(r*l-c*n)*_,e[8]=(o*n-r*s)*_,this}transpose(){let e;const n=this.elements;return e=n[1],n[1]=n[3],n[3]=e,e=n[2],n[2]=n[6],n[6]=e,e=n[5],n[5]=n[7],n[7]=e,this}getNormalMatrix(e){return this.setFromMatrix4(e).invert().transpose()}transposeIntoArray(e){const n=this.elements;return e[0]=n[0],e[1]=n[3],e[2]=n[6],e[3]=n[1],e[4]=n[4],e[5]=n[7],e[6]=n[2],e[7]=n[5],e[8]=n[8],this}setUvTransform(e,n,r,i,s,o,a){const l=Math.cos(s),c=Math.sin(s);return this.set(r*l,r*c,-r*(l*o+c*a)+o+e,-i*c,i*l,-i*(-c*o+l*a)+a+n,0,0,1),this}scale(e,n){return this.premultiply(u5.makeScale(e,n)),this}rotate(e){return this.premultiply(u5.makeRotation(-e)),this}translate(e,n){return this.premultiply(u5.makeTranslation(e,n)),this}makeTranslation(e,n){return e.isVector2?this.set(1,0,e.x,0,1,e.y,0,0,1):this.set(1,0,e,0,1,n,0,0,1),this}makeRotation(e){const n=Math.cos(e),r=Math.sin(e);return this.set(n,-r,0,r,n,0,0,0,1),this}makeScale(e,n){return this.set(e,0,0,0,n,0,0,0,1),this}equals(e){const n=this.elements,r=e.elements;for(let i=0;i<9;i++)if(n[i]!==r[i])return!1;return!0}fromArray(e,n=0){for(let r=0;r<9;r++)this.elements[r]=e[r+n];return this}toArray(e=[],n=0){const r=this.elements;return e[n]=r[0],e[n+1]=r[1],e[n+2]=r[2],e[n+3]=r[3],e[n+4]=r[4],e[n+5]=r[5],e[n+6]=r[6],e[n+7]=r[7],e[n+8]=r[8],e}clone(){return new this.constructor().fromArray(this.elements)}}const u5=new Bn;function XU(t){for(let e=t.length-1;e>=0;--e)if(t[e]>=65535)return!0;return!1}const the={Int8Array,Uint8Array,Uint8ClampedArray,Int16Array,Uint16Array,Int32Array,Uint32Array,Float32Array,Float64Array};function l0(t,e){return new the[t](e)}function gy(t){return document.createElementNS("http://www.w3.org/1999/xhtml",t)}function qU(){const t=gy("canvas");return t.style.display="block",t}const uO={};function ZU(t){t in uO||(uO[t]=!0,console.warn(t))}const dO=new Bn().set(.8224621,.177538,0,.0331941,.9668058,0,.0170827,.0723974,.9105199),fO=new Bn().set(1.2249401,-.2249404,0,-.0420569,1.0420571,0,-.0196376,-.0786361,1.0982735),ub={[Wu]:{transfer:dy,primaries:fy,toReference:t=>t,fromReference:t=>t},[ho]:{transfer:Hr,primaries:fy,toReference:t=>t.convertSRGBToLinear(),fromReference:t=>t.convertLinearToSRGB()},[ux]:{transfer:dy,primaries:hy,toReference:t=>t.applyMatrix3(fO),fromReference:t=>t.applyMatrix3(dO)},[aM]:{transfer:Hr,primaries:hy,toReference:t=>t.convertSRGBToLinear().applyMatrix3(fO),fromReference:t=>t.applyMatrix3(dO).convertLinearToSRGB()}},nhe=new Set([Wu,ux]),br={enabled:!0,_workingColorSpace:Wu,get workingColorSpace(){return this._workingColorSpace},set workingColorSpace(t){if(!nhe.has(t))throw new Error(`Unsupported working color space, "${t}".`);this._workingColorSpace=t},convert:function(t,e,n){if(this.enabled===!1||e===n||!e||!n)return t;const r=ub[e].toReference,i=ub[n].fromReference;return i(r(t))},fromWorkingColorSpace:function(t,e){return this.convert(t,this._workingColorSpace,e)},toWorkingColorSpace:function(t,e){return this.convert(t,e,this._workingColorSpace)},getPrimaries:function(t){return ub[t].primaries},getTransfer:function(t){return t===xu?dy:ub[t].transfer}};function b0(t){return t<.04045?t*.0773993808:Math.pow(t*.9478672986+.0521327014,2.4)}function d5(t){return t<.0031308?t*12.92:1.055*Math.pow(t,.41666)-.055}let ym;class YU{static getDataURL(e){if(/^data:/i.test(e.src)||typeof HTMLCanvasElement>"u")return e.src;let n;if(e instanceof HTMLCanvasElement)n=e;else{ym===void 0&&(ym=gy("canvas")),ym.width=e.width,ym.height=e.height;const r=ym.getContext("2d");e instanceof ImageData?r.putImageData(e,0,0):r.drawImage(e,0,0,e.width,e.height),n=ym}return n.width>2048||n.height>2048?(console.warn("THREE.ImageUtils.getDataURL: Image converted to jpg for performance reasons",e),n.toDataURL("image/jpeg",.6)):n.toDataURL("image/png")}static sRGBToLinear(e){if(typeof HTMLImageElement<"u"&&e instanceof HTMLImageElement||typeof HTMLCanvasElement<"u"&&e instanceof HTMLCanvasElement||typeof ImageBitmap<"u"&&e instanceof ImageBitmap){const n=gy("canvas");n.width=e.width,n.height=e.height;const r=n.getContext("2d");r.drawImage(e,0,0,e.width,e.height);const i=r.getImageData(0,0,e.width,e.height),s=i.data;for(let o=0;o0&&(r.userData=this.userData),n||(e.textures[this.uuid]=r),r}dispose(){this.dispatchEvent({type:"dispose"})}transformUv(e){if(this.mapping!==sM)return e;if(e.applyMatrix3(this.matrix),e.x<0||e.x>1)switch(this.wrapS){case wu:e.x=e.x-Math.floor(e.x);break;case Uo:e.x=e.x<0?0:1;break;case ay:Math.abs(Math.floor(e.x)%2)===1?e.x=Math.ceil(e.x)-e.x:e.x=e.x-Math.floor(e.x);break}if(e.y<0||e.y>1)switch(this.wrapT){case wu:e.y=e.y-Math.floor(e.y);break;case Uo:e.y=e.y<0?0:1;break;case ay:Math.abs(Math.floor(e.y)%2)===1?e.y=Math.ceil(e.y)-e.y:e.y=e.y-Math.floor(e.y);break}return this.flipY&&(e.y=1-e.y),e}set needsUpdate(e){e===!0&&(this.version++,this.source.needsUpdate=!0)}set needsPMREMUpdate(e){e===!0&&this.pmremVersion++}}Yr.DEFAULT_IMAGE=null;Yr.DEFAULT_MAPPING=sM;Yr.DEFAULT_ANISOTROPY=1;class Sr{constructor(e=0,n=0,r=0,i=1){Sr.prototype.isVector4=!0,this.x=e,this.y=n,this.z=r,this.w=i}get width(){return this.z}set width(e){this.z=e}get height(){return this.w}set height(e){this.w=e}set(e,n,r,i){return this.x=e,this.y=n,this.z=r,this.w=i,this}setScalar(e){return this.x=e,this.y=e,this.z=e,this.w=e,this}setX(e){return this.x=e,this}setY(e){return this.y=e,this}setZ(e){return this.z=e,this}setW(e){return this.w=e,this}setComponent(e,n){switch(e){case 0:this.x=n;break;case 1:this.y=n;break;case 2:this.z=n;break;case 3:this.w=n;break;default:throw new Error("index is out of range: "+e)}return this}getComponent(e){switch(e){case 0:return this.x;case 1:return this.y;case 2:return this.z;case 3:return this.w;default:throw new Error("index is out of range: "+e)}}clone(){return new this.constructor(this.x,this.y,this.z,this.w)}copy(e){return this.x=e.x,this.y=e.y,this.z=e.z,this.w=e.w!==void 0?e.w:1,this}add(e){return this.x+=e.x,this.y+=e.y,this.z+=e.z,this.w+=e.w,this}addScalar(e){return this.x+=e,this.y+=e,this.z+=e,this.w+=e,this}addVectors(e,n){return this.x=e.x+n.x,this.y=e.y+n.y,this.z=e.z+n.z,this.w=e.w+n.w,this}addScaledVector(e,n){return this.x+=e.x*n,this.y+=e.y*n,this.z+=e.z*n,this.w+=e.w*n,this}sub(e){return this.x-=e.x,this.y-=e.y,this.z-=e.z,this.w-=e.w,this}subScalar(e){return this.x-=e,this.y-=e,this.z-=e,this.w-=e,this}subVectors(e,n){return this.x=e.x-n.x,this.y=e.y-n.y,this.z=e.z-n.z,this.w=e.w-n.w,this}multiply(e){return this.x*=e.x,this.y*=e.y,this.z*=e.z,this.w*=e.w,this}multiplyScalar(e){return this.x*=e,this.y*=e,this.z*=e,this.w*=e,this}applyMatrix4(e){const n=this.x,r=this.y,i=this.z,s=this.w,o=e.elements;return this.x=o[0]*n+o[4]*r+o[8]*i+o[12]*s,this.y=o[1]*n+o[5]*r+o[9]*i+o[13]*s,this.z=o[2]*n+o[6]*r+o[10]*i+o[14]*s,this.w=o[3]*n+o[7]*r+o[11]*i+o[15]*s,this}divideScalar(e){return this.multiplyScalar(1/e)}setAxisAngleFromQuaternion(e){this.w=2*Math.acos(e.w);const n=Math.sqrt(1-e.w*e.w);return n<1e-4?(this.x=1,this.y=0,this.z=0):(this.x=e.x/n,this.y=e.y/n,this.z=e.z/n),this}setAxisAngleFromRotationMatrix(e){let n,r,i,s;const l=e.elements,c=l[0],f=l[4],p=l[8],g=l[1],v=l[5],x=l[9],_=l[2],b=l[6],y=l[10];if(Math.abs(f-g)<.01&&Math.abs(p-_)<.01&&Math.abs(x-b)<.01){if(Math.abs(f+g)<.1&&Math.abs(p+_)<.1&&Math.abs(x+b)<.1&&Math.abs(c+v+y-3)<.1)return this.set(1,0,0,0),this;n=Math.PI;const w=(c+1)/2,T=(v+1)/2,L=(y+1)/2,R=(f+g)/4,P=(p+_)/4,F=(x+b)/4;return w>T&&w>L?w<.01?(r=0,i=.707106781,s=.707106781):(r=Math.sqrt(w),i=R/r,s=P/r):T>L?T<.01?(r=.707106781,i=0,s=.707106781):(i=Math.sqrt(T),r=R/i,s=F/i):L<.01?(r=.707106781,i=.707106781,s=0):(s=Math.sqrt(L),r=P/s,i=F/s),this.set(r,i,s,n),this}let S=Math.sqrt((b-x)*(b-x)+(p-_)*(p-_)+(g-f)*(g-f));return Math.abs(S)<.001&&(S=1),this.x=(b-x)/S,this.y=(p-_)/S,this.z=(g-f)/S,this.w=Math.acos((c+v+y-1)/2),this}min(e){return this.x=Math.min(this.x,e.x),this.y=Math.min(this.y,e.y),this.z=Math.min(this.z,e.z),this.w=Math.min(this.w,e.w),this}max(e){return this.x=Math.max(this.x,e.x),this.y=Math.max(this.y,e.y),this.z=Math.max(this.z,e.z),this.w=Math.max(this.w,e.w),this}clamp(e,n){return this.x=Math.max(e.x,Math.min(n.x,this.x)),this.y=Math.max(e.y,Math.min(n.y,this.y)),this.z=Math.max(e.z,Math.min(n.z,this.z)),this.w=Math.max(e.w,Math.min(n.w,this.w)),this}clampScalar(e,n){return this.x=Math.max(e,Math.min(n,this.x)),this.y=Math.max(e,Math.min(n,this.y)),this.z=Math.max(e,Math.min(n,this.z)),this.w=Math.max(e,Math.min(n,this.w)),this}clampLength(e,n){const r=this.length();return this.divideScalar(r||1).multiplyScalar(Math.max(e,Math.min(n,r)))}floor(){return this.x=Math.floor(this.x),this.y=Math.floor(this.y),this.z=Math.floor(this.z),this.w=Math.floor(this.w),this}ceil(){return this.x=Math.ceil(this.x),this.y=Math.ceil(this.y),this.z=Math.ceil(this.z),this.w=Math.ceil(this.w),this}round(){return this.x=Math.round(this.x),this.y=Math.round(this.y),this.z=Math.round(this.z),this.w=Math.round(this.w),this}roundToZero(){return this.x=Math.trunc(this.x),this.y=Math.trunc(this.y),this.z=Math.trunc(this.z),this.w=Math.trunc(this.w),this}negate(){return this.x=-this.x,this.y=-this.y,this.z=-this.z,this.w=-this.w,this}dot(e){return this.x*e.x+this.y*e.y+this.z*e.z+this.w*e.w}lengthSq(){return this.x*this.x+this.y*this.y+this.z*this.z+this.w*this.w}length(){return Math.sqrt(this.x*this.x+this.y*this.y+this.z*this.z+this.w*this.w)}manhattanLength(){return Math.abs(this.x)+Math.abs(this.y)+Math.abs(this.z)+Math.abs(this.w)}normalize(){return this.divideScalar(this.length()||1)}setLength(e){return this.normalize().multiplyScalar(e)}lerp(e,n){return this.x+=(e.x-this.x)*n,this.y+=(e.y-this.y)*n,this.z+=(e.z-this.z)*n,this.w+=(e.w-this.w)*n,this}lerpVectors(e,n,r){return this.x=e.x+(n.x-e.x)*r,this.y=e.y+(n.y-e.y)*r,this.z=e.z+(n.z-e.z)*r,this.w=e.w+(n.w-e.w)*r,this}equals(e){return e.x===this.x&&e.y===this.y&&e.z===this.z&&e.w===this.w}fromArray(e,n=0){return this.x=e[n],this.y=e[n+1],this.z=e[n+2],this.w=e[n+3],this}toArray(e=[],n=0){return e[n]=this.x,e[n+1]=this.y,e[n+2]=this.z,e[n+3]=this.w,e}fromBufferAttribute(e,n){return this.x=e.getX(n),this.y=e.getY(n),this.z=e.getZ(n),this.w=e.getW(n),this}random(){return this.x=Math.random(),this.y=Math.random(),this.z=Math.random(),this.w=Math.random(),this}*[Symbol.iterator](){yield this.x,yield this.y,yield this.z,yield this.w}}class KU extends Bc{constructor(e=1,n=1,r={}){super(),this.isRenderTarget=!0,this.width=e,this.height=n,this.depth=1,this.scissor=new Sr(0,0,e,n),this.scissorTest=!1,this.viewport=new Sr(0,0,e,n);const i={width:e,height:n,depth:1};r=Object.assign({generateMipmaps:!1,internalFormat:null,minFilter:Mi,depthBuffer:!0,stencilBuffer:!1,resolveDepthBuffer:!0,resolveStencilBuffer:!0,depthTexture:null,samples:0,count:1},r);const s=new Yr(i,r.mapping,r.wrapS,r.wrapT,r.magFilter,r.minFilter,r.format,r.type,r.anisotropy,r.colorSpace);s.flipY=!1,s.generateMipmaps=r.generateMipmaps,s.internalFormat=r.internalFormat,this.textures=[];const o=r.count;for(let a=0;a=0?1:-1,w=1-y*y;if(w>Number.EPSILON){const L=Math.sqrt(w),R=Math.atan2(L,y*S);b=Math.sin(b*R)/L,a=Math.sin(a*R)/L}const T=a*S;if(l=l*b+g*T,c=c*b+v*T,f=f*b+x*T,p=p*b+_*T,b===1-a){const L=1/Math.sqrt(l*l+c*c+f*f+p*p);l*=L,c*=L,f*=L,p*=L}}e[n]=l,e[n+1]=c,e[n+2]=f,e[n+3]=p}static multiplyQuaternionsFlat(e,n,r,i,s,o){const a=r[i],l=r[i+1],c=r[i+2],f=r[i+3],p=s[o],g=s[o+1],v=s[o+2],x=s[o+3];return e[n]=a*x+f*p+l*v-c*g,e[n+1]=l*x+f*g+c*p-a*v,e[n+2]=c*x+f*v+a*g-l*p,e[n+3]=f*x-a*p-l*g-c*v,e}get x(){return this._x}set x(e){this._x=e,this._onChangeCallback()}get y(){return this._y}set y(e){this._y=e,this._onChangeCallback()}get z(){return this._z}set z(e){this._z=e,this._onChangeCallback()}get w(){return this._w}set w(e){this._w=e,this._onChangeCallback()}set(e,n,r,i){return this._x=e,this._y=n,this._z=r,this._w=i,this._onChangeCallback(),this}clone(){return new this.constructor(this._x,this._y,this._z,this._w)}copy(e){return this._x=e.x,this._y=e.y,this._z=e.z,this._w=e.w,this._onChangeCallback(),this}setFromEuler(e,n=!0){const r=e._x,i=e._y,s=e._z,o=e._order,a=Math.cos,l=Math.sin,c=a(r/2),f=a(i/2),p=a(s/2),g=l(r/2),v=l(i/2),x=l(s/2);switch(o){case"XYZ":this._x=g*f*p+c*v*x,this._y=c*v*p-g*f*x,this._z=c*f*x+g*v*p,this._w=c*f*p-g*v*x;break;case"YXZ":this._x=g*f*p+c*v*x,this._y=c*v*p-g*f*x,this._z=c*f*x-g*v*p,this._w=c*f*p+g*v*x;break;case"ZXY":this._x=g*f*p-c*v*x,this._y=c*v*p+g*f*x,this._z=c*f*x+g*v*p,this._w=c*f*p-g*v*x;break;case"ZYX":this._x=g*f*p-c*v*x,this._y=c*v*p+g*f*x,this._z=c*f*x-g*v*p,this._w=c*f*p+g*v*x;break;case"YZX":this._x=g*f*p+c*v*x,this._y=c*v*p+g*f*x,this._z=c*f*x-g*v*p,this._w=c*f*p-g*v*x;break;case"XZY":this._x=g*f*p-c*v*x,this._y=c*v*p-g*f*x,this._z=c*f*x+g*v*p,this._w=c*f*p+g*v*x;break;default:console.warn("THREE.Quaternion: .setFromEuler() encountered an unknown order: "+o)}return n===!0&&this._onChangeCallback(),this}setFromAxisAngle(e,n){const r=n/2,i=Math.sin(r);return this._x=e.x*i,this._y=e.y*i,this._z=e.z*i,this._w=Math.cos(r),this._onChangeCallback(),this}setFromRotationMatrix(e){const n=e.elements,r=n[0],i=n[4],s=n[8],o=n[1],a=n[5],l=n[9],c=n[2],f=n[6],p=n[10],g=r+a+p;if(g>0){const v=.5/Math.sqrt(g+1);this._w=.25/v,this._x=(f-l)*v,this._y=(s-c)*v,this._z=(o-i)*v}else if(r>a&&r>p){const v=2*Math.sqrt(1+r-a-p);this._w=(f-l)/v,this._x=.25*v,this._y=(i+o)/v,this._z=(s+c)/v}else if(a>p){const v=2*Math.sqrt(1+a-r-p);this._w=(s-c)/v,this._x=(i+o)/v,this._y=.25*v,this._z=(l+f)/v}else{const v=2*Math.sqrt(1+p-r-a);this._w=(o-i)/v,this._x=(s+c)/v,this._y=(l+f)/v,this._z=.25*v}return this._onChangeCallback(),this}setFromUnitVectors(e,n){let r=e.dot(n)+1;return rMath.abs(e.z)?(this._x=-e.y,this._y=e.x,this._z=0,this._w=r):(this._x=0,this._y=-e.z,this._z=e.y,this._w=r)):(this._x=e.y*n.z-e.z*n.y,this._y=e.z*n.x-e.x*n.z,this._z=e.x*n.y-e.y*n.x,this._w=r),this.normalize()}angleTo(e){return 2*Math.acos(Math.abs(wi(this.dot(e),-1,1)))}rotateTowards(e,n){const r=this.angleTo(e);if(r===0)return this;const i=Math.min(1,n/r);return this.slerp(e,i),this}identity(){return this.set(0,0,0,1)}invert(){return this.conjugate()}conjugate(){return this._x*=-1,this._y*=-1,this._z*=-1,this._onChangeCallback(),this}dot(e){return this._x*e._x+this._y*e._y+this._z*e._z+this._w*e._w}lengthSq(){return this._x*this._x+this._y*this._y+this._z*this._z+this._w*this._w}length(){return Math.sqrt(this._x*this._x+this._y*this._y+this._z*this._z+this._w*this._w)}normalize(){let e=this.length();return e===0?(this._x=0,this._y=0,this._z=0,this._w=1):(e=1/e,this._x=this._x*e,this._y=this._y*e,this._z=this._z*e,this._w=this._w*e),this._onChangeCallback(),this}multiply(e){return this.multiplyQuaternions(this,e)}premultiply(e){return this.multiplyQuaternions(e,this)}multiplyQuaternions(e,n){const r=e._x,i=e._y,s=e._z,o=e._w,a=n._x,l=n._y,c=n._z,f=n._w;return this._x=r*f+o*a+i*c-s*l,this._y=i*f+o*l+s*a-r*c,this._z=s*f+o*c+r*l-i*a,this._w=o*f-r*a-i*l-s*c,this._onChangeCallback(),this}slerp(e,n){if(n===0)return this;if(n===1)return this.copy(e);const r=this._x,i=this._y,s=this._z,o=this._w;let a=o*e._w+r*e._x+i*e._y+s*e._z;if(a<0?(this._w=-e._w,this._x=-e._x,this._y=-e._y,this._z=-e._z,a=-a):this.copy(e),a>=1)return this._w=o,this._x=r,this._y=i,this._z=s,this;const l=1-a*a;if(l<=Number.EPSILON){const v=1-n;return this._w=v*o+n*this._w,this._x=v*r+n*this._x,this._y=v*i+n*this._y,this._z=v*s+n*this._z,this.normalize(),this}const c=Math.sqrt(l),f=Math.atan2(c,a),p=Math.sin((1-n)*f)/c,g=Math.sin(n*f)/c;return this._w=o*p+this._w*g,this._x=r*p+this._x*g,this._y=i*p+this._y*g,this._z=s*p+this._z*g,this._onChangeCallback(),this}slerpQuaternions(e,n,r){return this.copy(e).slerp(n,r)}random(){const e=2*Math.PI*Math.random(),n=2*Math.PI*Math.random(),r=Math.random(),i=Math.sqrt(1-r),s=Math.sqrt(r);return this.set(i*Math.sin(e),i*Math.cos(e),s*Math.sin(n),s*Math.cos(n))}equals(e){return e._x===this._x&&e._y===this._y&&e._z===this._z&&e._w===this._w}fromArray(e,n=0){return this._x=e[n],this._y=e[n+1],this._z=e[n+2],this._w=e[n+3],this._onChangeCallback(),this}toArray(e=[],n=0){return e[n]=this._x,e[n+1]=this._y,e[n+2]=this._z,e[n+3]=this._w,e}fromBufferAttribute(e,n){return this._x=e.getX(n),this._y=e.getY(n),this._z=e.getZ(n),this._w=e.getW(n),this._onChangeCallback(),this}toJSON(){return this.toArray()}_onChange(e){return this._onChangeCallback=e,this}_onChangeCallback(){}*[Symbol.iterator](){yield this._x,yield this._y,yield this._z,yield this._w}}class K{constructor(e=0,n=0,r=0){K.prototype.isVector3=!0,this.x=e,this.y=n,this.z=r}set(e,n,r){return r===void 0&&(r=this.z),this.x=e,this.y=n,this.z=r,this}setScalar(e){return this.x=e,this.y=e,this.z=e,this}setX(e){return this.x=e,this}setY(e){return this.y=e,this}setZ(e){return this.z=e,this}setComponent(e,n){switch(e){case 0:this.x=n;break;case 1:this.y=n;break;case 2:this.z=n;break;default:throw new Error("index is out of range: "+e)}return this}getComponent(e){switch(e){case 0:return this.x;case 1:return this.y;case 2:return this.z;default:throw new Error("index is out of range: "+e)}}clone(){return new this.constructor(this.x,this.y,this.z)}copy(e){return this.x=e.x,this.y=e.y,this.z=e.z,this}add(e){return this.x+=e.x,this.y+=e.y,this.z+=e.z,this}addScalar(e){return this.x+=e,this.y+=e,this.z+=e,this}addVectors(e,n){return this.x=e.x+n.x,this.y=e.y+n.y,this.z=e.z+n.z,this}addScaledVector(e,n){return this.x+=e.x*n,this.y+=e.y*n,this.z+=e.z*n,this}sub(e){return this.x-=e.x,this.y-=e.y,this.z-=e.z,this}subScalar(e){return this.x-=e,this.y-=e,this.z-=e,this}subVectors(e,n){return this.x=e.x-n.x,this.y=e.y-n.y,this.z=e.z-n.z,this}multiply(e){return this.x*=e.x,this.y*=e.y,this.z*=e.z,this}multiplyScalar(e){return this.x*=e,this.y*=e,this.z*=e,this}multiplyVectors(e,n){return this.x=e.x*n.x,this.y=e.y*n.y,this.z=e.z*n.z,this}applyEuler(e){return this.applyQuaternion(hO.setFromEuler(e))}applyAxisAngle(e,n){return this.applyQuaternion(hO.setFromAxisAngle(e,n))}applyMatrix3(e){const n=this.x,r=this.y,i=this.z,s=e.elements;return this.x=s[0]*n+s[3]*r+s[6]*i,this.y=s[1]*n+s[4]*r+s[7]*i,this.z=s[2]*n+s[5]*r+s[8]*i,this}applyNormalMatrix(e){return this.applyMatrix3(e).normalize()}applyMatrix4(e){const n=this.x,r=this.y,i=this.z,s=e.elements,o=1/(s[3]*n+s[7]*r+s[11]*i+s[15]);return this.x=(s[0]*n+s[4]*r+s[8]*i+s[12])*o,this.y=(s[1]*n+s[5]*r+s[9]*i+s[13])*o,this.z=(s[2]*n+s[6]*r+s[10]*i+s[14])*o,this}applyQuaternion(e){const n=this.x,r=this.y,i=this.z,s=e.x,o=e.y,a=e.z,l=e.w,c=2*(o*i-a*r),f=2*(a*n-s*i),p=2*(s*r-o*n);return this.x=n+l*c+o*p-a*f,this.y=r+l*f+a*c-s*p,this.z=i+l*p+s*f-o*c,this}project(e){return this.applyMatrix4(e.matrixWorldInverse).applyMatrix4(e.projectionMatrix)}unproject(e){return this.applyMatrix4(e.projectionMatrixInverse).applyMatrix4(e.matrixWorld)}transformDirection(e){const n=this.x,r=this.y,i=this.z,s=e.elements;return this.x=s[0]*n+s[4]*r+s[8]*i,this.y=s[1]*n+s[5]*r+s[9]*i,this.z=s[2]*n+s[6]*r+s[10]*i,this.normalize()}divide(e){return this.x/=e.x,this.y/=e.y,this.z/=e.z,this}divideScalar(e){return this.multiplyScalar(1/e)}min(e){return this.x=Math.min(this.x,e.x),this.y=Math.min(this.y,e.y),this.z=Math.min(this.z,e.z),this}max(e){return this.x=Math.max(this.x,e.x),this.y=Math.max(this.y,e.y),this.z=Math.max(this.z,e.z),this}clamp(e,n){return this.x=Math.max(e.x,Math.min(n.x,this.x)),this.y=Math.max(e.y,Math.min(n.y,this.y)),this.z=Math.max(e.z,Math.min(n.z,this.z)),this}clampScalar(e,n){return this.x=Math.max(e,Math.min(n,this.x)),this.y=Math.max(e,Math.min(n,this.y)),this.z=Math.max(e,Math.min(n,this.z)),this}clampLength(e,n){const r=this.length();return this.divideScalar(r||1).multiplyScalar(Math.max(e,Math.min(n,r)))}floor(){return this.x=Math.floor(this.x),this.y=Math.floor(this.y),this.z=Math.floor(this.z),this}ceil(){return this.x=Math.ceil(this.x),this.y=Math.ceil(this.y),this.z=Math.ceil(this.z),this}round(){return this.x=Math.round(this.x),this.y=Math.round(this.y),this.z=Math.round(this.z),this}roundToZero(){return this.x=Math.trunc(this.x),this.y=Math.trunc(this.y),this.z=Math.trunc(this.z),this}negate(){return this.x=-this.x,this.y=-this.y,this.z=-this.z,this}dot(e){return this.x*e.x+this.y*e.y+this.z*e.z}lengthSq(){return this.x*this.x+this.y*this.y+this.z*this.z}length(){return Math.sqrt(this.x*this.x+this.y*this.y+this.z*this.z)}manhattanLength(){return Math.abs(this.x)+Math.abs(this.y)+Math.abs(this.z)}normalize(){return this.divideScalar(this.length()||1)}setLength(e){return this.normalize().multiplyScalar(e)}lerp(e,n){return this.x+=(e.x-this.x)*n,this.y+=(e.y-this.y)*n,this.z+=(e.z-this.z)*n,this}lerpVectors(e,n,r){return this.x=e.x+(n.x-e.x)*r,this.y=e.y+(n.y-e.y)*r,this.z=e.z+(n.z-e.z)*r,this}cross(e){return this.crossVectors(this,e)}crossVectors(e,n){const r=e.x,i=e.y,s=e.z,o=n.x,a=n.y,l=n.z;return this.x=i*l-s*a,this.y=s*o-r*l,this.z=r*a-i*o,this}projectOnVector(e){const n=e.lengthSq();if(n===0)return this.set(0,0,0);const r=e.dot(this)/n;return this.copy(e).multiplyScalar(r)}projectOnPlane(e){return h5.copy(this).projectOnVector(e),this.sub(h5)}reflect(e){return this.sub(h5.copy(e).multiplyScalar(2*this.dot(e)))}angleTo(e){const n=Math.sqrt(this.lengthSq()*e.lengthSq());if(n===0)return Math.PI/2;const r=this.dot(e)/n;return Math.acos(wi(r,-1,1))}distanceTo(e){return Math.sqrt(this.distanceToSquared(e))}distanceToSquared(e){const n=this.x-e.x,r=this.y-e.y,i=this.z-e.z;return n*n+r*r+i*i}manhattanDistanceTo(e){return Math.abs(this.x-e.x)+Math.abs(this.y-e.y)+Math.abs(this.z-e.z)}setFromSpherical(e){return this.setFromSphericalCoords(e.radius,e.phi,e.theta)}setFromSphericalCoords(e,n,r){const i=Math.sin(n)*e;return this.x=i*Math.sin(r),this.y=Math.cos(n)*e,this.z=i*Math.cos(r),this}setFromCylindrical(e){return this.setFromCylindricalCoords(e.radius,e.theta,e.y)}setFromCylindricalCoords(e,n,r){return this.x=e*Math.sin(n),this.y=r,this.z=e*Math.cos(n),this}setFromMatrixPosition(e){const n=e.elements;return this.x=n[12],this.y=n[13],this.z=n[14],this}setFromMatrixScale(e){const n=this.setFromMatrixColumn(e,0).length(),r=this.setFromMatrixColumn(e,1).length(),i=this.setFromMatrixColumn(e,2).length();return this.x=n,this.y=r,this.z=i,this}setFromMatrixColumn(e,n){return this.fromArray(e.elements,n*4)}setFromMatrix3Column(e,n){return this.fromArray(e.elements,n*3)}setFromEuler(e){return this.x=e._x,this.y=e._y,this.z=e._z,this}setFromColor(e){return this.x=e.r,this.y=e.g,this.z=e.b,this}equals(e){return e.x===this.x&&e.y===this.y&&e.z===this.z}fromArray(e,n=0){return this.x=e[n],this.y=e[n+1],this.z=e[n+2],this}toArray(e=[],n=0){return e[n]=this.x,e[n+1]=this.y,e[n+2]=this.z,e}fromBufferAttribute(e,n){return this.x=e.getX(n),this.y=e.getY(n),this.z=e.getZ(n),this}random(){return this.x=Math.random(),this.y=Math.random(),this.z=Math.random(),this}randomDirection(){const e=Math.random()*Math.PI*2,n=Math.random()*2-1,r=Math.sqrt(1-n*n);return this.x=r*Math.cos(e),this.y=n,this.z=r*Math.sin(e),this}*[Symbol.iterator](){yield this.x,yield this.y,yield this.z}}const h5=new K,hO=new sr;class xo{constructor(e=new K(1/0,1/0,1/0),n=new K(-1/0,-1/0,-1/0)){this.isBox3=!0,this.min=e,this.max=n}set(e,n){return this.min.copy(e),this.max.copy(n),this}setFromArray(e){this.makeEmpty();for(let n=0,r=e.length;nthis.max.x||e.ythis.max.y||e.zthis.max.z)}containsBox(e){return this.min.x<=e.min.x&&e.max.x<=this.max.x&&this.min.y<=e.min.y&&e.max.y<=this.max.y&&this.min.z<=e.min.z&&e.max.z<=this.max.z}getParameter(e,n){return n.set((e.x-this.min.x)/(this.max.x-this.min.x),(e.y-this.min.y)/(this.max.y-this.min.y),(e.z-this.min.z)/(this.max.z-this.min.z))}intersectsBox(e){return!(e.max.xthis.max.x||e.max.ythis.max.y||e.max.zthis.max.z)}intersectsSphere(e){return this.clampPoint(e.center,Rl),Rl.distanceToSquared(e.center)<=e.radius*e.radius}intersectsPlane(e){let n,r;return e.normal.x>0?(n=e.normal.x*this.min.x,r=e.normal.x*this.max.x):(n=e.normal.x*this.max.x,r=e.normal.x*this.min.x),e.normal.y>0?(n+=e.normal.y*this.min.y,r+=e.normal.y*this.max.y):(n+=e.normal.y*this.max.y,r+=e.normal.y*this.min.y),e.normal.z>0?(n+=e.normal.z*this.min.z,r+=e.normal.z*this.max.z):(n+=e.normal.z*this.max.z,r+=e.normal.z*this.min.z),n<=-e.constant&&r>=-e.constant}intersectsTriangle(e){if(this.isEmpty())return!1;this.getCenter(O1),fb.subVectors(this.max,O1),xm.subVectors(e.a,O1),_m.subVectors(e.b,O1),bm.subVectors(e.c,O1),Md.subVectors(_m,xm),Ed.subVectors(bm,_m),th.subVectors(xm,bm);let n=[0,-Md.z,Md.y,0,-Ed.z,Ed.y,0,-th.z,th.y,Md.z,0,-Md.x,Ed.z,0,-Ed.x,th.z,0,-th.x,-Md.y,Md.x,0,-Ed.y,Ed.x,0,-th.y,th.x,0];return!p5(n,xm,_m,bm,fb)||(n=[1,0,0,0,1,0,0,0,1],!p5(n,xm,_m,bm,fb))?!1:(hb.crossVectors(Md,Ed),n=[hb.x,hb.y,hb.z],p5(n,xm,_m,bm,fb))}clampPoint(e,n){return n.copy(e).clamp(this.min,this.max)}distanceToPoint(e){return this.clampPoint(e,Rl).distanceTo(e)}getBoundingSphere(e){return this.isEmpty()?e.makeEmpty():(this.getCenter(e.center),e.radius=this.getSize(Rl).length()*.5),e}intersect(e){return this.min.max(e.min),this.max.min(e.max),this.isEmpty()&&this.makeEmpty(),this}union(e){return this.min.min(e.min),this.max.max(e.max),this}applyMatrix4(e){return this.isEmpty()?this:(au[0].set(this.min.x,this.min.y,this.min.z).applyMatrix4(e),au[1].set(this.min.x,this.min.y,this.max.z).applyMatrix4(e),au[2].set(this.min.x,this.max.y,this.min.z).applyMatrix4(e),au[3].set(this.min.x,this.max.y,this.max.z).applyMatrix4(e),au[4].set(this.max.x,this.min.y,this.min.z).applyMatrix4(e),au[5].set(this.max.x,this.min.y,this.max.z).applyMatrix4(e),au[6].set(this.max.x,this.max.y,this.min.z).applyMatrix4(e),au[7].set(this.max.x,this.max.y,this.max.z).applyMatrix4(e),this.setFromPoints(au),this)}translate(e){return this.min.add(e),this.max.add(e),this}equals(e){return e.min.equals(this.min)&&e.max.equals(this.max)}}const au=[new K,new K,new K,new K,new K,new K,new K,new K],Rl=new K,db=new xo,xm=new K,_m=new K,bm=new K,Md=new K,Ed=new K,th=new K,O1=new K,fb=new K,hb=new K,nh=new K;function p5(t,e,n,r,i){for(let s=0,o=t.length-3;s<=o;s+=3){nh.fromArray(t,s);const a=i.x*Math.abs(nh.x)+i.y*Math.abs(nh.y)+i.z*Math.abs(nh.z),l=e.dot(nh),c=n.dot(nh),f=r.dot(nh);if(Math.max(-Math.max(l,c,f),Math.min(l,c,f))>a)return!1}return!0}const ahe=new xo,N1=new K,m5=new K;class Xs{constructor(e=new K,n=-1){this.isSphere=!0,this.center=e,this.radius=n}set(e,n){return this.center.copy(e),this.radius=n,this}setFromPoints(e,n){const r=this.center;n!==void 0?r.copy(n):ahe.setFromPoints(e).getCenter(r);let i=0;for(let s=0,o=e.length;sthis.radius*this.radius&&(n.sub(this.center).normalize(),n.multiplyScalar(this.radius).add(this.center)),n}getBoundingBox(e){return this.isEmpty()?(e.makeEmpty(),e):(e.set(this.center,this.center),e.expandByScalar(this.radius),e)}applyMatrix4(e){return this.center.applyMatrix4(e),this.radius=this.radius*e.getMaxScaleOnAxis(),this}translate(e){return this.center.add(e),this}expandByPoint(e){if(this.isEmpty())return this.center.copy(e),this.radius=0,this;N1.subVectors(e,this.center);const n=N1.lengthSq();if(n>this.radius*this.radius){const r=Math.sqrt(n),i=(r-this.radius)*.5;this.center.addScaledVector(N1,i/r),this.radius+=i}return this}union(e){return e.isEmpty()?this:this.isEmpty()?(this.copy(e),this):(this.center.equals(e.center)===!0?this.radius=Math.max(this.radius,e.radius):(m5.subVectors(e.center,this.center).setLength(e.radius),this.expandByPoint(N1.copy(e.center).add(m5)),this.expandByPoint(N1.copy(e.center).sub(m5))),this)}equals(e){return e.center.equals(this.center)&&e.radius===this.radius}clone(){return new this.constructor().copy(this)}}const lu=new K,g5=new K,pb=new K,Cd=new K,v5=new K,mb=new K,y5=new K;class wp{constructor(e=new K,n=new K(0,0,-1)){this.origin=e,this.direction=n}set(e,n){return this.origin.copy(e),this.direction.copy(n),this}copy(e){return this.origin.copy(e.origin),this.direction.copy(e.direction),this}at(e,n){return n.copy(this.origin).addScaledVector(this.direction,e)}lookAt(e){return this.direction.copy(e).sub(this.origin).normalize(),this}recast(e){return this.origin.copy(this.at(e,lu)),this}closestPointToPoint(e,n){n.subVectors(e,this.origin);const r=n.dot(this.direction);return r<0?n.copy(this.origin):n.copy(this.origin).addScaledVector(this.direction,r)}distanceToPoint(e){return Math.sqrt(this.distanceSqToPoint(e))}distanceSqToPoint(e){const n=lu.subVectors(e,this.origin).dot(this.direction);return n<0?this.origin.distanceToSquared(e):(lu.copy(this.origin).addScaledVector(this.direction,n),lu.distanceToSquared(e))}distanceSqToSegment(e,n,r,i){g5.copy(e).add(n).multiplyScalar(.5),pb.copy(n).sub(e).normalize(),Cd.copy(this.origin).sub(g5);const s=e.distanceTo(n)*.5,o=-this.direction.dot(pb),a=Cd.dot(this.direction),l=-Cd.dot(pb),c=Cd.lengthSq(),f=Math.abs(1-o*o);let p,g,v,x;if(f>0)if(p=o*l-a,g=o*a-l,x=s*f,p>=0)if(g>=-x)if(g<=x){const _=1/f;p*=_,g*=_,v=p*(p+o*g+2*a)+g*(o*p+g+2*l)+c}else g=s,p=Math.max(0,-(o*g+a)),v=-p*p+g*(g+2*l)+c;else g=-s,p=Math.max(0,-(o*g+a)),v=-p*p+g*(g+2*l)+c;else g<=-x?(p=Math.max(0,-(-o*s+a)),g=p>0?-s:Math.min(Math.max(-s,-l),s),v=-p*p+g*(g+2*l)+c):g<=x?(p=0,g=Math.min(Math.max(-s,-l),s),v=g*(g+2*l)+c):(p=Math.max(0,-(o*s+a)),g=p>0?s:Math.min(Math.max(-s,-l),s),v=-p*p+g*(g+2*l)+c);else g=o>0?-s:s,p=Math.max(0,-(o*g+a)),v=-p*p+g*(g+2*l)+c;return r&&r.copy(this.origin).addScaledVector(this.direction,p),i&&i.copy(g5).addScaledVector(pb,g),v}intersectSphere(e,n){lu.subVectors(e.center,this.origin);const r=lu.dot(this.direction),i=lu.dot(lu)-r*r,s=e.radius*e.radius;if(i>s)return null;const o=Math.sqrt(s-i),a=r-o,l=r+o;return l<0?null:a<0?this.at(l,n):this.at(a,n)}intersectsSphere(e){return this.distanceSqToPoint(e.center)<=e.radius*e.radius}distanceToPlane(e){const n=e.normal.dot(this.direction);if(n===0)return e.distanceToPoint(this.origin)===0?0:null;const r=-(this.origin.dot(e.normal)+e.constant)/n;return r>=0?r:null}intersectPlane(e,n){const r=this.distanceToPlane(e);return r===null?null:this.at(r,n)}intersectsPlane(e){const n=e.distanceToPoint(this.origin);return n===0||e.normal.dot(this.direction)*n<0}intersectBox(e,n){let r,i,s,o,a,l;const c=1/this.direction.x,f=1/this.direction.y,p=1/this.direction.z,g=this.origin;return c>=0?(r=(e.min.x-g.x)*c,i=(e.max.x-g.x)*c):(r=(e.max.x-g.x)*c,i=(e.min.x-g.x)*c),f>=0?(s=(e.min.y-g.y)*f,o=(e.max.y-g.y)*f):(s=(e.max.y-g.y)*f,o=(e.min.y-g.y)*f),r>o||s>i||((s>r||isNaN(r))&&(r=s),(o=0?(a=(e.min.z-g.z)*p,l=(e.max.z-g.z)*p):(a=(e.max.z-g.z)*p,l=(e.min.z-g.z)*p),r>l||a>i)||((a>r||r!==r)&&(r=a),(l=0?r:i,n)}intersectsBox(e){return this.intersectBox(e,lu)!==null}intersectTriangle(e,n,r,i,s){v5.subVectors(n,e),mb.subVectors(r,e),y5.crossVectors(v5,mb);let o=this.direction.dot(y5),a;if(o>0){if(i)return null;a=1}else if(o<0)a=-1,o=-o;else return null;Cd.subVectors(this.origin,e);const l=a*this.direction.dot(mb.crossVectors(Cd,mb));if(l<0)return null;const c=a*this.direction.dot(v5.cross(Cd));if(c<0||l+c>o)return null;const f=-a*Cd.dot(y5);return f<0?null:this.at(f/o,s)}applyMatrix4(e){return this.origin.applyMatrix4(e),this.direction.transformDirection(e),this}equals(e){return e.origin.equals(this.origin)&&e.direction.equals(this.direction)}clone(){return new this.constructor().copy(this)}}class Jt{constructor(e,n,r,i,s,o,a,l,c,f,p,g,v,x,_,b){Jt.prototype.isMatrix4=!0,this.elements=[1,0,0,0,0,1,0,0,0,0,1,0,0,0,0,1],e!==void 0&&this.set(e,n,r,i,s,o,a,l,c,f,p,g,v,x,_,b)}set(e,n,r,i,s,o,a,l,c,f,p,g,v,x,_,b){const y=this.elements;return y[0]=e,y[4]=n,y[8]=r,y[12]=i,y[1]=s,y[5]=o,y[9]=a,y[13]=l,y[2]=c,y[6]=f,y[10]=p,y[14]=g,y[3]=v,y[7]=x,y[11]=_,y[15]=b,this}identity(){return this.set(1,0,0,0,0,1,0,0,0,0,1,0,0,0,0,1),this}clone(){return new Jt().fromArray(this.elements)}copy(e){const n=this.elements,r=e.elements;return n[0]=r[0],n[1]=r[1],n[2]=r[2],n[3]=r[3],n[4]=r[4],n[5]=r[5],n[6]=r[6],n[7]=r[7],n[8]=r[8],n[9]=r[9],n[10]=r[10],n[11]=r[11],n[12]=r[12],n[13]=r[13],n[14]=r[14],n[15]=r[15],this}copyPosition(e){const n=this.elements,r=e.elements;return n[12]=r[12],n[13]=r[13],n[14]=r[14],this}setFromMatrix3(e){const n=e.elements;return this.set(n[0],n[3],n[6],0,n[1],n[4],n[7],0,n[2],n[5],n[8],0,0,0,0,1),this}extractBasis(e,n,r){return e.setFromMatrixColumn(this,0),n.setFromMatrixColumn(this,1),r.setFromMatrixColumn(this,2),this}makeBasis(e,n,r){return this.set(e.x,n.x,r.x,0,e.y,n.y,r.y,0,e.z,n.z,r.z,0,0,0,0,1),this}extractRotation(e){const n=this.elements,r=e.elements,i=1/Sm.setFromMatrixColumn(e,0).length(),s=1/Sm.setFromMatrixColumn(e,1).length(),o=1/Sm.setFromMatrixColumn(e,2).length();return n[0]=r[0]*i,n[1]=r[1]*i,n[2]=r[2]*i,n[3]=0,n[4]=r[4]*s,n[5]=r[5]*s,n[6]=r[6]*s,n[7]=0,n[8]=r[8]*o,n[9]=r[9]*o,n[10]=r[10]*o,n[11]=0,n[12]=0,n[13]=0,n[14]=0,n[15]=1,this}makeRotationFromEuler(e){const n=this.elements,r=e.x,i=e.y,s=e.z,o=Math.cos(r),a=Math.sin(r),l=Math.cos(i),c=Math.sin(i),f=Math.cos(s),p=Math.sin(s);if(e.order==="XYZ"){const g=o*f,v=o*p,x=a*f,_=a*p;n[0]=l*f,n[4]=-l*p,n[8]=c,n[1]=v+x*c,n[5]=g-_*c,n[9]=-a*l,n[2]=_-g*c,n[6]=x+v*c,n[10]=o*l}else if(e.order==="YXZ"){const g=l*f,v=l*p,x=c*f,_=c*p;n[0]=g+_*a,n[4]=x*a-v,n[8]=o*c,n[1]=o*p,n[5]=o*f,n[9]=-a,n[2]=v*a-x,n[6]=_+g*a,n[10]=o*l}else if(e.order==="ZXY"){const g=l*f,v=l*p,x=c*f,_=c*p;n[0]=g-_*a,n[4]=-o*p,n[8]=x+v*a,n[1]=v+x*a,n[5]=o*f,n[9]=_-g*a,n[2]=-o*c,n[6]=a,n[10]=o*l}else if(e.order==="ZYX"){const g=o*f,v=o*p,x=a*f,_=a*p;n[0]=l*f,n[4]=x*c-v,n[8]=g*c+_,n[1]=l*p,n[5]=_*c+g,n[9]=v*c-x,n[2]=-c,n[6]=a*l,n[10]=o*l}else if(e.order==="YZX"){const g=o*l,v=o*c,x=a*l,_=a*c;n[0]=l*f,n[4]=_-g*p,n[8]=x*p+v,n[1]=p,n[5]=o*f,n[9]=-a*f,n[2]=-c*f,n[6]=v*p+x,n[10]=g-_*p}else if(e.order==="XZY"){const g=o*l,v=o*c,x=a*l,_=a*c;n[0]=l*f,n[4]=-p,n[8]=c*f,n[1]=g*p+_,n[5]=o*f,n[9]=v*p-x,n[2]=x*p-v,n[6]=a*f,n[10]=_*p+g}return n[3]=0,n[7]=0,n[11]=0,n[12]=0,n[13]=0,n[14]=0,n[15]=1,this}makeRotationFromQuaternion(e){return this.compose(lhe,e,che)}lookAt(e,n,r){const i=this.elements;return da.subVectors(e,n),da.lengthSq()===0&&(da.z=1),da.normalize(),Td.crossVectors(r,da),Td.lengthSq()===0&&(Math.abs(r.z)===1?da.x+=1e-4:da.z+=1e-4,da.normalize(),Td.crossVectors(r,da)),Td.normalize(),gb.crossVectors(da,Td),i[0]=Td.x,i[4]=gb.x,i[8]=da.x,i[1]=Td.y,i[5]=gb.y,i[9]=da.y,i[2]=Td.z,i[6]=gb.z,i[10]=da.z,this}multiply(e){return this.multiplyMatrices(this,e)}premultiply(e){return this.multiplyMatrices(e,this)}multiplyMatrices(e,n){const r=e.elements,i=n.elements,s=this.elements,o=r[0],a=r[4],l=r[8],c=r[12],f=r[1],p=r[5],g=r[9],v=r[13],x=r[2],_=r[6],b=r[10],y=r[14],S=r[3],w=r[7],T=r[11],L=r[15],R=i[0],P=i[4],F=i[8],O=i[12],I=i[1],H=i[5],Q=i[9],q=i[13],le=i[2],ie=i[6],ee=i[10],ue=i[14],z=i[3],te=i[7],oe=i[11],de=i[15];return s[0]=o*R+a*I+l*le+c*z,s[4]=o*P+a*H+l*ie+c*te,s[8]=o*F+a*Q+l*ee+c*oe,s[12]=o*O+a*q+l*ue+c*de,s[1]=f*R+p*I+g*le+v*z,s[5]=f*P+p*H+g*ie+v*te,s[9]=f*F+p*Q+g*ee+v*oe,s[13]=f*O+p*q+g*ue+v*de,s[2]=x*R+_*I+b*le+y*z,s[6]=x*P+_*H+b*ie+y*te,s[10]=x*F+_*Q+b*ee+y*oe,s[14]=x*O+_*q+b*ue+y*de,s[3]=S*R+w*I+T*le+L*z,s[7]=S*P+w*H+T*ie+L*te,s[11]=S*F+w*Q+T*ee+L*oe,s[15]=S*O+w*q+T*ue+L*de,this}multiplyScalar(e){const n=this.elements;return n[0]*=e,n[4]*=e,n[8]*=e,n[12]*=e,n[1]*=e,n[5]*=e,n[9]*=e,n[13]*=e,n[2]*=e,n[6]*=e,n[10]*=e,n[14]*=e,n[3]*=e,n[7]*=e,n[11]*=e,n[15]*=e,this}determinant(){const e=this.elements,n=e[0],r=e[4],i=e[8],s=e[12],o=e[1],a=e[5],l=e[9],c=e[13],f=e[2],p=e[6],g=e[10],v=e[14],x=e[3],_=e[7],b=e[11],y=e[15];return x*(+s*l*p-i*c*p-s*a*g+r*c*g+i*a*v-r*l*v)+_*(+n*l*v-n*c*g+s*o*g-i*o*v+i*c*f-s*l*f)+b*(+n*c*p-n*a*v-s*o*p+r*o*v+s*a*f-r*c*f)+y*(-i*a*f-n*l*p+n*a*g+i*o*p-r*o*g+r*l*f)}transpose(){const e=this.elements;let n;return n=e[1],e[1]=e[4],e[4]=n,n=e[2],e[2]=e[8],e[8]=n,n=e[6],e[6]=e[9],e[9]=n,n=e[3],e[3]=e[12],e[12]=n,n=e[7],e[7]=e[13],e[13]=n,n=e[11],e[11]=e[14],e[14]=n,this}setPosition(e,n,r){const i=this.elements;return e.isVector3?(i[12]=e.x,i[13]=e.y,i[14]=e.z):(i[12]=e,i[13]=n,i[14]=r),this}invert(){const e=this.elements,n=e[0],r=e[1],i=e[2],s=e[3],o=e[4],a=e[5],l=e[6],c=e[7],f=e[8],p=e[9],g=e[10],v=e[11],x=e[12],_=e[13],b=e[14],y=e[15],S=p*b*c-_*g*c+_*l*v-a*b*v-p*l*y+a*g*y,w=x*g*c-f*b*c-x*l*v+o*b*v+f*l*y-o*g*y,T=f*_*c-x*p*c+x*a*v-o*_*v-f*a*y+o*p*y,L=x*p*l-f*_*l-x*a*g+o*_*g+f*a*b-o*p*b,R=n*S+r*w+i*T+s*L;if(R===0)return this.set(0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0);const P=1/R;return e[0]=S*P,e[1]=(_*g*s-p*b*s-_*i*v+r*b*v+p*i*y-r*g*y)*P,e[2]=(a*b*s-_*l*s+_*i*c-r*b*c-a*i*y+r*l*y)*P,e[3]=(p*l*s-a*g*s-p*i*c+r*g*c+a*i*v-r*l*v)*P,e[4]=w*P,e[5]=(f*b*s-x*g*s+x*i*v-n*b*v-f*i*y+n*g*y)*P,e[6]=(x*l*s-o*b*s-x*i*c+n*b*c+o*i*y-n*l*y)*P,e[7]=(o*g*s-f*l*s+f*i*c-n*g*c-o*i*v+n*l*v)*P,e[8]=T*P,e[9]=(x*p*s-f*_*s-x*r*v+n*_*v+f*r*y-n*p*y)*P,e[10]=(o*_*s-x*a*s+x*r*c-n*_*c-o*r*y+n*a*y)*P,e[11]=(f*a*s-o*p*s-f*r*c+n*p*c+o*r*v-n*a*v)*P,e[12]=L*P,e[13]=(f*_*i-x*p*i+x*r*g-n*_*g-f*r*b+n*p*b)*P,e[14]=(x*a*i-o*_*i-x*r*l+n*_*l+o*r*b-n*a*b)*P,e[15]=(o*p*i-f*a*i+f*r*l-n*p*l-o*r*g+n*a*g)*P,this}scale(e){const n=this.elements,r=e.x,i=e.y,s=e.z;return n[0]*=r,n[4]*=i,n[8]*=s,n[1]*=r,n[5]*=i,n[9]*=s,n[2]*=r,n[6]*=i,n[10]*=s,n[3]*=r,n[7]*=i,n[11]*=s,this}getMaxScaleOnAxis(){const e=this.elements,n=e[0]*e[0]+e[1]*e[1]+e[2]*e[2],r=e[4]*e[4]+e[5]*e[5]+e[6]*e[6],i=e[8]*e[8]+e[9]*e[9]+e[10]*e[10];return Math.sqrt(Math.max(n,r,i))}makeTranslation(e,n,r){return e.isVector3?this.set(1,0,0,e.x,0,1,0,e.y,0,0,1,e.z,0,0,0,1):this.set(1,0,0,e,0,1,0,n,0,0,1,r,0,0,0,1),this}makeRotationX(e){const n=Math.cos(e),r=Math.sin(e);return this.set(1,0,0,0,0,n,-r,0,0,r,n,0,0,0,0,1),this}makeRotationY(e){const n=Math.cos(e),r=Math.sin(e);return this.set(n,0,r,0,0,1,0,0,-r,0,n,0,0,0,0,1),this}makeRotationZ(e){const n=Math.cos(e),r=Math.sin(e);return this.set(n,-r,0,0,r,n,0,0,0,0,1,0,0,0,0,1),this}makeRotationAxis(e,n){const r=Math.cos(n),i=Math.sin(n),s=1-r,o=e.x,a=e.y,l=e.z,c=s*o,f=s*a;return this.set(c*o+r,c*a-i*l,c*l+i*a,0,c*a+i*l,f*a+r,f*l-i*o,0,c*l-i*a,f*l+i*o,s*l*l+r,0,0,0,0,1),this}makeScale(e,n,r){return this.set(e,0,0,0,0,n,0,0,0,0,r,0,0,0,0,1),this}makeShear(e,n,r,i,s,o){return this.set(1,r,s,0,e,1,o,0,n,i,1,0,0,0,0,1),this}compose(e,n,r){const i=this.elements,s=n._x,o=n._y,a=n._z,l=n._w,c=s+s,f=o+o,p=a+a,g=s*c,v=s*f,x=s*p,_=o*f,b=o*p,y=a*p,S=l*c,w=l*f,T=l*p,L=r.x,R=r.y,P=r.z;return i[0]=(1-(_+y))*L,i[1]=(v+T)*L,i[2]=(x-w)*L,i[3]=0,i[4]=(v-T)*R,i[5]=(1-(g+y))*R,i[6]=(b+S)*R,i[7]=0,i[8]=(x+w)*P,i[9]=(b-S)*P,i[10]=(1-(g+_))*P,i[11]=0,i[12]=e.x,i[13]=e.y,i[14]=e.z,i[15]=1,this}decompose(e,n,r){const i=this.elements;let s=Sm.set(i[0],i[1],i[2]).length();const o=Sm.set(i[4],i[5],i[6]).length(),a=Sm.set(i[8],i[9],i[10]).length();this.determinant()<0&&(s=-s),e.x=i[12],e.y=i[13],e.z=i[14],Pl.copy(this);const c=1/s,f=1/o,p=1/a;return Pl.elements[0]*=c,Pl.elements[1]*=c,Pl.elements[2]*=c,Pl.elements[4]*=f,Pl.elements[5]*=f,Pl.elements[6]*=f,Pl.elements[8]*=p,Pl.elements[9]*=p,Pl.elements[10]*=p,n.setFromRotationMatrix(Pl),r.x=s,r.y=o,r.z=a,this}makePerspective(e,n,r,i,s,o,a=Ec){const l=this.elements,c=2*s/(n-e),f=2*s/(r-i),p=(n+e)/(n-e),g=(r+i)/(r-i);let v,x;if(a===Ec)v=-(o+s)/(o-s),x=-2*o*s/(o-s);else if(a===my)v=-o/(o-s),x=-o*s/(o-s);else throw new Error("THREE.Matrix4.makePerspective(): Invalid coordinate system: "+a);return l[0]=c,l[4]=0,l[8]=p,l[12]=0,l[1]=0,l[5]=f,l[9]=g,l[13]=0,l[2]=0,l[6]=0,l[10]=v,l[14]=x,l[3]=0,l[7]=0,l[11]=-1,l[15]=0,this}makeOrthographic(e,n,r,i,s,o,a=Ec){const l=this.elements,c=1/(n-e),f=1/(r-i),p=1/(o-s),g=(n+e)*c,v=(r+i)*f;let x,_;if(a===Ec)x=(o+s)*p,_=-2*p;else if(a===my)x=s*p,_=-1*p;else throw new Error("THREE.Matrix4.makeOrthographic(): Invalid coordinate system: "+a);return l[0]=2*c,l[4]=0,l[8]=0,l[12]=-g,l[1]=0,l[5]=2*f,l[9]=0,l[13]=-v,l[2]=0,l[6]=0,l[10]=_,l[14]=-x,l[3]=0,l[7]=0,l[11]=0,l[15]=1,this}equals(e){const n=this.elements,r=e.elements;for(let i=0;i<16;i++)if(n[i]!==r[i])return!1;return!0}fromArray(e,n=0){for(let r=0;r<16;r++)this.elements[r]=e[r+n];return this}toArray(e=[],n=0){const r=this.elements;return e[n]=r[0],e[n+1]=r[1],e[n+2]=r[2],e[n+3]=r[3],e[n+4]=r[4],e[n+5]=r[5],e[n+6]=r[6],e[n+7]=r[7],e[n+8]=r[8],e[n+9]=r[9],e[n+10]=r[10],e[n+11]=r[11],e[n+12]=r[12],e[n+13]=r[13],e[n+14]=r[14],e[n+15]=r[15],e}}const Sm=new K,Pl=new Jt,lhe=new K(0,0,0),che=new K(1,1,1),Td=new K,gb=new K,da=new K,pO=new Jt,mO=new sr;class ns{constructor(e=0,n=0,r=0,i=ns.DEFAULT_ORDER){this.isEuler=!0,this._x=e,this._y=n,this._z=r,this._order=i}get x(){return this._x}set x(e){this._x=e,this._onChangeCallback()}get y(){return this._y}set y(e){this._y=e,this._onChangeCallback()}get z(){return this._z}set z(e){this._z=e,this._onChangeCallback()}get order(){return this._order}set order(e){this._order=e,this._onChangeCallback()}set(e,n,r,i=this._order){return this._x=e,this._y=n,this._z=r,this._order=i,this._onChangeCallback(),this}clone(){return new this.constructor(this._x,this._y,this._z,this._order)}copy(e){return this._x=e._x,this._y=e._y,this._z=e._z,this._order=e._order,this._onChangeCallback(),this}setFromRotationMatrix(e,n=this._order,r=!0){const i=e.elements,s=i[0],o=i[4],a=i[8],l=i[1],c=i[5],f=i[9],p=i[2],g=i[6],v=i[10];switch(n){case"XYZ":this._y=Math.asin(wi(a,-1,1)),Math.abs(a)<.9999999?(this._x=Math.atan2(-f,v),this._z=Math.atan2(-o,s)):(this._x=Math.atan2(g,c),this._z=0);break;case"YXZ":this._x=Math.asin(-wi(f,-1,1)),Math.abs(f)<.9999999?(this._y=Math.atan2(a,v),this._z=Math.atan2(l,c)):(this._y=Math.atan2(-p,s),this._z=0);break;case"ZXY":this._x=Math.asin(wi(g,-1,1)),Math.abs(g)<.9999999?(this._y=Math.atan2(-p,v),this._z=Math.atan2(-o,c)):(this._y=0,this._z=Math.atan2(l,s));break;case"ZYX":this._y=Math.asin(-wi(p,-1,1)),Math.abs(p)<.9999999?(this._x=Math.atan2(g,v),this._z=Math.atan2(l,s)):(this._x=0,this._z=Math.atan2(-o,c));break;case"YZX":this._z=Math.asin(wi(l,-1,1)),Math.abs(l)<.9999999?(this._x=Math.atan2(-f,c),this._y=Math.atan2(-p,s)):(this._x=0,this._y=Math.atan2(a,v));break;case"XZY":this._z=Math.asin(-wi(o,-1,1)),Math.abs(o)<.9999999?(this._x=Math.atan2(g,c),this._y=Math.atan2(a,s)):(this._x=Math.atan2(-f,v),this._y=0);break;default:console.warn("THREE.Euler: .setFromRotationMatrix() encountered an unknown order: "+n)}return this._order=n,r===!0&&this._onChangeCallback(),this}setFromQuaternion(e,n,r){return pO.makeRotationFromQuaternion(e),this.setFromRotationMatrix(pO,n,r)}setFromVector3(e,n=this._order){return this.set(e.x,e.y,e.z,n)}reorder(e){return mO.setFromEuler(this),this.setFromQuaternion(mO,e)}equals(e){return e._x===this._x&&e._y===this._y&&e._z===this._z&&e._order===this._order}fromArray(e){return this._x=e[0],this._y=e[1],this._z=e[2],e[3]!==void 0&&(this._order=e[3]),this._onChangeCallback(),this}toArray(e=[],n=0){return e[n]=this._x,e[n+1]=this._y,e[n+2]=this._z,e[n+3]=this._order,e}_onChange(e){return this._onChangeCallback=e,this}_onChangeCallback(){}*[Symbol.iterator](){yield this._x,yield this._y,yield this._z,yield this._order}}ns.DEFAULT_ORDER="XYZ";class Jh{constructor(){this.mask=1}set(e){this.mask=(1<>>0}enable(e){this.mask|=1<1){for(let n=0;n1){for(let r=0;r0&&(i.userData=this.userData),i.layers=this.layers.mask,i.matrix=this.matrix.toArray(),i.up=this.up.toArray(),this.matrixAutoUpdate===!1&&(i.matrixAutoUpdate=!1),this.isInstancedMesh&&(i.type="InstancedMesh",i.count=this.count,i.instanceMatrix=this.instanceMatrix.toJSON(),this.instanceColor!==null&&(i.instanceColor=this.instanceColor.toJSON())),this.isBatchedMesh&&(i.type="BatchedMesh",i.perObjectFrustumCulled=this.perObjectFrustumCulled,i.sortObjects=this.sortObjects,i.drawRanges=this._drawRanges,i.reservedRanges=this._reservedRanges,i.visibility=this._visibility,i.active=this._active,i.bounds=this._bounds.map(a=>({boxInitialized:a.boxInitialized,boxMin:a.box.min.toArray(),boxMax:a.box.max.toArray(),sphereInitialized:a.sphereInitialized,sphereRadius:a.sphere.radius,sphereCenter:a.sphere.center.toArray()})),i.maxGeometryCount=this._maxGeometryCount,i.maxVertexCount=this._maxVertexCount,i.maxIndexCount=this._maxIndexCount,i.geometryInitialized=this._geometryInitialized,i.geometryCount=this._geometryCount,i.matricesTexture=this._matricesTexture.toJSON(e),this.boundingSphere!==null&&(i.boundingSphere={center:i.boundingSphere.center.toArray(),radius:i.boundingSphere.radius}),this.boundingBox!==null&&(i.boundingBox={min:i.boundingBox.min.toArray(),max:i.boundingBox.max.toArray()}));function s(a,l){return a[l.uuid]===void 0&&(a[l.uuid]=l.toJSON(e)),l.uuid}if(this.isScene)this.background&&(this.background.isColor?i.background=this.background.toJSON():this.background.isTexture&&(i.background=this.background.toJSON(e).uuid)),this.environment&&this.environment.isTexture&&this.environment.isRenderTargetTexture!==!0&&(i.environment=this.environment.toJSON(e).uuid);else if(this.isMesh||this.isLine||this.isPoints){i.geometry=s(e.geometries,this.geometry);const a=this.geometry.parameters;if(a!==void 0&&a.shapes!==void 0){const l=a.shapes;if(Array.isArray(l))for(let c=0,f=l.length;c0){i.children=[];for(let a=0;a0){i.animations=[];for(let a=0;a0&&(r.geometries=a),l.length>0&&(r.materials=l),c.length>0&&(r.textures=c),f.length>0&&(r.images=f),p.length>0&&(r.shapes=p),g.length>0&&(r.skeletons=g),v.length>0&&(r.animations=v),x.length>0&&(r.nodes=x)}return r.object=i,r;function o(a){const l=[];for(const c in a){const f=a[c];delete f.metadata,l.push(f)}return l}}clone(e){return new this.constructor().copy(this,e)}copy(e,n=!0){if(this.name=e.name,this.up.copy(e.up),this.position.copy(e.position),this.rotation.order=e.rotation.order,this.quaternion.copy(e.quaternion),this.scale.copy(e.scale),this.matrix.copy(e.matrix),this.matrixWorld.copy(e.matrixWorld),this.matrixAutoUpdate=e.matrixAutoUpdate,this.matrixWorldAutoUpdate=e.matrixWorldAutoUpdate,this.matrixWorldNeedsUpdate=e.matrixWorldNeedsUpdate,this.layers.mask=e.layers.mask,this.visible=e.visible,this.castShadow=e.castShadow,this.receiveShadow=e.receiveShadow,this.frustumCulled=e.frustumCulled,this.renderOrder=e.renderOrder,this.animations=e.animations.slice(),this.userData=JSON.parse(JSON.stringify(e.userData)),n===!0)for(let r=0;r0?i.multiplyScalar(1/Math.sqrt(s)):i.set(0,0,0)}static getBarycoord(e,n,r,i,s){Il.subVectors(i,n),uu.subVectors(r,n),_5.subVectors(e,n);const o=Il.dot(Il),a=Il.dot(uu),l=Il.dot(_5),c=uu.dot(uu),f=uu.dot(_5),p=o*c-a*a;if(p===0)return s.set(0,0,0),null;const g=1/p,v=(c*l-a*f)*g,x=(o*f-a*l)*g;return s.set(1-v-x,x,v)}static containsPoint(e,n,r,i){return this.getBarycoord(e,n,r,i,du)===null?!1:du.x>=0&&du.y>=0&&du.x+du.y<=1}static getInterpolation(e,n,r,i,s,o,a,l){return this.getBarycoord(e,n,r,i,du)===null?(l.x=0,l.y=0,"z"in l&&(l.z=0),"w"in l&&(l.w=0),null):(l.setScalar(0),l.addScaledVector(s,du.x),l.addScaledVector(o,du.y),l.addScaledVector(a,du.z),l)}static isFrontFacing(e,n,r,i){return Il.subVectors(r,n),uu.subVectors(e,n),Il.cross(uu).dot(i)<0}set(e,n,r){return this.a.copy(e),this.b.copy(n),this.c.copy(r),this}setFromPointsAndIndices(e,n,r,i){return this.a.copy(e[n]),this.b.copy(e[r]),this.c.copy(e[i]),this}setFromAttributeAndIndices(e,n,r,i){return this.a.fromBufferAttribute(e,n),this.b.fromBufferAttribute(e,r),this.c.fromBufferAttribute(e,i),this}clone(){return new this.constructor().copy(this)}copy(e){return this.a.copy(e.a),this.b.copy(e.b),this.c.copy(e.c),this}getArea(){return Il.subVectors(this.c,this.b),uu.subVectors(this.a,this.b),Il.cross(uu).length()*.5}getMidpoint(e){return e.addVectors(this.a,this.b).add(this.c).multiplyScalar(1/3)}getNormal(e){return xa.getNormal(this.a,this.b,this.c,e)}getPlane(e){return e.setFromCoplanarPoints(this.a,this.b,this.c)}getBarycoord(e,n){return xa.getBarycoord(e,this.a,this.b,this.c,n)}getInterpolation(e,n,r,i,s){return xa.getInterpolation(e,this.a,this.b,this.c,n,r,i,s)}containsPoint(e){return xa.containsPoint(e,this.a,this.b,this.c)}isFrontFacing(e){return xa.isFrontFacing(this.a,this.b,this.c,e)}intersectsBox(e){return e.intersectsTriangle(this)}closestPointToPoint(e,n){const r=this.a,i=this.b,s=this.c;let o,a;Em.subVectors(i,r),Cm.subVectors(s,r),b5.subVectors(e,r);const l=Em.dot(b5),c=Cm.dot(b5);if(l<=0&&c<=0)return n.copy(r);S5.subVectors(e,i);const f=Em.dot(S5),p=Cm.dot(S5);if(f>=0&&p<=f)return n.copy(i);const g=l*p-f*c;if(g<=0&&l>=0&&f<=0)return o=l/(l-f),n.copy(r).addScaledVector(Em,o);w5.subVectors(e,s);const v=Em.dot(w5),x=Cm.dot(w5);if(x>=0&&v<=x)return n.copy(s);const _=v*c-l*x;if(_<=0&&c>=0&&x<=0)return a=c/(c-x),n.copy(r).addScaledVector(Cm,a);const b=f*x-v*p;if(b<=0&&p-f>=0&&v-x>=0)return bO.subVectors(s,i),a=(p-f)/(p-f+(v-x)),n.copy(i).addScaledVector(bO,a);const y=1/(b+_+g);return o=_*y,a=g*y,n.copy(r).addScaledVector(Em,o).addScaledVector(Cm,a)}equals(e){return e.a.equals(this.a)&&e.b.equals(this.b)&&e.c.equals(this.c)}}const QU={aliceblue:15792383,antiquewhite:16444375,aqua:65535,aquamarine:8388564,azure:15794175,beige:16119260,bisque:16770244,black:0,blanchedalmond:16772045,blue:255,blueviolet:9055202,brown:10824234,burlywood:14596231,cadetblue:6266528,chartreuse:8388352,chocolate:13789470,coral:16744272,cornflowerblue:6591981,cornsilk:16775388,crimson:14423100,cyan:65535,darkblue:139,darkcyan:35723,darkgoldenrod:12092939,darkgray:11119017,darkgreen:25600,darkgrey:11119017,darkkhaki:12433259,darkmagenta:9109643,darkolivegreen:5597999,darkorange:16747520,darkorchid:10040012,darkred:9109504,darksalmon:15308410,darkseagreen:9419919,darkslateblue:4734347,darkslategray:3100495,darkslategrey:3100495,darkturquoise:52945,darkviolet:9699539,deeppink:16716947,deepskyblue:49151,dimgray:6908265,dimgrey:6908265,dodgerblue:2003199,firebrick:11674146,floralwhite:16775920,forestgreen:2263842,fuchsia:16711935,gainsboro:14474460,ghostwhite:16316671,gold:16766720,goldenrod:14329120,gray:8421504,green:32768,greenyellow:11403055,grey:8421504,honeydew:15794160,hotpink:16738740,indianred:13458524,indigo:4915330,ivory:16777200,khaki:15787660,lavender:15132410,lavenderblush:16773365,lawngreen:8190976,lemonchiffon:16775885,lightblue:11393254,lightcoral:15761536,lightcyan:14745599,lightgoldenrodyellow:16448210,lightgray:13882323,lightgreen:9498256,lightgrey:13882323,lightpink:16758465,lightsalmon:16752762,lightseagreen:2142890,lightskyblue:8900346,lightslategray:7833753,lightslategrey:7833753,lightsteelblue:11584734,lightyellow:16777184,lime:65280,limegreen:3329330,linen:16445670,magenta:16711935,maroon:8388608,mediumaquamarine:6737322,mediumblue:205,mediumorchid:12211667,mediumpurple:9662683,mediumseagreen:3978097,mediumslateblue:8087790,mediumspringgreen:64154,mediumturquoise:4772300,mediumvioletred:13047173,midnightblue:1644912,mintcream:16121850,mistyrose:16770273,moccasin:16770229,navajowhite:16768685,navy:128,oldlace:16643558,olive:8421376,olivedrab:7048739,orange:16753920,orangered:16729344,orchid:14315734,palegoldenrod:15657130,palegreen:10025880,paleturquoise:11529966,palevioletred:14381203,papayawhip:16773077,peachpuff:16767673,peru:13468991,pink:16761035,plum:14524637,powderblue:11591910,purple:8388736,rebeccapurple:6697881,red:16711680,rosybrown:12357519,royalblue:4286945,saddlebrown:9127187,salmon:16416882,sandybrown:16032864,seagreen:3050327,seashell:16774638,sienna:10506797,silver:12632256,skyblue:8900331,slateblue:6970061,slategray:7372944,slategrey:7372944,snow:16775930,springgreen:65407,steelblue:4620980,tan:13808780,teal:32896,thistle:14204888,tomato:16737095,turquoise:4251856,violet:15631086,wheat:16113331,white:16777215,whitesmoke:16119285,yellow:16776960,yellowgreen:10145074},Ad={h:0,s:0,l:0},yb={h:0,s:0,l:0};function M5(t,e,n){return n<0&&(n+=1),n>1&&(n-=1),n<1/6?t+(e-t)*6*n:n<1/2?e:n<2/3?t+(e-t)*6*(2/3-n):t}class It{constructor(e,n,r){return this.isColor=!0,this.r=1,this.g=1,this.b=1,this.set(e,n,r)}set(e,n,r){if(n===void 0&&r===void 0){const i=e;i&&i.isColor?this.copy(i):typeof i=="number"?this.setHex(i):typeof i=="string"&&this.setStyle(i)}else this.setRGB(e,n,r);return this}setScalar(e){return this.r=e,this.g=e,this.b=e,this}setHex(e,n=ho){return e=Math.floor(e),this.r=(e>>16&255)/255,this.g=(e>>8&255)/255,this.b=(e&255)/255,br.toWorkingColorSpace(this,n),this}setRGB(e,n,r,i=br.workingColorSpace){return this.r=e,this.g=n,this.b=r,br.toWorkingColorSpace(this,i),this}setHSL(e,n,r,i=br.workingColorSpace){if(e=tP(e,1),n=wi(n,0,1),r=wi(r,0,1),n===0)this.r=this.g=this.b=r;else{const s=r<=.5?r*(1+n):r+n-r*n,o=2*r-s;this.r=M5(o,s,e+1/3),this.g=M5(o,s,e),this.b=M5(o,s,e-1/3)}return br.toWorkingColorSpace(this,i),this}setStyle(e,n=ho){function r(s){s!==void 0&&parseFloat(s)<1&&console.warn("THREE.Color: Alpha component of "+e+" will be ignored.")}let i;if(i=/^(\w+)\(([^\)]*)\)/.exec(e)){let s;const o=i[1],a=i[2];switch(o){case"rgb":case"rgba":if(s=/^\s*(\d+)\s*,\s*(\d+)\s*,\s*(\d+)\s*(?:,\s*(\d*\.?\d+)\s*)?$/.exec(a))return r(s[4]),this.setRGB(Math.min(255,parseInt(s[1],10))/255,Math.min(255,parseInt(s[2],10))/255,Math.min(255,parseInt(s[3],10))/255,n);if(s=/^\s*(\d+)\%\s*,\s*(\d+)\%\s*,\s*(\d+)\%\s*(?:,\s*(\d*\.?\d+)\s*)?$/.exec(a))return r(s[4]),this.setRGB(Math.min(100,parseInt(s[1],10))/100,Math.min(100,parseInt(s[2],10))/100,Math.min(100,parseInt(s[3],10))/100,n);break;case"hsl":case"hsla":if(s=/^\s*(\d*\.?\d+)\s*,\s*(\d*\.?\d+)\%\s*,\s*(\d*\.?\d+)\%\s*(?:,\s*(\d*\.?\d+)\s*)?$/.exec(a))return r(s[4]),this.setHSL(parseFloat(s[1])/360,parseFloat(s[2])/100,parseFloat(s[3])/100,n);break;default:console.warn("THREE.Color: Unknown color model "+e)}}else if(i=/^\#([A-Fa-f\d]+)$/.exec(e)){const s=i[1],o=s.length;if(o===3)return this.setRGB(parseInt(s.charAt(0),16)/15,parseInt(s.charAt(1),16)/15,parseInt(s.charAt(2),16)/15,n);if(o===6)return this.setHex(parseInt(s,16),n);console.warn("THREE.Color: Invalid hex color "+e)}else if(e&&e.length>0)return this.setColorName(e,n);return this}setColorName(e,n=ho){const r=QU[e.toLowerCase()];return r!==void 0?this.setHex(r,n):console.warn("THREE.Color: Unknown color "+e),this}clone(){return new this.constructor(this.r,this.g,this.b)}copy(e){return this.r=e.r,this.g=e.g,this.b=e.b,this}copySRGBToLinear(e){return this.r=b0(e.r),this.g=b0(e.g),this.b=b0(e.b),this}copyLinearToSRGB(e){return this.r=d5(e.r),this.g=d5(e.g),this.b=d5(e.b),this}convertSRGBToLinear(){return this.copySRGBToLinear(this),this}convertLinearToSRGB(){return this.copyLinearToSRGB(this),this}getHex(e=ho){return br.fromWorkingColorSpace(Vs.copy(this),e),Math.round(wi(Vs.r*255,0,255))*65536+Math.round(wi(Vs.g*255,0,255))*256+Math.round(wi(Vs.b*255,0,255))}getHexString(e=ho){return("000000"+this.getHex(e).toString(16)).slice(-6)}getHSL(e,n=br.workingColorSpace){br.fromWorkingColorSpace(Vs.copy(this),n);const r=Vs.r,i=Vs.g,s=Vs.b,o=Math.max(r,i,s),a=Math.min(r,i,s);let l,c;const f=(a+o)/2;if(a===o)l=0,c=0;else{const p=o-a;switch(c=f<=.5?p/(o+a):p/(2-o-a),o){case r:l=(i-s)/p+(i0!=e>0&&this.version++,this._alphaTest=e}onBuild(){}onBeforeRender(){}onBeforeCompile(){}customProgramCacheKey(){return this.onBeforeCompile.toString()}setValues(e){if(e!==void 0)for(const n in e){const r=e[n];if(r===void 0){console.warn(`THREE.Material: parameter '${n}' has value of undefined.`);continue}const i=this[n];if(i===void 0){console.warn(`THREE.Material: '${n}' is not a property of THREE.${this.type}.`);continue}i&&i.isColor?i.set(r):i&&i.isVector3&&r&&r.isVector3?i.copy(r):this[n]=r}}toJSON(e){const n=e===void 0||typeof e=="string";n&&(e={textures:{},images:{}});const r={metadata:{version:4.6,type:"Material",generator:"Material.toJSON"}};r.uuid=this.uuid,r.type=this.type,this.name!==""&&(r.name=this.name),this.color&&this.color.isColor&&(r.color=this.color.getHex()),this.roughness!==void 0&&(r.roughness=this.roughness),this.metalness!==void 0&&(r.metalness=this.metalness),this.sheen!==void 0&&(r.sheen=this.sheen),this.sheenColor&&this.sheenColor.isColor&&(r.sheenColor=this.sheenColor.getHex()),this.sheenRoughness!==void 0&&(r.sheenRoughness=this.sheenRoughness),this.emissive&&this.emissive.isColor&&(r.emissive=this.emissive.getHex()),this.emissiveIntensity!==void 0&&this.emissiveIntensity!==1&&(r.emissiveIntensity=this.emissiveIntensity),this.specular&&this.specular.isColor&&(r.specular=this.specular.getHex()),this.specularIntensity!==void 0&&(r.specularIntensity=this.specularIntensity),this.specularColor&&this.specularColor.isColor&&(r.specularColor=this.specularColor.getHex()),this.shininess!==void 0&&(r.shininess=this.shininess),this.clearcoat!==void 0&&(r.clearcoat=this.clearcoat),this.clearcoatRoughness!==void 0&&(r.clearcoatRoughness=this.clearcoatRoughness),this.clearcoatMap&&this.clearcoatMap.isTexture&&(r.clearcoatMap=this.clearcoatMap.toJSON(e).uuid),this.clearcoatRoughnessMap&&this.clearcoatRoughnessMap.isTexture&&(r.clearcoatRoughnessMap=this.clearcoatRoughnessMap.toJSON(e).uuid),this.clearcoatNormalMap&&this.clearcoatNormalMap.isTexture&&(r.clearcoatNormalMap=this.clearcoatNormalMap.toJSON(e).uuid,r.clearcoatNormalScale=this.clearcoatNormalScale.toArray()),this.dispersion!==void 0&&(r.dispersion=this.dispersion),this.iridescence!==void 0&&(r.iridescence=this.iridescence),this.iridescenceIOR!==void 0&&(r.iridescenceIOR=this.iridescenceIOR),this.iridescenceThicknessRange!==void 0&&(r.iridescenceThicknessRange=this.iridescenceThicknessRange),this.iridescenceMap&&this.iridescenceMap.isTexture&&(r.iridescenceMap=this.iridescenceMap.toJSON(e).uuid),this.iridescenceThicknessMap&&this.iridescenceThicknessMap.isTexture&&(r.iridescenceThicknessMap=this.iridescenceThicknessMap.toJSON(e).uuid),this.anisotropy!==void 0&&(r.anisotropy=this.anisotropy),this.anisotropyRotation!==void 0&&(r.anisotropyRotation=this.anisotropyRotation),this.anisotropyMap&&this.anisotropyMap.isTexture&&(r.anisotropyMap=this.anisotropyMap.toJSON(e).uuid),this.map&&this.map.isTexture&&(r.map=this.map.toJSON(e).uuid),this.matcap&&this.matcap.isTexture&&(r.matcap=this.matcap.toJSON(e).uuid),this.alphaMap&&this.alphaMap.isTexture&&(r.alphaMap=this.alphaMap.toJSON(e).uuid),this.lightMap&&this.lightMap.isTexture&&(r.lightMap=this.lightMap.toJSON(e).uuid,r.lightMapIntensity=this.lightMapIntensity),this.aoMap&&this.aoMap.isTexture&&(r.aoMap=this.aoMap.toJSON(e).uuid,r.aoMapIntensity=this.aoMapIntensity),this.bumpMap&&this.bumpMap.isTexture&&(r.bumpMap=this.bumpMap.toJSON(e).uuid,r.bumpScale=this.bumpScale),this.normalMap&&this.normalMap.isTexture&&(r.normalMap=this.normalMap.toJSON(e).uuid,r.normalMapType=this.normalMapType,r.normalScale=this.normalScale.toArray()),this.displacementMap&&this.displacementMap.isTexture&&(r.displacementMap=this.displacementMap.toJSON(e).uuid,r.displacementScale=this.displacementScale,r.displacementBias=this.displacementBias),this.roughnessMap&&this.roughnessMap.isTexture&&(r.roughnessMap=this.roughnessMap.toJSON(e).uuid),this.metalnessMap&&this.metalnessMap.isTexture&&(r.metalnessMap=this.metalnessMap.toJSON(e).uuid),this.emissiveMap&&this.emissiveMap.isTexture&&(r.emissiveMap=this.emissiveMap.toJSON(e).uuid),this.specularMap&&this.specularMap.isTexture&&(r.specularMap=this.specularMap.toJSON(e).uuid),this.specularIntensityMap&&this.specularIntensityMap.isTexture&&(r.specularIntensityMap=this.specularIntensityMap.toJSON(e).uuid),this.specularColorMap&&this.specularColorMap.isTexture&&(r.specularColorMap=this.specularColorMap.toJSON(e).uuid),this.envMap&&this.envMap.isTexture&&(r.envMap=this.envMap.toJSON(e).uuid,this.combine!==void 0&&(r.combine=this.combine)),this.envMapRotation!==void 0&&(r.envMapRotation=this.envMapRotation.toArray()),this.envMapIntensity!==void 0&&(r.envMapIntensity=this.envMapIntensity),this.reflectivity!==void 0&&(r.reflectivity=this.reflectivity),this.refractionRatio!==void 0&&(r.refractionRatio=this.refractionRatio),this.gradientMap&&this.gradientMap.isTexture&&(r.gradientMap=this.gradientMap.toJSON(e).uuid),this.transmission!==void 0&&(r.transmission=this.transmission),this.transmissionMap&&this.transmissionMap.isTexture&&(r.transmissionMap=this.transmissionMap.toJSON(e).uuid),this.thickness!==void 0&&(r.thickness=this.thickness),this.thicknessMap&&this.thicknessMap.isTexture&&(r.thicknessMap=this.thicknessMap.toJSON(e).uuid),this.attenuationDistance!==void 0&&this.attenuationDistance!==1/0&&(r.attenuationDistance=this.attenuationDistance),this.attenuationColor!==void 0&&(r.attenuationColor=this.attenuationColor.getHex()),this.size!==void 0&&(r.size=this.size),this.shadowSide!==null&&(r.shadowSide=this.shadowSide),this.sizeAttenuation!==void 0&&(r.sizeAttenuation=this.sizeAttenuation),this.blending!==Yh&&(r.blending=this.blending),this.side!==Dc&&(r.side=this.side),this.vertexColors===!0&&(r.vertexColors=!0),this.opacity<1&&(r.opacity=this.opacity),this.transparent===!0&&(r.transparent=!0),this.blendSrc!==_2&&(r.blendSrc=this.blendSrc),this.blendDst!==b2&&(r.blendDst=this.blendDst),this.blendEquation!==Ud&&(r.blendEquation=this.blendEquation),this.blendSrcAlpha!==null&&(r.blendSrcAlpha=this.blendSrcAlpha),this.blendDstAlpha!==null&&(r.blendDstAlpha=this.blendDstAlpha),this.blendEquationAlpha!==null&&(r.blendEquationAlpha=this.blendEquationAlpha),this.blendColor&&this.blendColor.isColor&&(r.blendColor=this.blendColor.getHex()),this.blendAlpha!==0&&(r.blendAlpha=this.blendAlpha),this.depthFunc!==iy&&(r.depthFunc=this.depthFunc),this.depthTest===!1&&(r.depthTest=this.depthTest),this.depthWrite===!1&&(r.depthWrite=this.depthWrite),this.colorWrite===!1&&(r.colorWrite=this.colorWrite),this.stencilWriteMask!==255&&(r.stencilWriteMask=this.stencilWriteMask),this.stencilFunc!==_A&&(r.stencilFunc=this.stencilFunc),this.stencilRef!==0&&(r.stencilRef=this.stencilRef),this.stencilFuncMask!==255&&(r.stencilFuncMask=this.stencilFuncMask),this.stencilFail!==_h&&(r.stencilFail=this.stencilFail),this.stencilZFail!==_h&&(r.stencilZFail=this.stencilZFail),this.stencilZPass!==_h&&(r.stencilZPass=this.stencilZPass),this.stencilWrite===!0&&(r.stencilWrite=this.stencilWrite),this.rotation!==void 0&&this.rotation!==0&&(r.rotation=this.rotation),this.polygonOffset===!0&&(r.polygonOffset=!0),this.polygonOffsetFactor!==0&&(r.polygonOffsetFactor=this.polygonOffsetFactor),this.polygonOffsetUnits!==0&&(r.polygonOffsetUnits=this.polygonOffsetUnits),this.linewidth!==void 0&&this.linewidth!==1&&(r.linewidth=this.linewidth),this.dashSize!==void 0&&(r.dashSize=this.dashSize),this.gapSize!==void 0&&(r.gapSize=this.gapSize),this.scale!==void 0&&(r.scale=this.scale),this.dithering===!0&&(r.dithering=!0),this.alphaTest>0&&(r.alphaTest=this.alphaTest),this.alphaHash===!0&&(r.alphaHash=!0),this.alphaToCoverage===!0&&(r.alphaToCoverage=!0),this.premultipliedAlpha===!0&&(r.premultipliedAlpha=!0),this.forceSinglePass===!0&&(r.forceSinglePass=!0),this.wireframe===!0&&(r.wireframe=!0),this.wireframeLinewidth>1&&(r.wireframeLinewidth=this.wireframeLinewidth),this.wireframeLinecap!=="round"&&(r.wireframeLinecap=this.wireframeLinecap),this.wireframeLinejoin!=="round"&&(r.wireframeLinejoin=this.wireframeLinejoin),this.flatShading===!0&&(r.flatShading=!0),this.visible===!1&&(r.visible=!1),this.toneMapped===!1&&(r.toneMapped=!1),this.fog===!1&&(r.fog=!1),Object.keys(this.userData).length>0&&(r.userData=this.userData);function i(s){const o=[];for(const a in s){const l=s[a];delete l.metadata,o.push(l)}return o}if(n){const s=i(e.textures),o=i(e.images);s.length>0&&(r.textures=s),o.length>0&&(r.images=o)}return r}clone(){return new this.constructor().copy(this)}copy(e){this.name=e.name,this.blending=e.blending,this.side=e.side,this.vertexColors=e.vertexColors,this.opacity=e.opacity,this.transparent=e.transparent,this.blendSrc=e.blendSrc,this.blendDst=e.blendDst,this.blendEquation=e.blendEquation,this.blendSrcAlpha=e.blendSrcAlpha,this.blendDstAlpha=e.blendDstAlpha,this.blendEquationAlpha=e.blendEquationAlpha,this.blendColor.copy(e.blendColor),this.blendAlpha=e.blendAlpha,this.depthFunc=e.depthFunc,this.depthTest=e.depthTest,this.depthWrite=e.depthWrite,this.stencilWriteMask=e.stencilWriteMask,this.stencilFunc=e.stencilFunc,this.stencilRef=e.stencilRef,this.stencilFuncMask=e.stencilFuncMask,this.stencilFail=e.stencilFail,this.stencilZFail=e.stencilZFail,this.stencilZPass=e.stencilZPass,this.stencilWrite=e.stencilWrite;const n=e.clippingPlanes;let r=null;if(n!==null){const i=n.length;r=new Array(i);for(let s=0;s!==i;++s)r[s]=n[s].clone()}return this.clippingPlanes=r,this.clipIntersection=e.clipIntersection,this.clipShadows=e.clipShadows,this.shadowSide=e.shadowSide,this.colorWrite=e.colorWrite,this.precision=e.precision,this.polygonOffset=e.polygonOffset,this.polygonOffsetFactor=e.polygonOffsetFactor,this.polygonOffsetUnits=e.polygonOffsetUnits,this.dithering=e.dithering,this.alphaTest=e.alphaTest,this.alphaHash=e.alphaHash,this.alphaToCoverage=e.alphaToCoverage,this.premultipliedAlpha=e.premultipliedAlpha,this.forceSinglePass=e.forceSinglePass,this.visible=e.visible,this.toneMapped=e.toneMapped,this.userData=JSON.parse(JSON.stringify(e.userData)),this}dispose(){this.dispatchEvent({type:"dispose"})}set needsUpdate(e){e===!0&&this.version++}}class pl extends Ds{constructor(e){super(),this.isMeshBasicMaterial=!0,this.type="MeshBasicMaterial",this.color=new It(16777215),this.map=null,this.lightMap=null,this.lightMapIntensity=1,this.aoMap=null,this.aoMapIntensity=1,this.specularMap=null,this.alphaMap=null,this.envMap=null,this.envMapRotation=new ns,this.combine=cx,this.reflectivity=1,this.refractionRatio=.98,this.wireframe=!1,this.wireframeLinewidth=1,this.wireframeLinecap="round",this.wireframeLinejoin="round",this.fog=!0,this.setValues(e)}copy(e){return super.copy(e),this.color.copy(e.color),this.map=e.map,this.lightMap=e.lightMap,this.lightMapIntensity=e.lightMapIntensity,this.aoMap=e.aoMap,this.aoMapIntensity=e.aoMapIntensity,this.specularMap=e.specularMap,this.alphaMap=e.alphaMap,this.envMap=e.envMap,this.envMapRotation.copy(e.envMapRotation),this.combine=e.combine,this.reflectivity=e.reflectivity,this.refractionRatio=e.refractionRatio,this.wireframe=e.wireframe,this.wireframeLinewidth=e.wireframeLinewidth,this.wireframeLinecap=e.wireframeLinecap,this.wireframeLinejoin=e.wireframeLinejoin,this.fog=e.fog,this}}const _u=mhe();function mhe(){const t=new ArrayBuffer(4),e=new Float32Array(t),n=new Uint32Array(t),r=new Uint32Array(512),i=new Uint32Array(512);for(let l=0;l<256;++l){const c=l-127;c<-27?(r[l]=0,r[l|256]=32768,i[l]=24,i[l|256]=24):c<-14?(r[l]=1024>>-c-14,r[l|256]=1024>>-c-14|32768,i[l]=-c-1,i[l|256]=-c-1):c<=15?(r[l]=c+15<<10,r[l|256]=c+15<<10|32768,i[l]=13,i[l|256]=13):c<128?(r[l]=31744,r[l|256]=64512,i[l]=24,i[l|256]=24):(r[l]=31744,r[l|256]=64512,i[l]=13,i[l|256]=13)}const s=new Uint32Array(2048),o=new Uint32Array(64),a=new Uint32Array(64);for(let l=1;l<1024;++l){let c=l<<13,f=0;for(;!(c&8388608);)c<<=1,f-=8388608;c&=-8388609,f+=947912704,s[l]=c|f}for(let l=1024;l<2048;++l)s[l]=939524096+(l-1024<<13);for(let l=1;l<31;++l)o[l]=l<<23;o[31]=1199570944,o[32]=2147483648;for(let l=33;l<63;++l)o[l]=2147483648+(l-32<<23);o[63]=3347054592;for(let l=1;l<64;++l)l!==32&&(a[l]=1024);return{floatView:e,uint32View:n,baseTable:r,shiftTable:i,mantissaTable:s,exponentTable:o,offsetTable:a}}function Lo(t){Math.abs(t)>65504&&console.warn("THREE.DataUtils.toHalfFloat(): Value out of range."),t=wi(t,-65504,65504),_u.floatView[0]=t;const e=_u.uint32View[0],n=e>>23&511;return _u.baseTable[n]+((e&8388607)>>_u.shiftTable[n])}function nv(t){const e=t>>10;return _u.uint32View[0]=_u.mantissaTable[_u.offsetTable[e]+(t&1023)]+_u.exponentTable[e],_u.floatView[0]}const ghe={toHalfFloat:Lo,fromHalfFloat:nv},$i=new K,xb=new ct;class fr{constructor(e,n,r=!1){if(Array.isArray(e))throw new TypeError("THREE.BufferAttribute: array should be a Typed Array.");this.isBufferAttribute=!0,this.name="",this.array=e,this.itemSize=n,this.count=e!==void 0?e.length/n:0,this.normalized=r,this.usage=py,this._updateRange={offset:0,count:-1},this.updateRanges=[],this.gpuType=ba,this.version=0}onUploadCallback(){}set needsUpdate(e){e===!0&&this.version++}get updateRange(){return ZU("THREE.BufferAttribute: updateRange() is deprecated and will be removed in r169. Use addUpdateRange() instead."),this._updateRange}setUsage(e){return this.usage=e,this}addUpdateRange(e,n){this.updateRanges.push({start:e,count:n})}clearUpdateRanges(){this.updateRanges.length=0}copy(e){return this.name=e.name,this.array=new e.array.constructor(e.array),this.itemSize=e.itemSize,this.count=e.count,this.normalized=e.normalized,this.usage=e.usage,this.gpuType=e.gpuType,this}copyAt(e,n,r){e*=this.itemSize,r*=n.itemSize;for(let i=0,s=this.itemSize;i0&&(e.userData=this.userData),this.parameters!==void 0){const l=this.parameters;for(const c in l)l[c]!==void 0&&(e[c]=l[c]);return e}e.data={attributes:{}};const n=this.index;n!==null&&(e.data.index={type:n.array.constructor.name,array:Array.prototype.slice.call(n.array)});const r=this.attributes;for(const l in r){const c=r[l];e.data.attributes[l]=c.toJSON(e.data)}const i={};let s=!1;for(const l in this.morphAttributes){const c=this.morphAttributes[l],f=[];for(let p=0,g=c.length;p0&&(i[l]=f,s=!0)}s&&(e.data.morphAttributes=i,e.data.morphTargetsRelative=this.morphTargetsRelative);const o=this.groups;o.length>0&&(e.data.groups=JSON.parse(JSON.stringify(o)));const a=this.boundingSphere;return a!==null&&(e.data.boundingSphere={center:a.center.toArray(),radius:a.radius}),e}clone(){return new this.constructor().copy(this)}copy(e){this.index=null,this.attributes={},this.morphAttributes={},this.groups=[],this.boundingBox=null,this.boundingSphere=null;const n={};this.name=e.name;const r=e.index;r!==null&&this.setIndex(r.clone(n));const i=e.attributes;for(const c in i){const f=i[c];this.setAttribute(c,f.clone(n))}const s=e.morphAttributes;for(const c in s){const f=[],p=s[c];for(let g=0,v=p.length;g0){const i=n[r[0]];if(i!==void 0){this.morphTargetInfluences=[],this.morphTargetDictionary={};for(let s=0,o=i.length;s(e.far-e.near)**2))&&(SO.copy(s).invert(),rh.copy(e.ray).applyMatrix4(SO),!(r.boundingBox!==null&&rh.intersectsBox(r.boundingBox)===!1)&&this._computeIntersections(e,n,rh)))}_computeIntersections(e,n,r){let i;const s=this.geometry,o=this.material,a=s.index,l=s.attributes.position,c=s.attributes.uv,f=s.attributes.uv1,p=s.attributes.normal,g=s.groups,v=s.drawRange;if(a!==null)if(Array.isArray(o))for(let x=0,_=g.length;x<_;x++){const b=g[x],y=o[b.materialIndex],S=Math.max(b.start,v.start),w=Math.min(a.count,Math.min(b.start+b.count,v.start+v.count));for(let T=S,L=w;Tn.far?null:{distance:c,point:Cb.clone(),object:t}}function Tb(t,e,n,r,i,s,o,a,l,c){t.getVertexPosition(a,Am),t.getVertexPosition(l,Rm),t.getVertexPosition(c,Pm);const f=Mhe(t,e,n,r,Am,Rm,Pm,Eb);if(f){i&&(Sb.fromBufferAttribute(i,a),wb.fromBufferAttribute(i,l),Mb.fromBufferAttribute(i,c),f.uv=xa.getInterpolation(Eb,Am,Rm,Pm,Sb,wb,Mb,new ct)),s&&(Sb.fromBufferAttribute(s,a),wb.fromBufferAttribute(s,l),Mb.fromBufferAttribute(s,c),f.uv1=xa.getInterpolation(Eb,Am,Rm,Pm,Sb,wb,Mb,new ct)),o&&(MO.fromBufferAttribute(o,a),EO.fromBufferAttribute(o,l),CO.fromBufferAttribute(o,c),f.normal=xa.getInterpolation(Eb,Am,Rm,Pm,MO,EO,CO,new K),f.normal.dot(r.direction)>0&&f.normal.multiplyScalar(-1));const p={a,b:l,c,normal:new K,materialIndex:0};xa.getNormal(Am,Rm,Pm,p.normal),f.face=p}return f}class po extends Tn{constructor(e=1,n=1,r=1,i=1,s=1,o=1){super(),this.type="BoxGeometry",this.parameters={width:e,height:n,depth:r,widthSegments:i,heightSegments:s,depthSegments:o};const a=this;i=Math.floor(i),s=Math.floor(s),o=Math.floor(o);const l=[],c=[],f=[],p=[];let g=0,v=0;x("z","y","x",-1,-1,r,n,e,o,s,0),x("z","y","x",1,-1,r,n,-e,o,s,1),x("x","z","y",1,1,e,r,n,i,o,2),x("x","z","y",1,-1,e,r,-n,i,o,3),x("x","y","z",1,-1,e,n,r,i,s,4),x("x","y","z",-1,-1,e,n,-r,i,s,5),this.setIndex(l),this.setAttribute("position",new Ut(c,3)),this.setAttribute("normal",new Ut(f,3)),this.setAttribute("uv",new Ut(p,2));function x(_,b,y,S,w,T,L,R,P,F,O){const I=T/P,H=L/F,Q=T/2,q=L/2,le=R/2,ie=P+1,ee=F+1;let ue=0,z=0;const te=new K;for(let oe=0;oe0?1:-1,f.push(te.x,te.y,te.z),p.push(Ce/P),p.push(1-oe/F),ue+=1}}for(let oe=0;oe0&&(n.defines=this.defines),n.vertexShader=this.vertexShader,n.fragmentShader=this.fragmentShader,n.lights=this.lights,n.clipping=this.clipping;const r={};for(const i in this.extensions)this.extensions[i]===!0&&(r[i]=!0);return Object.keys(r).length>0&&(n.extensions=r),n}}class dx extends Jn{constructor(){super(),this.isCamera=!0,this.type="Camera",this.matrixWorldInverse=new Jt,this.projectionMatrix=new Jt,this.projectionMatrixInverse=new Jt,this.coordinateSystem=Ec}copy(e,n){return super.copy(e,n),this.matrixWorldInverse.copy(e.matrixWorldInverse),this.projectionMatrix.copy(e.projectionMatrix),this.projectionMatrixInverse.copy(e.projectionMatrixInverse),this.coordinateSystem=e.coordinateSystem,this}getWorldDirection(e){return super.getWorldDirection(e).negate()}updateMatrixWorld(e){super.updateMatrixWorld(e),this.matrixWorldInverse.copy(this.matrixWorld).invert()}updateWorldMatrix(e,n){super.updateWorldMatrix(e,n),this.matrixWorldInverse.copy(this.matrixWorld).invert()}clone(){return new this.constructor().copy(this)}}const Rd=new K,TO=new ct,AO=new ct;let $r=class extends dx{constructor(e=50,n=1,r=.1,i=2e3){super(),this.isPerspectiveCamera=!0,this.type="PerspectiveCamera",this.fov=e,this.zoom=1,this.near=r,this.far=i,this.focus=10,this.aspect=n,this.view=null,this.filmGauge=35,this.filmOffset=0,this.updateProjectionMatrix()}copy(e,n){return super.copy(e,n),this.fov=e.fov,this.zoom=e.zoom,this.near=e.near,this.far=e.far,this.focus=e.focus,this.aspect=e.aspect,this.view=e.view===null?null:Object.assign({},e.view),this.filmGauge=e.filmGauge,this.filmOffset=e.filmOffset,this}setFocalLength(e){const n=.5*this.getFilmHeight()/e;this.fov=eg*2*Math.atan(n),this.updateProjectionMatrix()}getFocalLength(){const e=Math.tan(Qh*.5*this.fov);return .5*this.getFilmHeight()/e}getEffectiveFOV(){return eg*2*Math.atan(Math.tan(Qh*.5*this.fov)/this.zoom)}getFilmWidth(){return this.filmGauge*Math.min(this.aspect,1)}getFilmHeight(){return this.filmGauge/Math.max(this.aspect,1)}getViewBounds(e,n,r){Rd.set(-1,-1,.5).applyMatrix4(this.projectionMatrixInverse),n.set(Rd.x,Rd.y).multiplyScalar(-e/Rd.z),Rd.set(1,1,.5).applyMatrix4(this.projectionMatrixInverse),r.set(Rd.x,Rd.y).multiplyScalar(-e/Rd.z)}getViewSize(e,n){return this.getViewBounds(e,TO,AO),n.subVectors(AO,TO)}setViewOffset(e,n,r,i,s,o){this.aspect=e/n,this.view===null&&(this.view={enabled:!0,fullWidth:1,fullHeight:1,offsetX:0,offsetY:0,width:1,height:1}),this.view.enabled=!0,this.view.fullWidth=e,this.view.fullHeight=n,this.view.offsetX=r,this.view.offsetY=i,this.view.width=s,this.view.height=o,this.updateProjectionMatrix()}clearViewOffset(){this.view!==null&&(this.view.enabled=!1),this.updateProjectionMatrix()}updateProjectionMatrix(){const e=this.near;let n=e*Math.tan(Qh*.5*this.fov)/this.zoom,r=2*n,i=this.aspect*r,s=-.5*i;const o=this.view;if(this.view!==null&&this.view.enabled){const l=o.fullWidth,c=o.fullHeight;s+=o.offsetX*i/l,n-=o.offsetY*r/c,i*=o.width/l,r*=o.height/c}const a=this.filmOffset;a!==0&&(s+=e*a/this.getFilmWidth()),this.projectionMatrix.makePerspective(s,s+i,n,n-r,e,this.far,this.coordinateSystem),this.projectionMatrixInverse.copy(this.projectionMatrix).invert()}toJSON(e){const n=super.toJSON(e);return n.object.fov=this.fov,n.object.zoom=this.zoom,n.object.near=this.near,n.object.far=this.far,n.object.focus=this.focus,n.object.aspect=this.aspect,this.view!==null&&(n.object.view=Object.assign({},this.view)),n.object.filmGauge=this.filmGauge,n.object.filmOffset=this.filmOffset,n}};const Im=-90,Lm=1;class tz extends Jn{constructor(e,n,r){super(),this.type="CubeCamera",this.renderTarget=r,this.coordinateSystem=null,this.activeMipmapLevel=0;const i=new $r(Im,Lm,e,n);i.layers=this.layers,this.add(i);const s=new $r(Im,Lm,e,n);s.layers=this.layers,this.add(s);const o=new $r(Im,Lm,e,n);o.layers=this.layers,this.add(o);const a=new $r(Im,Lm,e,n);a.layers=this.layers,this.add(a);const l=new $r(Im,Lm,e,n);l.layers=this.layers,this.add(l);const c=new $r(Im,Lm,e,n);c.layers=this.layers,this.add(c)}updateCoordinateSystem(){const e=this.coordinateSystem,n=this.children.concat(),[r,i,s,o,a,l]=n;for(const c of n)this.remove(c);if(e===Ec)r.up.set(0,1,0),r.lookAt(1,0,0),i.up.set(0,1,0),i.lookAt(-1,0,0),s.up.set(0,0,-1),s.lookAt(0,1,0),o.up.set(0,0,1),o.lookAt(0,-1,0),a.up.set(0,1,0),a.lookAt(0,0,1),l.up.set(0,1,0),l.lookAt(0,0,-1);else if(e===my)r.up.set(0,-1,0),r.lookAt(-1,0,0),i.up.set(0,-1,0),i.lookAt(1,0,0),s.up.set(0,0,1),s.lookAt(0,1,0),o.up.set(0,0,-1),o.lookAt(0,-1,0),a.up.set(0,-1,0),a.lookAt(0,0,1),l.up.set(0,-1,0),l.lookAt(0,0,-1);else throw new Error("THREE.CubeCamera.updateCoordinateSystem(): Invalid coordinate system: "+e);for(const c of n)this.add(c),c.updateMatrixWorld()}update(e,n){this.parent===null&&this.updateMatrixWorld();const{renderTarget:r,activeMipmapLevel:i}=this;this.coordinateSystem!==e.coordinateSystem&&(this.coordinateSystem=e.coordinateSystem,this.updateCoordinateSystem());const[s,o,a,l,c,f]=this.children,p=e.getRenderTarget(),g=e.getActiveCubeFace(),v=e.getActiveMipmapLevel(),x=e.xr.enabled;e.xr.enabled=!1;const _=r.texture.generateMipmaps;r.texture.generateMipmaps=!1,e.setRenderTarget(r,0,i),e.render(n,s),e.setRenderTarget(r,1,i),e.render(n,o),e.setRenderTarget(r,2,i),e.render(n,a),e.setRenderTarget(r,3,i),e.render(n,l),e.setRenderTarget(r,4,i),e.render(n,c),r.texture.generateMipmaps=_,e.setRenderTarget(r,5,i),e.render(n,f),e.setRenderTarget(p,g,v),e.xr.enabled=x,r.texture.needsPMREMUpdate=!0}}class fx extends Yr{constructor(e,n,r,i,s,o,a,l,c,f){e=e!==void 0?e:[],n=n!==void 0?n:Fu,super(e,n,r,i,s,o,a,l,c,f),this.isCubeTexture=!0,this.flipY=!1}get images(){return this.image}set images(e){this.image=e}}class nz extends hl{constructor(e=1,n={}){super(e,e,n),this.isWebGLCubeRenderTarget=!0;const r={width:e,height:e,depth:1},i=[r,r,r,r,r,r];this.texture=new fx(i,n.mapping,n.wrapS,n.wrapT,n.magFilter,n.minFilter,n.format,n.type,n.anisotropy,n.colorSpace),this.texture.isRenderTargetTexture=!0,this.texture.generateMipmaps=n.generateMipmaps!==void 0?n.generateMipmaps:!1,this.texture.minFilter=n.minFilter!==void 0?n.minFilter:Mi}fromEquirectangularTexture(e,n){this.texture.type=n.type,this.texture.colorSpace=n.colorSpace,this.texture.generateMipmaps=n.generateMipmaps,this.texture.minFilter=n.minFilter,this.texture.magFilter=n.magFilter;const r={uniforms:{tEquirect:{value:null}},vertexShader:`
+
+ varying vec3 vWorldDirection;
+
+ vec3 transformDirection( in vec3 dir, in mat4 matrix ) {
+
+ return normalize( ( matrix * vec4( dir, 0.0 ) ).xyz );
+
+ }
+
+ void main() {
+
+ vWorldDirection = transformDirection( position, modelMatrix );
+
+ #include
+ #include
+
+ }
+ `,fragmentShader:`
+
+ uniform sampler2D tEquirect;
+
+ varying vec3 vWorldDirection;
+
+ #include
+
+ void main() {
+
+ vec3 direction = normalize( vWorldDirection );
+
+ vec2 sampleUV = equirectUv( direction );
+
+ gl_FragColor = texture2D( tEquirect, sampleUV );
+
+ }
+ `},i=new po(5,5,5),s=new Wl({name:"CubemapFromEquirect",uniforms:tg(r.uniforms),vertexShader:r.vertexShader,fragmentShader:r.fragmentShader,side:yo,blending:Pu});s.uniforms.tEquirect.value=n;const o=new Vt(i,s),a=n.minFilter;return n.minFilter===Bl&&(n.minFilter=Mi),new tz(1,10,this).update(e,o),n.minFilter=a,o.geometry.dispose(),o.material.dispose(),this}clear(e,n,r,i){const s=e.getRenderTarget();for(let o=0;o<6;o++)e.setRenderTarget(this,o),e.clear(n,r,i);e.setRenderTarget(s)}}const T5=new K,Ahe=new K,Rhe=new Bn;class gu{constructor(e=new K(1,0,0),n=0){this.isPlane=!0,this.normal=e,this.constant=n}set(e,n){return this.normal.copy(e),this.constant=n,this}setComponents(e,n,r,i){return this.normal.set(e,n,r),this.constant=i,this}setFromNormalAndCoplanarPoint(e,n){return this.normal.copy(e),this.constant=-n.dot(this.normal),this}setFromCoplanarPoints(e,n,r){const i=T5.subVectors(r,n).cross(Ahe.subVectors(e,n)).normalize();return this.setFromNormalAndCoplanarPoint(i,e),this}copy(e){return this.normal.copy(e.normal),this.constant=e.constant,this}normalize(){const e=1/this.normal.length();return this.normal.multiplyScalar(e),this.constant*=e,this}negate(){return this.constant*=-1,this.normal.negate(),this}distanceToPoint(e){return this.normal.dot(e)+this.constant}distanceToSphere(e){return this.distanceToPoint(e.center)-e.radius}projectPoint(e,n){return n.copy(e).addScaledVector(this.normal,-this.distanceToPoint(e))}intersectLine(e,n){const r=e.delta(T5),i=this.normal.dot(r);if(i===0)return this.distanceToPoint(e.start)===0?n.copy(e.start):null;const s=-(e.start.dot(this.normal)+this.constant)/i;return s<0||s>1?null:n.copy(e.start).addScaledVector(r,s)}intersectsLine(e){const n=this.distanceToPoint(e.start),r=this.distanceToPoint(e.end);return n<0&&r>0||r<0&&n>0}intersectsBox(e){return e.intersectsPlane(this)}intersectsSphere(e){return e.intersectsPlane(this)}coplanarPoint(e){return e.copy(this.normal).multiplyScalar(-this.constant)}applyMatrix4(e,n){const r=n||Rhe.getNormalMatrix(e),i=this.coplanarPoint(T5).applyMatrix4(e),s=this.normal.applyMatrix3(r).normalize();return this.constant=-i.dot(s),this}translate(e){return this.constant-=e.dot(this.normal),this}equals(e){return e.normal.equals(this.normal)&&e.constant===this.constant}clone(){return new this.constructor().copy(this)}}const ih=new Xs,Ab=new K;class hx{constructor(e=new gu,n=new gu,r=new gu,i=new gu,s=new gu,o=new gu){this.planes=[e,n,r,i,s,o]}set(e,n,r,i,s,o){const a=this.planes;return a[0].copy(e),a[1].copy(n),a[2].copy(r),a[3].copy(i),a[4].copy(s),a[5].copy(o),this}copy(e){const n=this.planes;for(let r=0;r<6;r++)n[r].copy(e.planes[r]);return this}setFromProjectionMatrix(e,n=Ec){const r=this.planes,i=e.elements,s=i[0],o=i[1],a=i[2],l=i[3],c=i[4],f=i[5],p=i[6],g=i[7],v=i[8],x=i[9],_=i[10],b=i[11],y=i[12],S=i[13],w=i[14],T=i[15];if(r[0].setComponents(l-s,g-c,b-v,T-y).normalize(),r[1].setComponents(l+s,g+c,b+v,T+y).normalize(),r[2].setComponents(l+o,g+f,b+x,T+S).normalize(),r[3].setComponents(l-o,g-f,b-x,T-S).normalize(),r[4].setComponents(l-a,g-p,b-_,T-w).normalize(),n===Ec)r[5].setComponents(l+a,g+p,b+_,T+w).normalize();else if(n===my)r[5].setComponents(a,p,_,w).normalize();else throw new Error("THREE.Frustum.setFromProjectionMatrix(): Invalid coordinate system: "+n);return this}intersectsObject(e){if(e.boundingSphere!==void 0)e.boundingSphere===null&&e.computeBoundingSphere(),ih.copy(e.boundingSphere).applyMatrix4(e.matrixWorld);else{const n=e.geometry;n.boundingSphere===null&&n.computeBoundingSphere(),ih.copy(n.boundingSphere).applyMatrix4(e.matrixWorld)}return this.intersectsSphere(ih)}intersectsSprite(e){return ih.center.set(0,0,0),ih.radius=.7071067811865476,ih.applyMatrix4(e.matrixWorld),this.intersectsSphere(ih)}intersectsSphere(e){const n=this.planes,r=e.center,i=-e.radius;for(let s=0;s<6;s++)if(n[s].distanceToPoint(r)0?e.max.x:e.min.x,Ab.y=i.normal.y>0?e.max.y:e.min.y,Ab.z=i.normal.z>0?e.max.z:e.min.z,i.distanceToPoint(Ab)<0)return!1}return!0}containsPoint(e){const n=this.planes;for(let r=0;r<6;r++)if(n[r].distanceToPoint(e)<0)return!1;return!0}clone(){return new this.constructor().copy(this)}}function rz(){let t=null,e=!1,n=null,r=null;function i(s,o){n(s,o),r=t.requestAnimationFrame(i)}return{start:function(){e!==!0&&n!==null&&(r=t.requestAnimationFrame(i),e=!0)},stop:function(){t.cancelAnimationFrame(r),e=!1},setAnimationLoop:function(s){n=s},setContext:function(s){t=s}}}function Phe(t){const e=new WeakMap;function n(a,l){const c=a.array,f=a.usage,p=c.byteLength,g=t.createBuffer();t.bindBuffer(l,g),t.bufferData(l,c,f),a.onUploadCallback();let v;if(c instanceof Float32Array)v=t.FLOAT;else if(c instanceof Uint16Array)a.isFloat16BufferAttribute?v=t.HALF_FLOAT:v=t.UNSIGNED_SHORT;else if(c instanceof Int16Array)v=t.SHORT;else if(c instanceof Uint32Array)v=t.UNSIGNED_INT;else if(c instanceof Int32Array)v=t.INT;else if(c instanceof Int8Array)v=t.BYTE;else if(c instanceof Uint8Array)v=t.UNSIGNED_BYTE;else if(c instanceof Uint8ClampedArray)v=t.UNSIGNED_BYTE;else throw new Error("THREE.WebGLAttributes: Unsupported buffer data format: "+c);return{buffer:g,type:v,bytesPerElement:c.BYTES_PER_ELEMENT,version:a.version,size:p}}function r(a,l,c){const f=l.array,p=l._updateRange,g=l.updateRanges;if(t.bindBuffer(c,a),p.count===-1&&g.length===0&&t.bufferSubData(c,0,f),g.length!==0){for(let v=0,x=g.length;v 0
+ vec4 plane;
+ #ifdef ALPHA_TO_COVERAGE
+ float distanceToPlane, distanceGradient;
+ float clipOpacity = 1.0;
+ #pragma unroll_loop_start
+ for ( int i = 0; i < UNION_CLIPPING_PLANES; i ++ ) {
+ plane = clippingPlanes[ i ];
+ distanceToPlane = - dot( vClipPosition, plane.xyz ) + plane.w;
+ distanceGradient = fwidth( distanceToPlane ) / 2.0;
+ clipOpacity *= smoothstep( - distanceGradient, distanceGradient, distanceToPlane );
+ if ( clipOpacity == 0.0 ) discard;
+ }
+ #pragma unroll_loop_end
+ #if UNION_CLIPPING_PLANES < NUM_CLIPPING_PLANES
+ float unionClipOpacity = 1.0;
+ #pragma unroll_loop_start
+ for ( int i = UNION_CLIPPING_PLANES; i < NUM_CLIPPING_PLANES; i ++ ) {
+ plane = clippingPlanes[ i ];
+ distanceToPlane = - dot( vClipPosition, plane.xyz ) + plane.w;
+ distanceGradient = fwidth( distanceToPlane ) / 2.0;
+ unionClipOpacity *= 1.0 - smoothstep( - distanceGradient, distanceGradient, distanceToPlane );
+ }
+ #pragma unroll_loop_end
+ clipOpacity *= 1.0 - unionClipOpacity;
+ #endif
+ diffuseColor.a *= clipOpacity;
+ if ( diffuseColor.a == 0.0 ) discard;
+ #else
+ #pragma unroll_loop_start
+ for ( int i = 0; i < UNION_CLIPPING_PLANES; i ++ ) {
+ plane = clippingPlanes[ i ];
+ if ( dot( vClipPosition, plane.xyz ) > plane.w ) discard;
+ }
+ #pragma unroll_loop_end
+ #if UNION_CLIPPING_PLANES < NUM_CLIPPING_PLANES
+ bool clipped = true;
+ #pragma unroll_loop_start
+ for ( int i = UNION_CLIPPING_PLANES; i < NUM_CLIPPING_PLANES; i ++ ) {
+ plane = clippingPlanes[ i ];
+ clipped = ( dot( vClipPosition, plane.xyz ) > plane.w ) && clipped;
+ }
+ #pragma unroll_loop_end
+ if ( clipped ) discard;
+ #endif
+ #endif
+#endif`,Xhe=`#if NUM_CLIPPING_PLANES > 0
+ varying vec3 vClipPosition;
+ uniform vec4 clippingPlanes[ NUM_CLIPPING_PLANES ];
+#endif`,qhe=`#if NUM_CLIPPING_PLANES > 0
+ varying vec3 vClipPosition;
+#endif`,Zhe=`#if NUM_CLIPPING_PLANES > 0
+ vClipPosition = - mvPosition.xyz;
+#endif`,Yhe=`#if defined( USE_COLOR_ALPHA )
+ diffuseColor *= vColor;
+#elif defined( USE_COLOR )
+ diffuseColor.rgb *= vColor;
+#endif`,Khe=`#if defined( USE_COLOR_ALPHA )
+ varying vec4 vColor;
+#elif defined( USE_COLOR )
+ varying vec3 vColor;
+#endif`,Qhe=`#if defined( USE_COLOR_ALPHA )
+ varying vec4 vColor;
+#elif defined( USE_COLOR ) || defined( USE_INSTANCING_COLOR )
+ varying vec3 vColor;
+#endif`,Jhe=`#if defined( USE_COLOR_ALPHA )
+ vColor = vec4( 1.0 );
+#elif defined( USE_COLOR ) || defined( USE_INSTANCING_COLOR )
+ vColor = vec3( 1.0 );
+#endif
+#ifdef USE_COLOR
+ vColor *= color;
+#endif
+#ifdef USE_INSTANCING_COLOR
+ vColor.xyz *= instanceColor.xyz;
+#endif`,epe=`#define PI 3.141592653589793
+#define PI2 6.283185307179586
+#define PI_HALF 1.5707963267948966
+#define RECIPROCAL_PI 0.3183098861837907
+#define RECIPROCAL_PI2 0.15915494309189535
+#define EPSILON 1e-6
+#ifndef saturate
+#define saturate( a ) clamp( a, 0.0, 1.0 )
+#endif
+#define whiteComplement( a ) ( 1.0 - saturate( a ) )
+float pow2( const in float x ) { return x*x; }
+vec3 pow2( const in vec3 x ) { return x*x; }
+float pow3( const in float x ) { return x*x*x; }
+float pow4( const in float x ) { float x2 = x*x; return x2*x2; }
+float max3( const in vec3 v ) { return max( max( v.x, v.y ), v.z ); }
+float average( const in vec3 v ) { return dot( v, vec3( 0.3333333 ) ); }
+highp float rand( const in vec2 uv ) {
+ const highp float a = 12.9898, b = 78.233, c = 43758.5453;
+ highp float dt = dot( uv.xy, vec2( a,b ) ), sn = mod( dt, PI );
+ return fract( sin( sn ) * c );
+}
+#ifdef HIGH_PRECISION
+ float precisionSafeLength( vec3 v ) { return length( v ); }
+#else
+ float precisionSafeLength( vec3 v ) {
+ float maxComponent = max3( abs( v ) );
+ return length( v / maxComponent ) * maxComponent;
+ }
+#endif
+struct IncidentLight {
+ vec3 color;
+ vec3 direction;
+ bool visible;
+};
+struct ReflectedLight {
+ vec3 directDiffuse;
+ vec3 directSpecular;
+ vec3 indirectDiffuse;
+ vec3 indirectSpecular;
+};
+#ifdef USE_ALPHAHASH
+ varying vec3 vPosition;
+#endif
+vec3 transformDirection( in vec3 dir, in mat4 matrix ) {
+ return normalize( ( matrix * vec4( dir, 0.0 ) ).xyz );
+}
+vec3 inverseTransformDirection( in vec3 dir, in mat4 matrix ) {
+ return normalize( ( vec4( dir, 0.0 ) * matrix ).xyz );
+}
+mat3 transposeMat3( const in mat3 m ) {
+ mat3 tmp;
+ tmp[ 0 ] = vec3( m[ 0 ].x, m[ 1 ].x, m[ 2 ].x );
+ tmp[ 1 ] = vec3( m[ 0 ].y, m[ 1 ].y, m[ 2 ].y );
+ tmp[ 2 ] = vec3( m[ 0 ].z, m[ 1 ].z, m[ 2 ].z );
+ return tmp;
+}
+float luminance( const in vec3 rgb ) {
+ const vec3 weights = vec3( 0.2126729, 0.7151522, 0.0721750 );
+ return dot( weights, rgb );
+}
+bool isPerspectiveMatrix( mat4 m ) {
+ return m[ 2 ][ 3 ] == - 1.0;
+}
+vec2 equirectUv( in vec3 dir ) {
+ float u = atan( dir.z, dir.x ) * RECIPROCAL_PI2 + 0.5;
+ float v = asin( clamp( dir.y, - 1.0, 1.0 ) ) * RECIPROCAL_PI + 0.5;
+ return vec2( u, v );
+}
+vec3 BRDF_Lambert( const in vec3 diffuseColor ) {
+ return RECIPROCAL_PI * diffuseColor;
+}
+vec3 F_Schlick( const in vec3 f0, const in float f90, const in float dotVH ) {
+ float fresnel = exp2( ( - 5.55473 * dotVH - 6.98316 ) * dotVH );
+ return f0 * ( 1.0 - fresnel ) + ( f90 * fresnel );
+}
+float F_Schlick( const in float f0, const in float f90, const in float dotVH ) {
+ float fresnel = exp2( ( - 5.55473 * dotVH - 6.98316 ) * dotVH );
+ return f0 * ( 1.0 - fresnel ) + ( f90 * fresnel );
+} // validated`,tpe=`#ifdef ENVMAP_TYPE_CUBE_UV
+ #define cubeUV_minMipLevel 4.0
+ #define cubeUV_minTileSize 16.0
+ float getFace( vec3 direction ) {
+ vec3 absDirection = abs( direction );
+ float face = - 1.0;
+ if ( absDirection.x > absDirection.z ) {
+ if ( absDirection.x > absDirection.y )
+ face = direction.x > 0.0 ? 0.0 : 3.0;
+ else
+ face = direction.y > 0.0 ? 1.0 : 4.0;
+ } else {
+ if ( absDirection.z > absDirection.y )
+ face = direction.z > 0.0 ? 2.0 : 5.0;
+ else
+ face = direction.y > 0.0 ? 1.0 : 4.0;
+ }
+ return face;
+ }
+ vec2 getUV( vec3 direction, float face ) {
+ vec2 uv;
+ if ( face == 0.0 ) {
+ uv = vec2( direction.z, direction.y ) / abs( direction.x );
+ } else if ( face == 1.0 ) {
+ uv = vec2( - direction.x, - direction.z ) / abs( direction.y );
+ } else if ( face == 2.0 ) {
+ uv = vec2( - direction.x, direction.y ) / abs( direction.z );
+ } else if ( face == 3.0 ) {
+ uv = vec2( - direction.z, direction.y ) / abs( direction.x );
+ } else if ( face == 4.0 ) {
+ uv = vec2( - direction.x, direction.z ) / abs( direction.y );
+ } else {
+ uv = vec2( direction.x, direction.y ) / abs( direction.z );
+ }
+ return 0.5 * ( uv + 1.0 );
+ }
+ vec3 bilinearCubeUV( sampler2D envMap, vec3 direction, float mipInt ) {
+ float face = getFace( direction );
+ float filterInt = max( cubeUV_minMipLevel - mipInt, 0.0 );
+ mipInt = max( mipInt, cubeUV_minMipLevel );
+ float faceSize = exp2( mipInt );
+ highp vec2 uv = getUV( direction, face ) * ( faceSize - 2.0 ) + 1.0;
+ if ( face > 2.0 ) {
+ uv.y += faceSize;
+ face -= 3.0;
+ }
+ uv.x += face * faceSize;
+ uv.x += filterInt * 3.0 * cubeUV_minTileSize;
+ uv.y += 4.0 * ( exp2( CUBEUV_MAX_MIP ) - faceSize );
+ uv.x *= CUBEUV_TEXEL_WIDTH;
+ uv.y *= CUBEUV_TEXEL_HEIGHT;
+ #ifdef texture2DGradEXT
+ return texture2DGradEXT( envMap, uv, vec2( 0.0 ), vec2( 0.0 ) ).rgb;
+ #else
+ return texture2D( envMap, uv ).rgb;
+ #endif
+ }
+ #define cubeUV_r0 1.0
+ #define cubeUV_m0 - 2.0
+ #define cubeUV_r1 0.8
+ #define cubeUV_m1 - 1.0
+ #define cubeUV_r4 0.4
+ #define cubeUV_m4 2.0
+ #define cubeUV_r5 0.305
+ #define cubeUV_m5 3.0
+ #define cubeUV_r6 0.21
+ #define cubeUV_m6 4.0
+ float roughnessToMip( float roughness ) {
+ float mip = 0.0;
+ if ( roughness >= cubeUV_r1 ) {
+ mip = ( cubeUV_r0 - roughness ) * ( cubeUV_m1 - cubeUV_m0 ) / ( cubeUV_r0 - cubeUV_r1 ) + cubeUV_m0;
+ } else if ( roughness >= cubeUV_r4 ) {
+ mip = ( cubeUV_r1 - roughness ) * ( cubeUV_m4 - cubeUV_m1 ) / ( cubeUV_r1 - cubeUV_r4 ) + cubeUV_m1;
+ } else if ( roughness >= cubeUV_r5 ) {
+ mip = ( cubeUV_r4 - roughness ) * ( cubeUV_m5 - cubeUV_m4 ) / ( cubeUV_r4 - cubeUV_r5 ) + cubeUV_m4;
+ } else if ( roughness >= cubeUV_r6 ) {
+ mip = ( cubeUV_r5 - roughness ) * ( cubeUV_m6 - cubeUV_m5 ) / ( cubeUV_r5 - cubeUV_r6 ) + cubeUV_m5;
+ } else {
+ mip = - 2.0 * log2( 1.16 * roughness ); }
+ return mip;
+ }
+ vec4 textureCubeUV( sampler2D envMap, vec3 sampleDir, float roughness ) {
+ float mip = clamp( roughnessToMip( roughness ), cubeUV_m0, CUBEUV_MAX_MIP );
+ float mipF = fract( mip );
+ float mipInt = floor( mip );
+ vec3 color0 = bilinearCubeUV( envMap, sampleDir, mipInt );
+ if ( mipF == 0.0 ) {
+ return vec4( color0, 1.0 );
+ } else {
+ vec3 color1 = bilinearCubeUV( envMap, sampleDir, mipInt + 1.0 );
+ return vec4( mix( color0, color1, mipF ), 1.0 );
+ }
+ }
+#endif`,npe=`vec3 transformedNormal = objectNormal;
+#ifdef USE_TANGENT
+ vec3 transformedTangent = objectTangent;
+#endif
+#ifdef USE_BATCHING
+ mat3 bm = mat3( batchingMatrix );
+ transformedNormal /= vec3( dot( bm[ 0 ], bm[ 0 ] ), dot( bm[ 1 ], bm[ 1 ] ), dot( bm[ 2 ], bm[ 2 ] ) );
+ transformedNormal = bm * transformedNormal;
+ #ifdef USE_TANGENT
+ transformedTangent = bm * transformedTangent;
+ #endif
+#endif
+#ifdef USE_INSTANCING
+ mat3 im = mat3( instanceMatrix );
+ transformedNormal /= vec3( dot( im[ 0 ], im[ 0 ] ), dot( im[ 1 ], im[ 1 ] ), dot( im[ 2 ], im[ 2 ] ) );
+ transformedNormal = im * transformedNormal;
+ #ifdef USE_TANGENT
+ transformedTangent = im * transformedTangent;
+ #endif
+#endif
+transformedNormal = normalMatrix * transformedNormal;
+#ifdef FLIP_SIDED
+ transformedNormal = - transformedNormal;
+#endif
+#ifdef USE_TANGENT
+ transformedTangent = ( modelViewMatrix * vec4( transformedTangent, 0.0 ) ).xyz;
+ #ifdef FLIP_SIDED
+ transformedTangent = - transformedTangent;
+ #endif
+#endif`,rpe=`#ifdef USE_DISPLACEMENTMAP
+ uniform sampler2D displacementMap;
+ uniform float displacementScale;
+ uniform float displacementBias;
+#endif`,ipe=`#ifdef USE_DISPLACEMENTMAP
+ transformed += normalize( objectNormal ) * ( texture2D( displacementMap, vDisplacementMapUv ).x * displacementScale + displacementBias );
+#endif`,spe=`#ifdef USE_EMISSIVEMAP
+ vec4 emissiveColor = texture2D( emissiveMap, vEmissiveMapUv );
+ totalEmissiveRadiance *= emissiveColor.rgb;
+#endif`,ope=`#ifdef USE_EMISSIVEMAP
+ uniform sampler2D emissiveMap;
+#endif`,ape="gl_FragColor = linearToOutputTexel( gl_FragColor );",lpe=`
+const mat3 LINEAR_SRGB_TO_LINEAR_DISPLAY_P3 = mat3(
+ vec3( 0.8224621, 0.177538, 0.0 ),
+ vec3( 0.0331941, 0.9668058, 0.0 ),
+ vec3( 0.0170827, 0.0723974, 0.9105199 )
+);
+const mat3 LINEAR_DISPLAY_P3_TO_LINEAR_SRGB = mat3(
+ vec3( 1.2249401, - 0.2249404, 0.0 ),
+ vec3( - 0.0420569, 1.0420571, 0.0 ),
+ vec3( - 0.0196376, - 0.0786361, 1.0982735 )
+);
+vec4 LinearSRGBToLinearDisplayP3( in vec4 value ) {
+ return vec4( value.rgb * LINEAR_SRGB_TO_LINEAR_DISPLAY_P3, value.a );
+}
+vec4 LinearDisplayP3ToLinearSRGB( in vec4 value ) {
+ return vec4( value.rgb * LINEAR_DISPLAY_P3_TO_LINEAR_SRGB, value.a );
+}
+vec4 LinearTransferOETF( in vec4 value ) {
+ return value;
+}
+vec4 sRGBTransferOETF( in vec4 value ) {
+ return vec4( mix( pow( value.rgb, vec3( 0.41666 ) ) * 1.055 - vec3( 0.055 ), value.rgb * 12.92, vec3( lessThanEqual( value.rgb, vec3( 0.0031308 ) ) ) ), value.a );
+}
+vec4 LinearToLinear( in vec4 value ) {
+ return value;
+}
+vec4 LinearTosRGB( in vec4 value ) {
+ return sRGBTransferOETF( value );
+}`,cpe=`#ifdef USE_ENVMAP
+ #ifdef ENV_WORLDPOS
+ vec3 cameraToFrag;
+ if ( isOrthographic ) {
+ cameraToFrag = normalize( vec3( - viewMatrix[ 0 ][ 2 ], - viewMatrix[ 1 ][ 2 ], - viewMatrix[ 2 ][ 2 ] ) );
+ } else {
+ cameraToFrag = normalize( vWorldPosition - cameraPosition );
+ }
+ vec3 worldNormal = inverseTransformDirection( normal, viewMatrix );
+ #ifdef ENVMAP_MODE_REFLECTION
+ vec3 reflectVec = reflect( cameraToFrag, worldNormal );
+ #else
+ vec3 reflectVec = refract( cameraToFrag, worldNormal, refractionRatio );
+ #endif
+ #else
+ vec3 reflectVec = vReflect;
+ #endif
+ #ifdef ENVMAP_TYPE_CUBE
+ vec4 envColor = textureCube( envMap, envMapRotation * vec3( flipEnvMap * reflectVec.x, reflectVec.yz ) );
+ #else
+ vec4 envColor = vec4( 0.0 );
+ #endif
+ #ifdef ENVMAP_BLENDING_MULTIPLY
+ outgoingLight = mix( outgoingLight, outgoingLight * envColor.xyz, specularStrength * reflectivity );
+ #elif defined( ENVMAP_BLENDING_MIX )
+ outgoingLight = mix( outgoingLight, envColor.xyz, specularStrength * reflectivity );
+ #elif defined( ENVMAP_BLENDING_ADD )
+ outgoingLight += envColor.xyz * specularStrength * reflectivity;
+ #endif
+#endif`,upe=`#ifdef USE_ENVMAP
+ uniform float envMapIntensity;
+ uniform float flipEnvMap;
+ uniform mat3 envMapRotation;
+ #ifdef ENVMAP_TYPE_CUBE
+ uniform samplerCube envMap;
+ #else
+ uniform sampler2D envMap;
+ #endif
+
+#endif`,dpe=`#ifdef USE_ENVMAP
+ uniform float reflectivity;
+ #if defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( PHONG ) || defined( LAMBERT )
+ #define ENV_WORLDPOS
+ #endif
+ #ifdef ENV_WORLDPOS
+ varying vec3 vWorldPosition;
+ uniform float refractionRatio;
+ #else
+ varying vec3 vReflect;
+ #endif
+#endif`,fpe=`#ifdef USE_ENVMAP
+ #if defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( PHONG ) || defined( LAMBERT )
+ #define ENV_WORLDPOS
+ #endif
+ #ifdef ENV_WORLDPOS
+
+ varying vec3 vWorldPosition;
+ #else
+ varying vec3 vReflect;
+ uniform float refractionRatio;
+ #endif
+#endif`,hpe=`#ifdef USE_ENVMAP
+ #ifdef ENV_WORLDPOS
+ vWorldPosition = worldPosition.xyz;
+ #else
+ vec3 cameraToVertex;
+ if ( isOrthographic ) {
+ cameraToVertex = normalize( vec3( - viewMatrix[ 0 ][ 2 ], - viewMatrix[ 1 ][ 2 ], - viewMatrix[ 2 ][ 2 ] ) );
+ } else {
+ cameraToVertex = normalize( worldPosition.xyz - cameraPosition );
+ }
+ vec3 worldNormal = inverseTransformDirection( transformedNormal, viewMatrix );
+ #ifdef ENVMAP_MODE_REFLECTION
+ vReflect = reflect( cameraToVertex, worldNormal );
+ #else
+ vReflect = refract( cameraToVertex, worldNormal, refractionRatio );
+ #endif
+ #endif
+#endif`,ppe=`#ifdef USE_FOG
+ vFogDepth = - mvPosition.z;
+#endif`,mpe=`#ifdef USE_FOG
+ varying float vFogDepth;
+#endif`,gpe=`#ifdef USE_FOG
+ #ifdef FOG_EXP2
+ float fogFactor = 1.0 - exp( - fogDensity * fogDensity * vFogDepth * vFogDepth );
+ #else
+ float fogFactor = smoothstep( fogNear, fogFar, vFogDepth );
+ #endif
+ gl_FragColor.rgb = mix( gl_FragColor.rgb, fogColor, fogFactor );
+#endif`,vpe=`#ifdef USE_FOG
+ uniform vec3 fogColor;
+ varying float vFogDepth;
+ #ifdef FOG_EXP2
+ uniform float fogDensity;
+ #else
+ uniform float fogNear;
+ uniform float fogFar;
+ #endif
+#endif`,ype=`#ifdef USE_GRADIENTMAP
+ uniform sampler2D gradientMap;
+#endif
+vec3 getGradientIrradiance( vec3 normal, vec3 lightDirection ) {
+ float dotNL = dot( normal, lightDirection );
+ vec2 coord = vec2( dotNL * 0.5 + 0.5, 0.0 );
+ #ifdef USE_GRADIENTMAP
+ return vec3( texture2D( gradientMap, coord ).r );
+ #else
+ vec2 fw = fwidth( coord ) * 0.5;
+ return mix( vec3( 0.7 ), vec3( 1.0 ), smoothstep( 0.7 - fw.x, 0.7 + fw.x, coord.x ) );
+ #endif
+}`,xpe=`#ifdef USE_LIGHTMAP
+ uniform sampler2D lightMap;
+ uniform float lightMapIntensity;
+#endif`,_pe=`LambertMaterial material;
+material.diffuseColor = diffuseColor.rgb;
+material.specularStrength = specularStrength;`,bpe=`varying vec3 vViewPosition;
+struct LambertMaterial {
+ vec3 diffuseColor;
+ float specularStrength;
+};
+void RE_Direct_Lambert( const in IncidentLight directLight, const in vec3 geometryPosition, const in vec3 geometryNormal, const in vec3 geometryViewDir, const in vec3 geometryClearcoatNormal, const in LambertMaterial material, inout ReflectedLight reflectedLight ) {
+ float dotNL = saturate( dot( geometryNormal, directLight.direction ) );
+ vec3 irradiance = dotNL * directLight.color;
+ reflectedLight.directDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );
+}
+void RE_IndirectDiffuse_Lambert( const in vec3 irradiance, const in vec3 geometryPosition, const in vec3 geometryNormal, const in vec3 geometryViewDir, const in vec3 geometryClearcoatNormal, const in LambertMaterial material, inout ReflectedLight reflectedLight ) {
+ reflectedLight.indirectDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );
+}
+#define RE_Direct RE_Direct_Lambert
+#define RE_IndirectDiffuse RE_IndirectDiffuse_Lambert`,Spe=`uniform bool receiveShadow;
+uniform vec3 ambientLightColor;
+#if defined( USE_LIGHT_PROBES )
+ uniform vec3 lightProbe[ 9 ];
+#endif
+vec3 shGetIrradianceAt( in vec3 normal, in vec3 shCoefficients[ 9 ] ) {
+ float x = normal.x, y = normal.y, z = normal.z;
+ vec3 result = shCoefficients[ 0 ] * 0.886227;
+ result += shCoefficients[ 1 ] * 2.0 * 0.511664 * y;
+ result += shCoefficients[ 2 ] * 2.0 * 0.511664 * z;
+ result += shCoefficients[ 3 ] * 2.0 * 0.511664 * x;
+ result += shCoefficients[ 4 ] * 2.0 * 0.429043 * x * y;
+ result += shCoefficients[ 5 ] * 2.0 * 0.429043 * y * z;
+ result += shCoefficients[ 6 ] * ( 0.743125 * z * z - 0.247708 );
+ result += shCoefficients[ 7 ] * 2.0 * 0.429043 * x * z;
+ result += shCoefficients[ 8 ] * 0.429043 * ( x * x - y * y );
+ return result;
+}
+vec3 getLightProbeIrradiance( const in vec3 lightProbe[ 9 ], const in vec3 normal ) {
+ vec3 worldNormal = inverseTransformDirection( normal, viewMatrix );
+ vec3 irradiance = shGetIrradianceAt( worldNormal, lightProbe );
+ return irradiance;
+}
+vec3 getAmbientLightIrradiance( const in vec3 ambientLightColor ) {
+ vec3 irradiance = ambientLightColor;
+ return irradiance;
+}
+float getDistanceAttenuation( const in float lightDistance, const in float cutoffDistance, const in float decayExponent ) {
+ #if defined ( LEGACY_LIGHTS )
+ if ( cutoffDistance > 0.0 && decayExponent > 0.0 ) {
+ return pow( saturate( - lightDistance / cutoffDistance + 1.0 ), decayExponent );
+ }
+ return 1.0;
+ #else
+ float distanceFalloff = 1.0 / max( pow( lightDistance, decayExponent ), 0.01 );
+ if ( cutoffDistance > 0.0 ) {
+ distanceFalloff *= pow2( saturate( 1.0 - pow4( lightDistance / cutoffDistance ) ) );
+ }
+ return distanceFalloff;
+ #endif
+}
+float getSpotAttenuation( const in float coneCosine, const in float penumbraCosine, const in float angleCosine ) {
+ return smoothstep( coneCosine, penumbraCosine, angleCosine );
+}
+#if NUM_DIR_LIGHTS > 0
+ struct DirectionalLight {
+ vec3 direction;
+ vec3 color;
+ };
+ uniform DirectionalLight directionalLights[ NUM_DIR_LIGHTS ];
+ void getDirectionalLightInfo( const in DirectionalLight directionalLight, out IncidentLight light ) {
+ light.color = directionalLight.color;
+ light.direction = directionalLight.direction;
+ light.visible = true;
+ }
+#endif
+#if NUM_POINT_LIGHTS > 0
+ struct PointLight {
+ vec3 position;
+ vec3 color;
+ float distance;
+ float decay;
+ };
+ uniform PointLight pointLights[ NUM_POINT_LIGHTS ];
+ void getPointLightInfo( const in PointLight pointLight, const in vec3 geometryPosition, out IncidentLight light ) {
+ vec3 lVector = pointLight.position - geometryPosition;
+ light.direction = normalize( lVector );
+ float lightDistance = length( lVector );
+ light.color = pointLight.color;
+ light.color *= getDistanceAttenuation( lightDistance, pointLight.distance, pointLight.decay );
+ light.visible = ( light.color != vec3( 0.0 ) );
+ }
+#endif
+#if NUM_SPOT_LIGHTS > 0
+ struct SpotLight {
+ vec3 position;
+ vec3 direction;
+ vec3 color;
+ float distance;
+ float decay;
+ float coneCos;
+ float penumbraCos;
+ };
+ uniform SpotLight spotLights[ NUM_SPOT_LIGHTS ];
+ void getSpotLightInfo( const in SpotLight spotLight, const in vec3 geometryPosition, out IncidentLight light ) {
+ vec3 lVector = spotLight.position - geometryPosition;
+ light.direction = normalize( lVector );
+ float angleCos = dot( light.direction, spotLight.direction );
+ float spotAttenuation = getSpotAttenuation( spotLight.coneCos, spotLight.penumbraCos, angleCos );
+ if ( spotAttenuation > 0.0 ) {
+ float lightDistance = length( lVector );
+ light.color = spotLight.color * spotAttenuation;
+ light.color *= getDistanceAttenuation( lightDistance, spotLight.distance, spotLight.decay );
+ light.visible = ( light.color != vec3( 0.0 ) );
+ } else {
+ light.color = vec3( 0.0 );
+ light.visible = false;
+ }
+ }
+#endif
+#if NUM_RECT_AREA_LIGHTS > 0
+ struct RectAreaLight {
+ vec3 color;
+ vec3 position;
+ vec3 halfWidth;
+ vec3 halfHeight;
+ };
+ uniform sampler2D ltc_1; uniform sampler2D ltc_2;
+ uniform RectAreaLight rectAreaLights[ NUM_RECT_AREA_LIGHTS ];
+#endif
+#if NUM_HEMI_LIGHTS > 0
+ struct HemisphereLight {
+ vec3 direction;
+ vec3 skyColor;
+ vec3 groundColor;
+ };
+ uniform HemisphereLight hemisphereLights[ NUM_HEMI_LIGHTS ];
+ vec3 getHemisphereLightIrradiance( const in HemisphereLight hemiLight, const in vec3 normal ) {
+ float dotNL = dot( normal, hemiLight.direction );
+ float hemiDiffuseWeight = 0.5 * dotNL + 0.5;
+ vec3 irradiance = mix( hemiLight.groundColor, hemiLight.skyColor, hemiDiffuseWeight );
+ return irradiance;
+ }
+#endif`,wpe=`#ifdef USE_ENVMAP
+ vec3 getIBLIrradiance( const in vec3 normal ) {
+ #ifdef ENVMAP_TYPE_CUBE_UV
+ vec3 worldNormal = inverseTransformDirection( normal, viewMatrix );
+ vec4 envMapColor = textureCubeUV( envMap, envMapRotation * worldNormal, 1.0 );
+ return PI * envMapColor.rgb * envMapIntensity;
+ #else
+ return vec3( 0.0 );
+ #endif
+ }
+ vec3 getIBLRadiance( const in vec3 viewDir, const in vec3 normal, const in float roughness ) {
+ #ifdef ENVMAP_TYPE_CUBE_UV
+ vec3 reflectVec = reflect( - viewDir, normal );
+ reflectVec = normalize( mix( reflectVec, normal, roughness * roughness) );
+ reflectVec = inverseTransformDirection( reflectVec, viewMatrix );
+ vec4 envMapColor = textureCubeUV( envMap, envMapRotation * reflectVec, roughness );
+ return envMapColor.rgb * envMapIntensity;
+ #else
+ return vec3( 0.0 );
+ #endif
+ }
+ #ifdef USE_ANISOTROPY
+ vec3 getIBLAnisotropyRadiance( const in vec3 viewDir, const in vec3 normal, const in float roughness, const in vec3 bitangent, const in float anisotropy ) {
+ #ifdef ENVMAP_TYPE_CUBE_UV
+ vec3 bentNormal = cross( bitangent, viewDir );
+ bentNormal = normalize( cross( bentNormal, bitangent ) );
+ bentNormal = normalize( mix( bentNormal, normal, pow2( pow2( 1.0 - anisotropy * ( 1.0 - roughness ) ) ) ) );
+ return getIBLRadiance( viewDir, bentNormal, roughness );
+ #else
+ return vec3( 0.0 );
+ #endif
+ }
+ #endif
+#endif`,Mpe=`ToonMaterial material;
+material.diffuseColor = diffuseColor.rgb;`,Epe=`varying vec3 vViewPosition;
+struct ToonMaterial {
+ vec3 diffuseColor;
+};
+void RE_Direct_Toon( const in IncidentLight directLight, const in vec3 geometryPosition, const in vec3 geometryNormal, const in vec3 geometryViewDir, const in vec3 geometryClearcoatNormal, const in ToonMaterial material, inout ReflectedLight reflectedLight ) {
+ vec3 irradiance = getGradientIrradiance( geometryNormal, directLight.direction ) * directLight.color;
+ reflectedLight.directDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );
+}
+void RE_IndirectDiffuse_Toon( const in vec3 irradiance, const in vec3 geometryPosition, const in vec3 geometryNormal, const in vec3 geometryViewDir, const in vec3 geometryClearcoatNormal, const in ToonMaterial material, inout ReflectedLight reflectedLight ) {
+ reflectedLight.indirectDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );
+}
+#define RE_Direct RE_Direct_Toon
+#define RE_IndirectDiffuse RE_IndirectDiffuse_Toon`,Cpe=`BlinnPhongMaterial material;
+material.diffuseColor = diffuseColor.rgb;
+material.specularColor = specular;
+material.specularShininess = shininess;
+material.specularStrength = specularStrength;`,Tpe=`varying vec3 vViewPosition;
+struct BlinnPhongMaterial {
+ vec3 diffuseColor;
+ vec3 specularColor;
+ float specularShininess;
+ float specularStrength;
+};
+void RE_Direct_BlinnPhong( const in IncidentLight directLight, const in vec3 geometryPosition, const in vec3 geometryNormal, const in vec3 geometryViewDir, const in vec3 geometryClearcoatNormal, const in BlinnPhongMaterial material, inout ReflectedLight reflectedLight ) {
+ float dotNL = saturate( dot( geometryNormal, directLight.direction ) );
+ vec3 irradiance = dotNL * directLight.color;
+ reflectedLight.directDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );
+ reflectedLight.directSpecular += irradiance * BRDF_BlinnPhong( directLight.direction, geometryViewDir, geometryNormal, material.specularColor, material.specularShininess ) * material.specularStrength;
+}
+void RE_IndirectDiffuse_BlinnPhong( const in vec3 irradiance, const in vec3 geometryPosition, const in vec3 geometryNormal, const in vec3 geometryViewDir, const in vec3 geometryClearcoatNormal, const in BlinnPhongMaterial material, inout ReflectedLight reflectedLight ) {
+ reflectedLight.indirectDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );
+}
+#define RE_Direct RE_Direct_BlinnPhong
+#define RE_IndirectDiffuse RE_IndirectDiffuse_BlinnPhong`,Ape=`PhysicalMaterial material;
+material.diffuseColor = diffuseColor.rgb * ( 1.0 - metalnessFactor );
+vec3 dxy = max( abs( dFdx( nonPerturbedNormal ) ), abs( dFdy( nonPerturbedNormal ) ) );
+float geometryRoughness = max( max( dxy.x, dxy.y ), dxy.z );
+material.roughness = max( roughnessFactor, 0.0525 );material.roughness += geometryRoughness;
+material.roughness = min( material.roughness, 1.0 );
+#ifdef IOR
+ material.ior = ior;
+ #ifdef USE_SPECULAR
+ float specularIntensityFactor = specularIntensity;
+ vec3 specularColorFactor = specularColor;
+ #ifdef USE_SPECULAR_COLORMAP
+ specularColorFactor *= texture2D( specularColorMap, vSpecularColorMapUv ).rgb;
+ #endif
+ #ifdef USE_SPECULAR_INTENSITYMAP
+ specularIntensityFactor *= texture2D( specularIntensityMap, vSpecularIntensityMapUv ).a;
+ #endif
+ material.specularF90 = mix( specularIntensityFactor, 1.0, metalnessFactor );
+ #else
+ float specularIntensityFactor = 1.0;
+ vec3 specularColorFactor = vec3( 1.0 );
+ material.specularF90 = 1.0;
+ #endif
+ material.specularColor = mix( min( pow2( ( material.ior - 1.0 ) / ( material.ior + 1.0 ) ) * specularColorFactor, vec3( 1.0 ) ) * specularIntensityFactor, diffuseColor.rgb, metalnessFactor );
+#else
+ material.specularColor = mix( vec3( 0.04 ), diffuseColor.rgb, metalnessFactor );
+ material.specularF90 = 1.0;
+#endif
+#ifdef USE_CLEARCOAT
+ material.clearcoat = clearcoat;
+ material.clearcoatRoughness = clearcoatRoughness;
+ material.clearcoatF0 = vec3( 0.04 );
+ material.clearcoatF90 = 1.0;
+ #ifdef USE_CLEARCOATMAP
+ material.clearcoat *= texture2D( clearcoatMap, vClearcoatMapUv ).x;
+ #endif
+ #ifdef USE_CLEARCOAT_ROUGHNESSMAP
+ material.clearcoatRoughness *= texture2D( clearcoatRoughnessMap, vClearcoatRoughnessMapUv ).y;
+ #endif
+ material.clearcoat = saturate( material.clearcoat ); material.clearcoatRoughness = max( material.clearcoatRoughness, 0.0525 );
+ material.clearcoatRoughness += geometryRoughness;
+ material.clearcoatRoughness = min( material.clearcoatRoughness, 1.0 );
+#endif
+#ifdef USE_DISPERSION
+ material.dispersion = dispersion;
+#endif
+#ifdef USE_IRIDESCENCE
+ material.iridescence = iridescence;
+ material.iridescenceIOR = iridescenceIOR;
+ #ifdef USE_IRIDESCENCEMAP
+ material.iridescence *= texture2D( iridescenceMap, vIridescenceMapUv ).r;
+ #endif
+ #ifdef USE_IRIDESCENCE_THICKNESSMAP
+ material.iridescenceThickness = (iridescenceThicknessMaximum - iridescenceThicknessMinimum) * texture2D( iridescenceThicknessMap, vIridescenceThicknessMapUv ).g + iridescenceThicknessMinimum;
+ #else
+ material.iridescenceThickness = iridescenceThicknessMaximum;
+ #endif
+#endif
+#ifdef USE_SHEEN
+ material.sheenColor = sheenColor;
+ #ifdef USE_SHEEN_COLORMAP
+ material.sheenColor *= texture2D( sheenColorMap, vSheenColorMapUv ).rgb;
+ #endif
+ material.sheenRoughness = clamp( sheenRoughness, 0.07, 1.0 );
+ #ifdef USE_SHEEN_ROUGHNESSMAP
+ material.sheenRoughness *= texture2D( sheenRoughnessMap, vSheenRoughnessMapUv ).a;
+ #endif
+#endif
+#ifdef USE_ANISOTROPY
+ #ifdef USE_ANISOTROPYMAP
+ mat2 anisotropyMat = mat2( anisotropyVector.x, anisotropyVector.y, - anisotropyVector.y, anisotropyVector.x );
+ vec3 anisotropyPolar = texture2D( anisotropyMap, vAnisotropyMapUv ).rgb;
+ vec2 anisotropyV = anisotropyMat * normalize( 2.0 * anisotropyPolar.rg - vec2( 1.0 ) ) * anisotropyPolar.b;
+ #else
+ vec2 anisotropyV = anisotropyVector;
+ #endif
+ material.anisotropy = length( anisotropyV );
+ if( material.anisotropy == 0.0 ) {
+ anisotropyV = vec2( 1.0, 0.0 );
+ } else {
+ anisotropyV /= material.anisotropy;
+ material.anisotropy = saturate( material.anisotropy );
+ }
+ material.alphaT = mix( pow2( material.roughness ), 1.0, pow2( material.anisotropy ) );
+ material.anisotropyT = tbn[ 0 ] * anisotropyV.x + tbn[ 1 ] * anisotropyV.y;
+ material.anisotropyB = tbn[ 1 ] * anisotropyV.x - tbn[ 0 ] * anisotropyV.y;
+#endif`,Rpe=`struct PhysicalMaterial {
+ vec3 diffuseColor;
+ float roughness;
+ vec3 specularColor;
+ float specularF90;
+ float dispersion;
+ #ifdef USE_CLEARCOAT
+ float clearcoat;
+ float clearcoatRoughness;
+ vec3 clearcoatF0;
+ float clearcoatF90;
+ #endif
+ #ifdef USE_IRIDESCENCE
+ float iridescence;
+ float iridescenceIOR;
+ float iridescenceThickness;
+ vec3 iridescenceFresnel;
+ vec3 iridescenceF0;
+ #endif
+ #ifdef USE_SHEEN
+ vec3 sheenColor;
+ float sheenRoughness;
+ #endif
+ #ifdef IOR
+ float ior;
+ #endif
+ #ifdef USE_TRANSMISSION
+ float transmission;
+ float transmissionAlpha;
+ float thickness;
+ float attenuationDistance;
+ vec3 attenuationColor;
+ #endif
+ #ifdef USE_ANISOTROPY
+ float anisotropy;
+ float alphaT;
+ vec3 anisotropyT;
+ vec3 anisotropyB;
+ #endif
+};
+vec3 clearcoatSpecularDirect = vec3( 0.0 );
+vec3 clearcoatSpecularIndirect = vec3( 0.0 );
+vec3 sheenSpecularDirect = vec3( 0.0 );
+vec3 sheenSpecularIndirect = vec3(0.0 );
+vec3 Schlick_to_F0( const in vec3 f, const in float f90, const in float dotVH ) {
+ float x = clamp( 1.0 - dotVH, 0.0, 1.0 );
+ float x2 = x * x;
+ float x5 = clamp( x * x2 * x2, 0.0, 0.9999 );
+ return ( f - vec3( f90 ) * x5 ) / ( 1.0 - x5 );
+}
+float V_GGX_SmithCorrelated( const in float alpha, const in float dotNL, const in float dotNV ) {
+ float a2 = pow2( alpha );
+ float gv = dotNL * sqrt( a2 + ( 1.0 - a2 ) * pow2( dotNV ) );
+ float gl = dotNV * sqrt( a2 + ( 1.0 - a2 ) * pow2( dotNL ) );
+ return 0.5 / max( gv + gl, EPSILON );
+}
+float D_GGX( const in float alpha, const in float dotNH ) {
+ float a2 = pow2( alpha );
+ float denom = pow2( dotNH ) * ( a2 - 1.0 ) + 1.0;
+ return RECIPROCAL_PI * a2 / pow2( denom );
+}
+#ifdef USE_ANISOTROPY
+ float V_GGX_SmithCorrelated_Anisotropic( const in float alphaT, const in float alphaB, const in float dotTV, const in float dotBV, const in float dotTL, const in float dotBL, const in float dotNV, const in float dotNL ) {
+ float gv = dotNL * length( vec3( alphaT * dotTV, alphaB * dotBV, dotNV ) );
+ float gl = dotNV * length( vec3( alphaT * dotTL, alphaB * dotBL, dotNL ) );
+ float v = 0.5 / ( gv + gl );
+ return saturate(v);
+ }
+ float D_GGX_Anisotropic( const in float alphaT, const in float alphaB, const in float dotNH, const in float dotTH, const in float dotBH ) {
+ float a2 = alphaT * alphaB;
+ highp vec3 v = vec3( alphaB * dotTH, alphaT * dotBH, a2 * dotNH );
+ highp float v2 = dot( v, v );
+ float w2 = a2 / v2;
+ return RECIPROCAL_PI * a2 * pow2 ( w2 );
+ }
+#endif
+#ifdef USE_CLEARCOAT
+ vec3 BRDF_GGX_Clearcoat( const in vec3 lightDir, const in vec3 viewDir, const in vec3 normal, const in PhysicalMaterial material) {
+ vec3 f0 = material.clearcoatF0;
+ float f90 = material.clearcoatF90;
+ float roughness = material.clearcoatRoughness;
+ float alpha = pow2( roughness );
+ vec3 halfDir = normalize( lightDir + viewDir );
+ float dotNL = saturate( dot( normal, lightDir ) );
+ float dotNV = saturate( dot( normal, viewDir ) );
+ float dotNH = saturate( dot( normal, halfDir ) );
+ float dotVH = saturate( dot( viewDir, halfDir ) );
+ vec3 F = F_Schlick( f0, f90, dotVH );
+ float V = V_GGX_SmithCorrelated( alpha, dotNL, dotNV );
+ float D = D_GGX( alpha, dotNH );
+ return F * ( V * D );
+ }
+#endif
+vec3 BRDF_GGX( const in vec3 lightDir, const in vec3 viewDir, const in vec3 normal, const in PhysicalMaterial material ) {
+ vec3 f0 = material.specularColor;
+ float f90 = material.specularF90;
+ float roughness = material.roughness;
+ float alpha = pow2( roughness );
+ vec3 halfDir = normalize( lightDir + viewDir );
+ float dotNL = saturate( dot( normal, lightDir ) );
+ float dotNV = saturate( dot( normal, viewDir ) );
+ float dotNH = saturate( dot( normal, halfDir ) );
+ float dotVH = saturate( dot( viewDir, halfDir ) );
+ vec3 F = F_Schlick( f0, f90, dotVH );
+ #ifdef USE_IRIDESCENCE
+ F = mix( F, material.iridescenceFresnel, material.iridescence );
+ #endif
+ #ifdef USE_ANISOTROPY
+ float dotTL = dot( material.anisotropyT, lightDir );
+ float dotTV = dot( material.anisotropyT, viewDir );
+ float dotTH = dot( material.anisotropyT, halfDir );
+ float dotBL = dot( material.anisotropyB, lightDir );
+ float dotBV = dot( material.anisotropyB, viewDir );
+ float dotBH = dot( material.anisotropyB, halfDir );
+ float V = V_GGX_SmithCorrelated_Anisotropic( material.alphaT, alpha, dotTV, dotBV, dotTL, dotBL, dotNV, dotNL );
+ float D = D_GGX_Anisotropic( material.alphaT, alpha, dotNH, dotTH, dotBH );
+ #else
+ float V = V_GGX_SmithCorrelated( alpha, dotNL, dotNV );
+ float D = D_GGX( alpha, dotNH );
+ #endif
+ return F * ( V * D );
+}
+vec2 LTC_Uv( const in vec3 N, const in vec3 V, const in float roughness ) {
+ const float LUT_SIZE = 64.0;
+ const float LUT_SCALE = ( LUT_SIZE - 1.0 ) / LUT_SIZE;
+ const float LUT_BIAS = 0.5 / LUT_SIZE;
+ float dotNV = saturate( dot( N, V ) );
+ vec2 uv = vec2( roughness, sqrt( 1.0 - dotNV ) );
+ uv = uv * LUT_SCALE + LUT_BIAS;
+ return uv;
+}
+float LTC_ClippedSphereFormFactor( const in vec3 f ) {
+ float l = length( f );
+ return max( ( l * l + f.z ) / ( l + 1.0 ), 0.0 );
+}
+vec3 LTC_EdgeVectorFormFactor( const in vec3 v1, const in vec3 v2 ) {
+ float x = dot( v1, v2 );
+ float y = abs( x );
+ float a = 0.8543985 + ( 0.4965155 + 0.0145206 * y ) * y;
+ float b = 3.4175940 + ( 4.1616724 + y ) * y;
+ float v = a / b;
+ float theta_sintheta = ( x > 0.0 ) ? v : 0.5 * inversesqrt( max( 1.0 - x * x, 1e-7 ) ) - v;
+ return cross( v1, v2 ) * theta_sintheta;
+}
+vec3 LTC_Evaluate( const in vec3 N, const in vec3 V, const in vec3 P, const in mat3 mInv, const in vec3 rectCoords[ 4 ] ) {
+ vec3 v1 = rectCoords[ 1 ] - rectCoords[ 0 ];
+ vec3 v2 = rectCoords[ 3 ] - rectCoords[ 0 ];
+ vec3 lightNormal = cross( v1, v2 );
+ if( dot( lightNormal, P - rectCoords[ 0 ] ) < 0.0 ) return vec3( 0.0 );
+ vec3 T1, T2;
+ T1 = normalize( V - N * dot( V, N ) );
+ T2 = - cross( N, T1 );
+ mat3 mat = mInv * transposeMat3( mat3( T1, T2, N ) );
+ vec3 coords[ 4 ];
+ coords[ 0 ] = mat * ( rectCoords[ 0 ] - P );
+ coords[ 1 ] = mat * ( rectCoords[ 1 ] - P );
+ coords[ 2 ] = mat * ( rectCoords[ 2 ] - P );
+ coords[ 3 ] = mat * ( rectCoords[ 3 ] - P );
+ coords[ 0 ] = normalize( coords[ 0 ] );
+ coords[ 1 ] = normalize( coords[ 1 ] );
+ coords[ 2 ] = normalize( coords[ 2 ] );
+ coords[ 3 ] = normalize( coords[ 3 ] );
+ vec3 vectorFormFactor = vec3( 0.0 );
+ vectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 0 ], coords[ 1 ] );
+ vectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 1 ], coords[ 2 ] );
+ vectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 2 ], coords[ 3 ] );
+ vectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 3 ], coords[ 0 ] );
+ float result = LTC_ClippedSphereFormFactor( vectorFormFactor );
+ return vec3( result );
+}
+#if defined( USE_SHEEN )
+float D_Charlie( float roughness, float dotNH ) {
+ float alpha = pow2( roughness );
+ float invAlpha = 1.0 / alpha;
+ float cos2h = dotNH * dotNH;
+ float sin2h = max( 1.0 - cos2h, 0.0078125 );
+ return ( 2.0 + invAlpha ) * pow( sin2h, invAlpha * 0.5 ) / ( 2.0 * PI );
+}
+float V_Neubelt( float dotNV, float dotNL ) {
+ return saturate( 1.0 / ( 4.0 * ( dotNL + dotNV - dotNL * dotNV ) ) );
+}
+vec3 BRDF_Sheen( const in vec3 lightDir, const in vec3 viewDir, const in vec3 normal, vec3 sheenColor, const in float sheenRoughness ) {
+ vec3 halfDir = normalize( lightDir + viewDir );
+ float dotNL = saturate( dot( normal, lightDir ) );
+ float dotNV = saturate( dot( normal, viewDir ) );
+ float dotNH = saturate( dot( normal, halfDir ) );
+ float D = D_Charlie( sheenRoughness, dotNH );
+ float V = V_Neubelt( dotNV, dotNL );
+ return sheenColor * ( D * V );
+}
+#endif
+float IBLSheenBRDF( const in vec3 normal, const in vec3 viewDir, const in float roughness ) {
+ float dotNV = saturate( dot( normal, viewDir ) );
+ float r2 = roughness * roughness;
+ float a = roughness < 0.25 ? -339.2 * r2 + 161.4 * roughness - 25.9 : -8.48 * r2 + 14.3 * roughness - 9.95;
+ float b = roughness < 0.25 ? 44.0 * r2 - 23.7 * roughness + 3.26 : 1.97 * r2 - 3.27 * roughness + 0.72;
+ float DG = exp( a * dotNV + b ) + ( roughness < 0.25 ? 0.0 : 0.1 * ( roughness - 0.25 ) );
+ return saturate( DG * RECIPROCAL_PI );
+}
+vec2 DFGApprox( const in vec3 normal, const in vec3 viewDir, const in float roughness ) {
+ float dotNV = saturate( dot( normal, viewDir ) );
+ const vec4 c0 = vec4( - 1, - 0.0275, - 0.572, 0.022 );
+ const vec4 c1 = vec4( 1, 0.0425, 1.04, - 0.04 );
+ vec4 r = roughness * c0 + c1;
+ float a004 = min( r.x * r.x, exp2( - 9.28 * dotNV ) ) * r.x + r.y;
+ vec2 fab = vec2( - 1.04, 1.04 ) * a004 + r.zw;
+ return fab;
+}
+vec3 EnvironmentBRDF( const in vec3 normal, const in vec3 viewDir, const in vec3 specularColor, const in float specularF90, const in float roughness ) {
+ vec2 fab = DFGApprox( normal, viewDir, roughness );
+ return specularColor * fab.x + specularF90 * fab.y;
+}
+#ifdef USE_IRIDESCENCE
+void computeMultiscatteringIridescence( const in vec3 normal, const in vec3 viewDir, const in vec3 specularColor, const in float specularF90, const in float iridescence, const in vec3 iridescenceF0, const in float roughness, inout vec3 singleScatter, inout vec3 multiScatter ) {
+#else
+void computeMultiscattering( const in vec3 normal, const in vec3 viewDir, const in vec3 specularColor, const in float specularF90, const in float roughness, inout vec3 singleScatter, inout vec3 multiScatter ) {
+#endif
+ vec2 fab = DFGApprox( normal, viewDir, roughness );
+ #ifdef USE_IRIDESCENCE
+ vec3 Fr = mix( specularColor, iridescenceF0, iridescence );
+ #else
+ vec3 Fr = specularColor;
+ #endif
+ vec3 FssEss = Fr * fab.x + specularF90 * fab.y;
+ float Ess = fab.x + fab.y;
+ float Ems = 1.0 - Ess;
+ vec3 Favg = Fr + ( 1.0 - Fr ) * 0.047619; vec3 Fms = FssEss * Favg / ( 1.0 - Ems * Favg );
+ singleScatter += FssEss;
+ multiScatter += Fms * Ems;
+}
+#if NUM_RECT_AREA_LIGHTS > 0
+ void RE_Direct_RectArea_Physical( const in RectAreaLight rectAreaLight, const in vec3 geometryPosition, const in vec3 geometryNormal, const in vec3 geometryViewDir, const in vec3 geometryClearcoatNormal, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {
+ vec3 normal = geometryNormal;
+ vec3 viewDir = geometryViewDir;
+ vec3 position = geometryPosition;
+ vec3 lightPos = rectAreaLight.position;
+ vec3 halfWidth = rectAreaLight.halfWidth;
+ vec3 halfHeight = rectAreaLight.halfHeight;
+ vec3 lightColor = rectAreaLight.color;
+ float roughness = material.roughness;
+ vec3 rectCoords[ 4 ];
+ rectCoords[ 0 ] = lightPos + halfWidth - halfHeight; rectCoords[ 1 ] = lightPos - halfWidth - halfHeight;
+ rectCoords[ 2 ] = lightPos - halfWidth + halfHeight;
+ rectCoords[ 3 ] = lightPos + halfWidth + halfHeight;
+ vec2 uv = LTC_Uv( normal, viewDir, roughness );
+ vec4 t1 = texture2D( ltc_1, uv );
+ vec4 t2 = texture2D( ltc_2, uv );
+ mat3 mInv = mat3(
+ vec3( t1.x, 0, t1.y ),
+ vec3( 0, 1, 0 ),
+ vec3( t1.z, 0, t1.w )
+ );
+ vec3 fresnel = ( material.specularColor * t2.x + ( vec3( 1.0 ) - material.specularColor ) * t2.y );
+ reflectedLight.directSpecular += lightColor * fresnel * LTC_Evaluate( normal, viewDir, position, mInv, rectCoords );
+ reflectedLight.directDiffuse += lightColor * material.diffuseColor * LTC_Evaluate( normal, viewDir, position, mat3( 1.0 ), rectCoords );
+ }
+#endif
+void RE_Direct_Physical( const in IncidentLight directLight, const in vec3 geometryPosition, const in vec3 geometryNormal, const in vec3 geometryViewDir, const in vec3 geometryClearcoatNormal, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {
+ float dotNL = saturate( dot( geometryNormal, directLight.direction ) );
+ vec3 irradiance = dotNL * directLight.color;
+ #ifdef USE_CLEARCOAT
+ float dotNLcc = saturate( dot( geometryClearcoatNormal, directLight.direction ) );
+ vec3 ccIrradiance = dotNLcc * directLight.color;
+ clearcoatSpecularDirect += ccIrradiance * BRDF_GGX_Clearcoat( directLight.direction, geometryViewDir, geometryClearcoatNormal, material );
+ #endif
+ #ifdef USE_SHEEN
+ sheenSpecularDirect += irradiance * BRDF_Sheen( directLight.direction, geometryViewDir, geometryNormal, material.sheenColor, material.sheenRoughness );
+ #endif
+ reflectedLight.directSpecular += irradiance * BRDF_GGX( directLight.direction, geometryViewDir, geometryNormal, material );
+ reflectedLight.directDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );
+}
+void RE_IndirectDiffuse_Physical( const in vec3 irradiance, const in vec3 geometryPosition, const in vec3 geometryNormal, const in vec3 geometryViewDir, const in vec3 geometryClearcoatNormal, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {
+ reflectedLight.indirectDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );
+}
+void RE_IndirectSpecular_Physical( const in vec3 radiance, const in vec3 irradiance, const in vec3 clearcoatRadiance, const in vec3 geometryPosition, const in vec3 geometryNormal, const in vec3 geometryViewDir, const in vec3 geometryClearcoatNormal, const in PhysicalMaterial material, inout ReflectedLight reflectedLight) {
+ #ifdef USE_CLEARCOAT
+ clearcoatSpecularIndirect += clearcoatRadiance * EnvironmentBRDF( geometryClearcoatNormal, geometryViewDir, material.clearcoatF0, material.clearcoatF90, material.clearcoatRoughness );
+ #endif
+ #ifdef USE_SHEEN
+ sheenSpecularIndirect += irradiance * material.sheenColor * IBLSheenBRDF( geometryNormal, geometryViewDir, material.sheenRoughness );
+ #endif
+ vec3 singleScattering = vec3( 0.0 );
+ vec3 multiScattering = vec3( 0.0 );
+ vec3 cosineWeightedIrradiance = irradiance * RECIPROCAL_PI;
+ #ifdef USE_IRIDESCENCE
+ computeMultiscatteringIridescence( geometryNormal, geometryViewDir, material.specularColor, material.specularF90, material.iridescence, material.iridescenceFresnel, material.roughness, singleScattering, multiScattering );
+ #else
+ computeMultiscattering( geometryNormal, geometryViewDir, material.specularColor, material.specularF90, material.roughness, singleScattering, multiScattering );
+ #endif
+ vec3 totalScattering = singleScattering + multiScattering;
+ vec3 diffuse = material.diffuseColor * ( 1.0 - max( max( totalScattering.r, totalScattering.g ), totalScattering.b ) );
+ reflectedLight.indirectSpecular += radiance * singleScattering;
+ reflectedLight.indirectSpecular += multiScattering * cosineWeightedIrradiance;
+ reflectedLight.indirectDiffuse += diffuse * cosineWeightedIrradiance;
+}
+#define RE_Direct RE_Direct_Physical
+#define RE_Direct_RectArea RE_Direct_RectArea_Physical
+#define RE_IndirectDiffuse RE_IndirectDiffuse_Physical
+#define RE_IndirectSpecular RE_IndirectSpecular_Physical
+float computeSpecularOcclusion( const in float dotNV, const in float ambientOcclusion, const in float roughness ) {
+ return saturate( pow( dotNV + ambientOcclusion, exp2( - 16.0 * roughness - 1.0 ) ) - 1.0 + ambientOcclusion );
+}`,Ppe=`
+vec3 geometryPosition = - vViewPosition;
+vec3 geometryNormal = normal;
+vec3 geometryViewDir = ( isOrthographic ) ? vec3( 0, 0, 1 ) : normalize( vViewPosition );
+vec3 geometryClearcoatNormal = vec3( 0.0 );
+#ifdef USE_CLEARCOAT
+ geometryClearcoatNormal = clearcoatNormal;
+#endif
+#ifdef USE_IRIDESCENCE
+ float dotNVi = saturate( dot( normal, geometryViewDir ) );
+ if ( material.iridescenceThickness == 0.0 ) {
+ material.iridescence = 0.0;
+ } else {
+ material.iridescence = saturate( material.iridescence );
+ }
+ if ( material.iridescence > 0.0 ) {
+ material.iridescenceFresnel = evalIridescence( 1.0, material.iridescenceIOR, dotNVi, material.iridescenceThickness, material.specularColor );
+ material.iridescenceF0 = Schlick_to_F0( material.iridescenceFresnel, 1.0, dotNVi );
+ }
+#endif
+IncidentLight directLight;
+#if ( NUM_POINT_LIGHTS > 0 ) && defined( RE_Direct )
+ PointLight pointLight;
+ #if defined( USE_SHADOWMAP ) && NUM_POINT_LIGHT_SHADOWS > 0
+ PointLightShadow pointLightShadow;
+ #endif
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_POINT_LIGHTS; i ++ ) {
+ pointLight = pointLights[ i ];
+ getPointLightInfo( pointLight, geometryPosition, directLight );
+ #if defined( USE_SHADOWMAP ) && ( UNROLLED_LOOP_INDEX < NUM_POINT_LIGHT_SHADOWS )
+ pointLightShadow = pointLightShadows[ i ];
+ directLight.color *= ( directLight.visible && receiveShadow ) ? getPointShadow( pointShadowMap[ i ], pointLightShadow.shadowMapSize, pointLightShadow.shadowBias, pointLightShadow.shadowRadius, vPointShadowCoord[ i ], pointLightShadow.shadowCameraNear, pointLightShadow.shadowCameraFar ) : 1.0;
+ #endif
+ RE_Direct( directLight, geometryPosition, geometryNormal, geometryViewDir, geometryClearcoatNormal, material, reflectedLight );
+ }
+ #pragma unroll_loop_end
+#endif
+#if ( NUM_SPOT_LIGHTS > 0 ) && defined( RE_Direct )
+ SpotLight spotLight;
+ vec4 spotColor;
+ vec3 spotLightCoord;
+ bool inSpotLightMap;
+ #if defined( USE_SHADOWMAP ) && NUM_SPOT_LIGHT_SHADOWS > 0
+ SpotLightShadow spotLightShadow;
+ #endif
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_SPOT_LIGHTS; i ++ ) {
+ spotLight = spotLights[ i ];
+ getSpotLightInfo( spotLight, geometryPosition, directLight );
+ #if ( UNROLLED_LOOP_INDEX < NUM_SPOT_LIGHT_SHADOWS_WITH_MAPS )
+ #define SPOT_LIGHT_MAP_INDEX UNROLLED_LOOP_INDEX
+ #elif ( UNROLLED_LOOP_INDEX < NUM_SPOT_LIGHT_SHADOWS )
+ #define SPOT_LIGHT_MAP_INDEX NUM_SPOT_LIGHT_MAPS
+ #else
+ #define SPOT_LIGHT_MAP_INDEX ( UNROLLED_LOOP_INDEX - NUM_SPOT_LIGHT_SHADOWS + NUM_SPOT_LIGHT_SHADOWS_WITH_MAPS )
+ #endif
+ #if ( SPOT_LIGHT_MAP_INDEX < NUM_SPOT_LIGHT_MAPS )
+ spotLightCoord = vSpotLightCoord[ i ].xyz / vSpotLightCoord[ i ].w;
+ inSpotLightMap = all( lessThan( abs( spotLightCoord * 2. - 1. ), vec3( 1.0 ) ) );
+ spotColor = texture2D( spotLightMap[ SPOT_LIGHT_MAP_INDEX ], spotLightCoord.xy );
+ directLight.color = inSpotLightMap ? directLight.color * spotColor.rgb : directLight.color;
+ #endif
+ #undef SPOT_LIGHT_MAP_INDEX
+ #if defined( USE_SHADOWMAP ) && ( UNROLLED_LOOP_INDEX < NUM_SPOT_LIGHT_SHADOWS )
+ spotLightShadow = spotLightShadows[ i ];
+ directLight.color *= ( directLight.visible && receiveShadow ) ? getShadow( spotShadowMap[ i ], spotLightShadow.shadowMapSize, spotLightShadow.shadowBias, spotLightShadow.shadowRadius, vSpotLightCoord[ i ] ) : 1.0;
+ #endif
+ RE_Direct( directLight, geometryPosition, geometryNormal, geometryViewDir, geometryClearcoatNormal, material, reflectedLight );
+ }
+ #pragma unroll_loop_end
+#endif
+#if ( NUM_DIR_LIGHTS > 0 ) && defined( RE_Direct )
+ DirectionalLight directionalLight;
+ #if defined( USE_SHADOWMAP ) && NUM_DIR_LIGHT_SHADOWS > 0
+ DirectionalLightShadow directionalLightShadow;
+ #endif
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_DIR_LIGHTS; i ++ ) {
+ directionalLight = directionalLights[ i ];
+ getDirectionalLightInfo( directionalLight, directLight );
+ #if defined( USE_SHADOWMAP ) && ( UNROLLED_LOOP_INDEX < NUM_DIR_LIGHT_SHADOWS )
+ directionalLightShadow = directionalLightShadows[ i ];
+ directLight.color *= ( directLight.visible && receiveShadow ) ? getShadow( directionalShadowMap[ i ], directionalLightShadow.shadowMapSize, directionalLightShadow.shadowBias, directionalLightShadow.shadowRadius, vDirectionalShadowCoord[ i ] ) : 1.0;
+ #endif
+ RE_Direct( directLight, geometryPosition, geometryNormal, geometryViewDir, geometryClearcoatNormal, material, reflectedLight );
+ }
+ #pragma unroll_loop_end
+#endif
+#if ( NUM_RECT_AREA_LIGHTS > 0 ) && defined( RE_Direct_RectArea )
+ RectAreaLight rectAreaLight;
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_RECT_AREA_LIGHTS; i ++ ) {
+ rectAreaLight = rectAreaLights[ i ];
+ RE_Direct_RectArea( rectAreaLight, geometryPosition, geometryNormal, geometryViewDir, geometryClearcoatNormal, material, reflectedLight );
+ }
+ #pragma unroll_loop_end
+#endif
+#if defined( RE_IndirectDiffuse )
+ vec3 iblIrradiance = vec3( 0.0 );
+ vec3 irradiance = getAmbientLightIrradiance( ambientLightColor );
+ #if defined( USE_LIGHT_PROBES )
+ irradiance += getLightProbeIrradiance( lightProbe, geometryNormal );
+ #endif
+ #if ( NUM_HEMI_LIGHTS > 0 )
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_HEMI_LIGHTS; i ++ ) {
+ irradiance += getHemisphereLightIrradiance( hemisphereLights[ i ], geometryNormal );
+ }
+ #pragma unroll_loop_end
+ #endif
+#endif
+#if defined( RE_IndirectSpecular )
+ vec3 radiance = vec3( 0.0 );
+ vec3 clearcoatRadiance = vec3( 0.0 );
+#endif`,Ipe=`#if defined( RE_IndirectDiffuse )
+ #ifdef USE_LIGHTMAP
+ vec4 lightMapTexel = texture2D( lightMap, vLightMapUv );
+ vec3 lightMapIrradiance = lightMapTexel.rgb * lightMapIntensity;
+ irradiance += lightMapIrradiance;
+ #endif
+ #if defined( USE_ENVMAP ) && defined( STANDARD ) && defined( ENVMAP_TYPE_CUBE_UV )
+ iblIrradiance += getIBLIrradiance( geometryNormal );
+ #endif
+#endif
+#if defined( USE_ENVMAP ) && defined( RE_IndirectSpecular )
+ #ifdef USE_ANISOTROPY
+ radiance += getIBLAnisotropyRadiance( geometryViewDir, geometryNormal, material.roughness, material.anisotropyB, material.anisotropy );
+ #else
+ radiance += getIBLRadiance( geometryViewDir, geometryNormal, material.roughness );
+ #endif
+ #ifdef USE_CLEARCOAT
+ clearcoatRadiance += getIBLRadiance( geometryViewDir, geometryClearcoatNormal, material.clearcoatRoughness );
+ #endif
+#endif`,Lpe=`#if defined( RE_IndirectDiffuse )
+ RE_IndirectDiffuse( irradiance, geometryPosition, geometryNormal, geometryViewDir, geometryClearcoatNormal, material, reflectedLight );
+#endif
+#if defined( RE_IndirectSpecular )
+ RE_IndirectSpecular( radiance, iblIrradiance, clearcoatRadiance, geometryPosition, geometryNormal, geometryViewDir, geometryClearcoatNormal, material, reflectedLight );
+#endif`,kpe=`#if defined( USE_LOGDEPTHBUF )
+ gl_FragDepth = vIsPerspective == 0.0 ? gl_FragCoord.z : log2( vFragDepth ) * logDepthBufFC * 0.5;
+#endif`,Ope=`#if defined( USE_LOGDEPTHBUF )
+ uniform float logDepthBufFC;
+ varying float vFragDepth;
+ varying float vIsPerspective;
+#endif`,Npe=`#ifdef USE_LOGDEPTHBUF
+ varying float vFragDepth;
+ varying float vIsPerspective;
+#endif`,Dpe=`#ifdef USE_LOGDEPTHBUF
+ vFragDepth = 1.0 + gl_Position.w;
+ vIsPerspective = float( isPerspectiveMatrix( projectionMatrix ) );
+#endif`,Fpe=`#ifdef USE_MAP
+ vec4 sampledDiffuseColor = texture2D( map, vMapUv );
+ #ifdef DECODE_VIDEO_TEXTURE
+ sampledDiffuseColor = vec4( mix( pow( sampledDiffuseColor.rgb * 0.9478672986 + vec3( 0.0521327014 ), vec3( 2.4 ) ), sampledDiffuseColor.rgb * 0.0773993808, vec3( lessThanEqual( sampledDiffuseColor.rgb, vec3( 0.04045 ) ) ) ), sampledDiffuseColor.w );
+
+ #endif
+ diffuseColor *= sampledDiffuseColor;
+#endif`,Upe=`#ifdef USE_MAP
+ uniform sampler2D map;
+#endif`,zpe=`#if defined( USE_MAP ) || defined( USE_ALPHAMAP )
+ #if defined( USE_POINTS_UV )
+ vec2 uv = vUv;
+ #else
+ vec2 uv = ( uvTransform * vec3( gl_PointCoord.x, 1.0 - gl_PointCoord.y, 1 ) ).xy;
+ #endif
+#endif
+#ifdef USE_MAP
+ diffuseColor *= texture2D( map, uv );
+#endif
+#ifdef USE_ALPHAMAP
+ diffuseColor.a *= texture2D( alphaMap, uv ).g;
+#endif`,Bpe=`#if defined( USE_POINTS_UV )
+ varying vec2 vUv;
+#else
+ #if defined( USE_MAP ) || defined( USE_ALPHAMAP )
+ uniform mat3 uvTransform;
+ #endif
+#endif
+#ifdef USE_MAP
+ uniform sampler2D map;
+#endif
+#ifdef USE_ALPHAMAP
+ uniform sampler2D alphaMap;
+#endif`,Hpe=`float metalnessFactor = metalness;
+#ifdef USE_METALNESSMAP
+ vec4 texelMetalness = texture2D( metalnessMap, vMetalnessMapUv );
+ metalnessFactor *= texelMetalness.b;
+#endif`,$pe=`#ifdef USE_METALNESSMAP
+ uniform sampler2D metalnessMap;
+#endif`,Vpe=`#ifdef USE_INSTANCING_MORPH
+ float morphTargetInfluences[MORPHTARGETS_COUNT];
+ float morphTargetBaseInfluence = texelFetch( morphTexture, ivec2( 0, gl_InstanceID ), 0 ).r;
+ for ( int i = 0; i < MORPHTARGETS_COUNT; i ++ ) {
+ morphTargetInfluences[i] = texelFetch( morphTexture, ivec2( i + 1, gl_InstanceID ), 0 ).r;
+ }
+#endif`,Wpe=`#if defined( USE_MORPHCOLORS ) && defined( MORPHTARGETS_TEXTURE )
+ vColor *= morphTargetBaseInfluence;
+ for ( int i = 0; i < MORPHTARGETS_COUNT; i ++ ) {
+ #if defined( USE_COLOR_ALPHA )
+ if ( morphTargetInfluences[ i ] != 0.0 ) vColor += getMorph( gl_VertexID, i, 2 ) * morphTargetInfluences[ i ];
+ #elif defined( USE_COLOR )
+ if ( morphTargetInfluences[ i ] != 0.0 ) vColor += getMorph( gl_VertexID, i, 2 ).rgb * morphTargetInfluences[ i ];
+ #endif
+ }
+#endif`,jpe=`#ifdef USE_MORPHNORMALS
+ objectNormal *= morphTargetBaseInfluence;
+ #ifdef MORPHTARGETS_TEXTURE
+ for ( int i = 0; i < MORPHTARGETS_COUNT; i ++ ) {
+ if ( morphTargetInfluences[ i ] != 0.0 ) objectNormal += getMorph( gl_VertexID, i, 1 ).xyz * morphTargetInfluences[ i ];
+ }
+ #else
+ objectNormal += morphNormal0 * morphTargetInfluences[ 0 ];
+ objectNormal += morphNormal1 * morphTargetInfluences[ 1 ];
+ objectNormal += morphNormal2 * morphTargetInfluences[ 2 ];
+ objectNormal += morphNormal3 * morphTargetInfluences[ 3 ];
+ #endif
+#endif`,Gpe=`#ifdef USE_MORPHTARGETS
+ #ifndef USE_INSTANCING_MORPH
+ uniform float morphTargetBaseInfluence;
+ #endif
+ #ifdef MORPHTARGETS_TEXTURE
+ #ifndef USE_INSTANCING_MORPH
+ uniform float morphTargetInfluences[ MORPHTARGETS_COUNT ];
+ #endif
+ uniform sampler2DArray morphTargetsTexture;
+ uniform ivec2 morphTargetsTextureSize;
+ vec4 getMorph( const in int vertexIndex, const in int morphTargetIndex, const in int offset ) {
+ int texelIndex = vertexIndex * MORPHTARGETS_TEXTURE_STRIDE + offset;
+ int y = texelIndex / morphTargetsTextureSize.x;
+ int x = texelIndex - y * morphTargetsTextureSize.x;
+ ivec3 morphUV = ivec3( x, y, morphTargetIndex );
+ return texelFetch( morphTargetsTexture, morphUV, 0 );
+ }
+ #else
+ #ifndef USE_MORPHNORMALS
+ uniform float morphTargetInfluences[ 8 ];
+ #else
+ uniform float morphTargetInfluences[ 4 ];
+ #endif
+ #endif
+#endif`,Xpe=`#ifdef USE_MORPHTARGETS
+ transformed *= morphTargetBaseInfluence;
+ #ifdef MORPHTARGETS_TEXTURE
+ for ( int i = 0; i < MORPHTARGETS_COUNT; i ++ ) {
+ if ( morphTargetInfluences[ i ] != 0.0 ) transformed += getMorph( gl_VertexID, i, 0 ).xyz * morphTargetInfluences[ i ];
+ }
+ #else
+ transformed += morphTarget0 * morphTargetInfluences[ 0 ];
+ transformed += morphTarget1 * morphTargetInfluences[ 1 ];
+ transformed += morphTarget2 * morphTargetInfluences[ 2 ];
+ transformed += morphTarget3 * morphTargetInfluences[ 3 ];
+ #ifndef USE_MORPHNORMALS
+ transformed += morphTarget4 * morphTargetInfluences[ 4 ];
+ transformed += morphTarget5 * morphTargetInfluences[ 5 ];
+ transformed += morphTarget6 * morphTargetInfluences[ 6 ];
+ transformed += morphTarget7 * morphTargetInfluences[ 7 ];
+ #endif
+ #endif
+#endif`,qpe=`float faceDirection = gl_FrontFacing ? 1.0 : - 1.0;
+#ifdef FLAT_SHADED
+ vec3 fdx = dFdx( vViewPosition );
+ vec3 fdy = dFdy( vViewPosition );
+ vec3 normal = normalize( cross( fdx, fdy ) );
+#else
+ vec3 normal = normalize( vNormal );
+ #ifdef DOUBLE_SIDED
+ normal *= faceDirection;
+ #endif
+#endif
+#if defined( USE_NORMALMAP_TANGENTSPACE ) || defined( USE_CLEARCOAT_NORMALMAP ) || defined( USE_ANISOTROPY )
+ #ifdef USE_TANGENT
+ mat3 tbn = mat3( normalize( vTangent ), normalize( vBitangent ), normal );
+ #else
+ mat3 tbn = getTangentFrame( - vViewPosition, normal,
+ #if defined( USE_NORMALMAP )
+ vNormalMapUv
+ #elif defined( USE_CLEARCOAT_NORMALMAP )
+ vClearcoatNormalMapUv
+ #else
+ vUv
+ #endif
+ );
+ #endif
+ #if defined( DOUBLE_SIDED ) && ! defined( FLAT_SHADED )
+ tbn[0] *= faceDirection;
+ tbn[1] *= faceDirection;
+ #endif
+#endif
+#ifdef USE_CLEARCOAT_NORMALMAP
+ #ifdef USE_TANGENT
+ mat3 tbn2 = mat3( normalize( vTangent ), normalize( vBitangent ), normal );
+ #else
+ mat3 tbn2 = getTangentFrame( - vViewPosition, normal, vClearcoatNormalMapUv );
+ #endif
+ #if defined( DOUBLE_SIDED ) && ! defined( FLAT_SHADED )
+ tbn2[0] *= faceDirection;
+ tbn2[1] *= faceDirection;
+ #endif
+#endif
+vec3 nonPerturbedNormal = normal;`,Zpe=`#ifdef USE_NORMALMAP_OBJECTSPACE
+ normal = texture2D( normalMap, vNormalMapUv ).xyz * 2.0 - 1.0;
+ #ifdef FLIP_SIDED
+ normal = - normal;
+ #endif
+ #ifdef DOUBLE_SIDED
+ normal = normal * faceDirection;
+ #endif
+ normal = normalize( normalMatrix * normal );
+#elif defined( USE_NORMALMAP_TANGENTSPACE )
+ vec3 mapN = texture2D( normalMap, vNormalMapUv ).xyz * 2.0 - 1.0;
+ mapN.xy *= normalScale;
+ normal = normalize( tbn * mapN );
+#elif defined( USE_BUMPMAP )
+ normal = perturbNormalArb( - vViewPosition, normal, dHdxy_fwd(), faceDirection );
+#endif`,Ype=`#ifndef FLAT_SHADED
+ varying vec3 vNormal;
+ #ifdef USE_TANGENT
+ varying vec3 vTangent;
+ varying vec3 vBitangent;
+ #endif
+#endif`,Kpe=`#ifndef FLAT_SHADED
+ varying vec3 vNormal;
+ #ifdef USE_TANGENT
+ varying vec3 vTangent;
+ varying vec3 vBitangent;
+ #endif
+#endif`,Qpe=`#ifndef FLAT_SHADED
+ vNormal = normalize( transformedNormal );
+ #ifdef USE_TANGENT
+ vTangent = normalize( transformedTangent );
+ vBitangent = normalize( cross( vNormal, vTangent ) * tangent.w );
+ #endif
+#endif`,Jpe=`#ifdef USE_NORMALMAP
+ uniform sampler2D normalMap;
+ uniform vec2 normalScale;
+#endif
+#ifdef USE_NORMALMAP_OBJECTSPACE
+ uniform mat3 normalMatrix;
+#endif
+#if ! defined ( USE_TANGENT ) && ( defined ( USE_NORMALMAP_TANGENTSPACE ) || defined ( USE_CLEARCOAT_NORMALMAP ) || defined( USE_ANISOTROPY ) )
+ mat3 getTangentFrame( vec3 eye_pos, vec3 surf_norm, vec2 uv ) {
+ vec3 q0 = dFdx( eye_pos.xyz );
+ vec3 q1 = dFdy( eye_pos.xyz );
+ vec2 st0 = dFdx( uv.st );
+ vec2 st1 = dFdy( uv.st );
+ vec3 N = surf_norm;
+ vec3 q1perp = cross( q1, N );
+ vec3 q0perp = cross( N, q0 );
+ vec3 T = q1perp * st0.x + q0perp * st1.x;
+ vec3 B = q1perp * st0.y + q0perp * st1.y;
+ float det = max( dot( T, T ), dot( B, B ) );
+ float scale = ( det == 0.0 ) ? 0.0 : inversesqrt( det );
+ return mat3( T * scale, B * scale, N );
+ }
+#endif`,eme=`#ifdef USE_CLEARCOAT
+ vec3 clearcoatNormal = nonPerturbedNormal;
+#endif`,tme=`#ifdef USE_CLEARCOAT_NORMALMAP
+ vec3 clearcoatMapN = texture2D( clearcoatNormalMap, vClearcoatNormalMapUv ).xyz * 2.0 - 1.0;
+ clearcoatMapN.xy *= clearcoatNormalScale;
+ clearcoatNormal = normalize( tbn2 * clearcoatMapN );
+#endif`,nme=`#ifdef USE_CLEARCOATMAP
+ uniform sampler2D clearcoatMap;
+#endif
+#ifdef USE_CLEARCOAT_NORMALMAP
+ uniform sampler2D clearcoatNormalMap;
+ uniform vec2 clearcoatNormalScale;
+#endif
+#ifdef USE_CLEARCOAT_ROUGHNESSMAP
+ uniform sampler2D clearcoatRoughnessMap;
+#endif`,rme=`#ifdef USE_IRIDESCENCEMAP
+ uniform sampler2D iridescenceMap;
+#endif
+#ifdef USE_IRIDESCENCE_THICKNESSMAP
+ uniform sampler2D iridescenceThicknessMap;
+#endif`,ime=`#ifdef OPAQUE
+diffuseColor.a = 1.0;
+#endif
+#ifdef USE_TRANSMISSION
+diffuseColor.a *= material.transmissionAlpha;
+#endif
+gl_FragColor = vec4( outgoingLight, diffuseColor.a );`,sme=`vec3 packNormalToRGB( const in vec3 normal ) {
+ return normalize( normal ) * 0.5 + 0.5;
+}
+vec3 unpackRGBToNormal( const in vec3 rgb ) {
+ return 2.0 * rgb.xyz - 1.0;
+}
+const float PackUpscale = 256. / 255.;const float UnpackDownscale = 255. / 256.;
+const vec3 PackFactors = vec3( 256. * 256. * 256., 256. * 256., 256. );
+const vec4 UnpackFactors = UnpackDownscale / vec4( PackFactors, 1. );
+const float ShiftRight8 = 1. / 256.;
+vec4 packDepthToRGBA( const in float v ) {
+ vec4 r = vec4( fract( v * PackFactors ), v );
+ r.yzw -= r.xyz * ShiftRight8; return r * PackUpscale;
+}
+float unpackRGBAToDepth( const in vec4 v ) {
+ return dot( v, UnpackFactors );
+}
+vec2 packDepthToRG( in highp float v ) {
+ return packDepthToRGBA( v ).yx;
+}
+float unpackRGToDepth( const in highp vec2 v ) {
+ return unpackRGBAToDepth( vec4( v.xy, 0.0, 0.0 ) );
+}
+vec4 pack2HalfToRGBA( vec2 v ) {
+ vec4 r = vec4( v.x, fract( v.x * 255.0 ), v.y, fract( v.y * 255.0 ) );
+ return vec4( r.x - r.y / 255.0, r.y, r.z - r.w / 255.0, r.w );
+}
+vec2 unpackRGBATo2Half( vec4 v ) {
+ return vec2( v.x + ( v.y / 255.0 ), v.z + ( v.w / 255.0 ) );
+}
+float viewZToOrthographicDepth( const in float viewZ, const in float near, const in float far ) {
+ return ( viewZ + near ) / ( near - far );
+}
+float orthographicDepthToViewZ( const in float depth, const in float near, const in float far ) {
+ return depth * ( near - far ) - near;
+}
+float viewZToPerspectiveDepth( const in float viewZ, const in float near, const in float far ) {
+ return ( ( near + viewZ ) * far ) / ( ( far - near ) * viewZ );
+}
+float perspectiveDepthToViewZ( const in float depth, const in float near, const in float far ) {
+ return ( near * far ) / ( ( far - near ) * depth - far );
+}`,ome=`#ifdef PREMULTIPLIED_ALPHA
+ gl_FragColor.rgb *= gl_FragColor.a;
+#endif`,ame=`vec4 mvPosition = vec4( transformed, 1.0 );
+#ifdef USE_BATCHING
+ mvPosition = batchingMatrix * mvPosition;
+#endif
+#ifdef USE_INSTANCING
+ mvPosition = instanceMatrix * mvPosition;
+#endif
+mvPosition = modelViewMatrix * mvPosition;
+gl_Position = projectionMatrix * mvPosition;`,lme=`#ifdef DITHERING
+ gl_FragColor.rgb = dithering( gl_FragColor.rgb );
+#endif`,cme=`#ifdef DITHERING
+ vec3 dithering( vec3 color ) {
+ float grid_position = rand( gl_FragCoord.xy );
+ vec3 dither_shift_RGB = vec3( 0.25 / 255.0, -0.25 / 255.0, 0.25 / 255.0 );
+ dither_shift_RGB = mix( 2.0 * dither_shift_RGB, -2.0 * dither_shift_RGB, grid_position );
+ return color + dither_shift_RGB;
+ }
+#endif`,ume=`float roughnessFactor = roughness;
+#ifdef USE_ROUGHNESSMAP
+ vec4 texelRoughness = texture2D( roughnessMap, vRoughnessMapUv );
+ roughnessFactor *= texelRoughness.g;
+#endif`,dme=`#ifdef USE_ROUGHNESSMAP
+ uniform sampler2D roughnessMap;
+#endif`,fme=`#if NUM_SPOT_LIGHT_COORDS > 0
+ varying vec4 vSpotLightCoord[ NUM_SPOT_LIGHT_COORDS ];
+#endif
+#if NUM_SPOT_LIGHT_MAPS > 0
+ uniform sampler2D spotLightMap[ NUM_SPOT_LIGHT_MAPS ];
+#endif
+#ifdef USE_SHADOWMAP
+ #if NUM_DIR_LIGHT_SHADOWS > 0
+ uniform sampler2D directionalShadowMap[ NUM_DIR_LIGHT_SHADOWS ];
+ varying vec4 vDirectionalShadowCoord[ NUM_DIR_LIGHT_SHADOWS ];
+ struct DirectionalLightShadow {
+ float shadowBias;
+ float shadowNormalBias;
+ float shadowRadius;
+ vec2 shadowMapSize;
+ };
+ uniform DirectionalLightShadow directionalLightShadows[ NUM_DIR_LIGHT_SHADOWS ];
+ #endif
+ #if NUM_SPOT_LIGHT_SHADOWS > 0
+ uniform sampler2D spotShadowMap[ NUM_SPOT_LIGHT_SHADOWS ];
+ struct SpotLightShadow {
+ float shadowBias;
+ float shadowNormalBias;
+ float shadowRadius;
+ vec2 shadowMapSize;
+ };
+ uniform SpotLightShadow spotLightShadows[ NUM_SPOT_LIGHT_SHADOWS ];
+ #endif
+ #if NUM_POINT_LIGHT_SHADOWS > 0
+ uniform sampler2D pointShadowMap[ NUM_POINT_LIGHT_SHADOWS ];
+ varying vec4 vPointShadowCoord[ NUM_POINT_LIGHT_SHADOWS ];
+ struct PointLightShadow {
+ float shadowBias;
+ float shadowNormalBias;
+ float shadowRadius;
+ vec2 shadowMapSize;
+ float shadowCameraNear;
+ float shadowCameraFar;
+ };
+ uniform PointLightShadow pointLightShadows[ NUM_POINT_LIGHT_SHADOWS ];
+ #endif
+ float texture2DCompare( sampler2D depths, vec2 uv, float compare ) {
+ return step( compare, unpackRGBAToDepth( texture2D( depths, uv ) ) );
+ }
+ vec2 texture2DDistribution( sampler2D shadow, vec2 uv ) {
+ return unpackRGBATo2Half( texture2D( shadow, uv ) );
+ }
+ float VSMShadow (sampler2D shadow, vec2 uv, float compare ){
+ float occlusion = 1.0;
+ vec2 distribution = texture2DDistribution( shadow, uv );
+ float hard_shadow = step( compare , distribution.x );
+ if (hard_shadow != 1.0 ) {
+ float distance = compare - distribution.x ;
+ float variance = max( 0.00000, distribution.y * distribution.y );
+ float softness_probability = variance / (variance + distance * distance ); softness_probability = clamp( ( softness_probability - 0.3 ) / ( 0.95 - 0.3 ), 0.0, 1.0 ); occlusion = clamp( max( hard_shadow, softness_probability ), 0.0, 1.0 );
+ }
+ return occlusion;
+ }
+ float getShadow( sampler2D shadowMap, vec2 shadowMapSize, float shadowBias, float shadowRadius, vec4 shadowCoord ) {
+ float shadow = 1.0;
+ shadowCoord.xyz /= shadowCoord.w;
+ shadowCoord.z += shadowBias;
+ bool inFrustum = shadowCoord.x >= 0.0 && shadowCoord.x <= 1.0 && shadowCoord.y >= 0.0 && shadowCoord.y <= 1.0;
+ bool frustumTest = inFrustum && shadowCoord.z <= 1.0;
+ if ( frustumTest ) {
+ #if defined( SHADOWMAP_TYPE_PCF )
+ vec2 texelSize = vec2( 1.0 ) / shadowMapSize;
+ float dx0 = - texelSize.x * shadowRadius;
+ float dy0 = - texelSize.y * shadowRadius;
+ float dx1 = + texelSize.x * shadowRadius;
+ float dy1 = + texelSize.y * shadowRadius;
+ float dx2 = dx0 / 2.0;
+ float dy2 = dy0 / 2.0;
+ float dx3 = dx1 / 2.0;
+ float dy3 = dy1 / 2.0;
+ shadow = (
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, dy0 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy0 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, dy0 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx2, dy2 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy2 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx3, dy2 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, 0.0 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx2, 0.0 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy, shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx3, 0.0 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, 0.0 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx2, dy3 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy3 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx3, dy3 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, dy1 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy1 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, dy1 ), shadowCoord.z )
+ ) * ( 1.0 / 17.0 );
+ #elif defined( SHADOWMAP_TYPE_PCF_SOFT )
+ vec2 texelSize = vec2( 1.0 ) / shadowMapSize;
+ float dx = texelSize.x;
+ float dy = texelSize.y;
+ vec2 uv = shadowCoord.xy;
+ vec2 f = fract( uv * shadowMapSize + 0.5 );
+ uv -= f * texelSize;
+ shadow = (
+ texture2DCompare( shadowMap, uv, shadowCoord.z ) +
+ texture2DCompare( shadowMap, uv + vec2( dx, 0.0 ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, uv + vec2( 0.0, dy ), shadowCoord.z ) +
+ texture2DCompare( shadowMap, uv + texelSize, shadowCoord.z ) +
+ mix( texture2DCompare( shadowMap, uv + vec2( -dx, 0.0 ), shadowCoord.z ),
+ texture2DCompare( shadowMap, uv + vec2( 2.0 * dx, 0.0 ), shadowCoord.z ),
+ f.x ) +
+ mix( texture2DCompare( shadowMap, uv + vec2( -dx, dy ), shadowCoord.z ),
+ texture2DCompare( shadowMap, uv + vec2( 2.0 * dx, dy ), shadowCoord.z ),
+ f.x ) +
+ mix( texture2DCompare( shadowMap, uv + vec2( 0.0, -dy ), shadowCoord.z ),
+ texture2DCompare( shadowMap, uv + vec2( 0.0, 2.0 * dy ), shadowCoord.z ),
+ f.y ) +
+ mix( texture2DCompare( shadowMap, uv + vec2( dx, -dy ), shadowCoord.z ),
+ texture2DCompare( shadowMap, uv + vec2( dx, 2.0 * dy ), shadowCoord.z ),
+ f.y ) +
+ mix( mix( texture2DCompare( shadowMap, uv + vec2( -dx, -dy ), shadowCoord.z ),
+ texture2DCompare( shadowMap, uv + vec2( 2.0 * dx, -dy ), shadowCoord.z ),
+ f.x ),
+ mix( texture2DCompare( shadowMap, uv + vec2( -dx, 2.0 * dy ), shadowCoord.z ),
+ texture2DCompare( shadowMap, uv + vec2( 2.0 * dx, 2.0 * dy ), shadowCoord.z ),
+ f.x ),
+ f.y )
+ ) * ( 1.0 / 9.0 );
+ #elif defined( SHADOWMAP_TYPE_VSM )
+ shadow = VSMShadow( shadowMap, shadowCoord.xy, shadowCoord.z );
+ #else
+ shadow = texture2DCompare( shadowMap, shadowCoord.xy, shadowCoord.z );
+ #endif
+ }
+ return shadow;
+ }
+ vec2 cubeToUV( vec3 v, float texelSizeY ) {
+ vec3 absV = abs( v );
+ float scaleToCube = 1.0 / max( absV.x, max( absV.y, absV.z ) );
+ absV *= scaleToCube;
+ v *= scaleToCube * ( 1.0 - 2.0 * texelSizeY );
+ vec2 planar = v.xy;
+ float almostATexel = 1.5 * texelSizeY;
+ float almostOne = 1.0 - almostATexel;
+ if ( absV.z >= almostOne ) {
+ if ( v.z > 0.0 )
+ planar.x = 4.0 - v.x;
+ } else if ( absV.x >= almostOne ) {
+ float signX = sign( v.x );
+ planar.x = v.z * signX + 2.0 * signX;
+ } else if ( absV.y >= almostOne ) {
+ float signY = sign( v.y );
+ planar.x = v.x + 2.0 * signY + 2.0;
+ planar.y = v.z * signY - 2.0;
+ }
+ return vec2( 0.125, 0.25 ) * planar + vec2( 0.375, 0.75 );
+ }
+ float getPointShadow( sampler2D shadowMap, vec2 shadowMapSize, float shadowBias, float shadowRadius, vec4 shadowCoord, float shadowCameraNear, float shadowCameraFar ) {
+ float shadow = 1.0;
+ vec3 lightToPosition = shadowCoord.xyz;
+
+ float lightToPositionLength = length( lightToPosition );
+ if ( lightToPositionLength - shadowCameraFar <= 0.0 && lightToPositionLength - shadowCameraNear >= 0.0 ) {
+ float dp = ( lightToPositionLength - shadowCameraNear ) / ( shadowCameraFar - shadowCameraNear ); dp += shadowBias;
+ vec3 bd3D = normalize( lightToPosition );
+ vec2 texelSize = vec2( 1.0 ) / ( shadowMapSize * vec2( 4.0, 2.0 ) );
+ #if defined( SHADOWMAP_TYPE_PCF ) || defined( SHADOWMAP_TYPE_PCF_SOFT ) || defined( SHADOWMAP_TYPE_VSM )
+ vec2 offset = vec2( - 1, 1 ) * shadowRadius * texelSize.y;
+ shadow = (
+ texture2DCompare( shadowMap, cubeToUV( bd3D + offset.xyy, texelSize.y ), dp ) +
+ texture2DCompare( shadowMap, cubeToUV( bd3D + offset.yyy, texelSize.y ), dp ) +
+ texture2DCompare( shadowMap, cubeToUV( bd3D + offset.xyx, texelSize.y ), dp ) +
+ texture2DCompare( shadowMap, cubeToUV( bd3D + offset.yyx, texelSize.y ), dp ) +
+ texture2DCompare( shadowMap, cubeToUV( bd3D, texelSize.y ), dp ) +
+ texture2DCompare( shadowMap, cubeToUV( bd3D + offset.xxy, texelSize.y ), dp ) +
+ texture2DCompare( shadowMap, cubeToUV( bd3D + offset.yxy, texelSize.y ), dp ) +
+ texture2DCompare( shadowMap, cubeToUV( bd3D + offset.xxx, texelSize.y ), dp ) +
+ texture2DCompare( shadowMap, cubeToUV( bd3D + offset.yxx, texelSize.y ), dp )
+ ) * ( 1.0 / 9.0 );
+ #else
+ shadow = texture2DCompare( shadowMap, cubeToUV( bd3D, texelSize.y ), dp );
+ #endif
+ }
+ return shadow;
+ }
+#endif`,hme=`#if NUM_SPOT_LIGHT_COORDS > 0
+ uniform mat4 spotLightMatrix[ NUM_SPOT_LIGHT_COORDS ];
+ varying vec4 vSpotLightCoord[ NUM_SPOT_LIGHT_COORDS ];
+#endif
+#ifdef USE_SHADOWMAP
+ #if NUM_DIR_LIGHT_SHADOWS > 0
+ uniform mat4 directionalShadowMatrix[ NUM_DIR_LIGHT_SHADOWS ];
+ varying vec4 vDirectionalShadowCoord[ NUM_DIR_LIGHT_SHADOWS ];
+ struct DirectionalLightShadow {
+ float shadowBias;
+ float shadowNormalBias;
+ float shadowRadius;
+ vec2 shadowMapSize;
+ };
+ uniform DirectionalLightShadow directionalLightShadows[ NUM_DIR_LIGHT_SHADOWS ];
+ #endif
+ #if NUM_SPOT_LIGHT_SHADOWS > 0
+ struct SpotLightShadow {
+ float shadowBias;
+ float shadowNormalBias;
+ float shadowRadius;
+ vec2 shadowMapSize;
+ };
+ uniform SpotLightShadow spotLightShadows[ NUM_SPOT_LIGHT_SHADOWS ];
+ #endif
+ #if NUM_POINT_LIGHT_SHADOWS > 0
+ uniform mat4 pointShadowMatrix[ NUM_POINT_LIGHT_SHADOWS ];
+ varying vec4 vPointShadowCoord[ NUM_POINT_LIGHT_SHADOWS ];
+ struct PointLightShadow {
+ float shadowBias;
+ float shadowNormalBias;
+ float shadowRadius;
+ vec2 shadowMapSize;
+ float shadowCameraNear;
+ float shadowCameraFar;
+ };
+ uniform PointLightShadow pointLightShadows[ NUM_POINT_LIGHT_SHADOWS ];
+ #endif
+#endif`,pme=`#if ( defined( USE_SHADOWMAP ) && ( NUM_DIR_LIGHT_SHADOWS > 0 || NUM_POINT_LIGHT_SHADOWS > 0 ) ) || ( NUM_SPOT_LIGHT_COORDS > 0 )
+ vec3 shadowWorldNormal = inverseTransformDirection( transformedNormal, viewMatrix );
+ vec4 shadowWorldPosition;
+#endif
+#if defined( USE_SHADOWMAP )
+ #if NUM_DIR_LIGHT_SHADOWS > 0
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_DIR_LIGHT_SHADOWS; i ++ ) {
+ shadowWorldPosition = worldPosition + vec4( shadowWorldNormal * directionalLightShadows[ i ].shadowNormalBias, 0 );
+ vDirectionalShadowCoord[ i ] = directionalShadowMatrix[ i ] * shadowWorldPosition;
+ }
+ #pragma unroll_loop_end
+ #endif
+ #if NUM_POINT_LIGHT_SHADOWS > 0
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_POINT_LIGHT_SHADOWS; i ++ ) {
+ shadowWorldPosition = worldPosition + vec4( shadowWorldNormal * pointLightShadows[ i ].shadowNormalBias, 0 );
+ vPointShadowCoord[ i ] = pointShadowMatrix[ i ] * shadowWorldPosition;
+ }
+ #pragma unroll_loop_end
+ #endif
+#endif
+#if NUM_SPOT_LIGHT_COORDS > 0
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_SPOT_LIGHT_COORDS; i ++ ) {
+ shadowWorldPosition = worldPosition;
+ #if ( defined( USE_SHADOWMAP ) && UNROLLED_LOOP_INDEX < NUM_SPOT_LIGHT_SHADOWS )
+ shadowWorldPosition.xyz += shadowWorldNormal * spotLightShadows[ i ].shadowNormalBias;
+ #endif
+ vSpotLightCoord[ i ] = spotLightMatrix[ i ] * shadowWorldPosition;
+ }
+ #pragma unroll_loop_end
+#endif`,mme=`float getShadowMask() {
+ float shadow = 1.0;
+ #ifdef USE_SHADOWMAP
+ #if NUM_DIR_LIGHT_SHADOWS > 0
+ DirectionalLightShadow directionalLight;
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_DIR_LIGHT_SHADOWS; i ++ ) {
+ directionalLight = directionalLightShadows[ i ];
+ shadow *= receiveShadow ? getShadow( directionalShadowMap[ i ], directionalLight.shadowMapSize, directionalLight.shadowBias, directionalLight.shadowRadius, vDirectionalShadowCoord[ i ] ) : 1.0;
+ }
+ #pragma unroll_loop_end
+ #endif
+ #if NUM_SPOT_LIGHT_SHADOWS > 0
+ SpotLightShadow spotLight;
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_SPOT_LIGHT_SHADOWS; i ++ ) {
+ spotLight = spotLightShadows[ i ];
+ shadow *= receiveShadow ? getShadow( spotShadowMap[ i ], spotLight.shadowMapSize, spotLight.shadowBias, spotLight.shadowRadius, vSpotLightCoord[ i ] ) : 1.0;
+ }
+ #pragma unroll_loop_end
+ #endif
+ #if NUM_POINT_LIGHT_SHADOWS > 0
+ PointLightShadow pointLight;
+ #pragma unroll_loop_start
+ for ( int i = 0; i < NUM_POINT_LIGHT_SHADOWS; i ++ ) {
+ pointLight = pointLightShadows[ i ];
+ shadow *= receiveShadow ? getPointShadow( pointShadowMap[ i ], pointLight.shadowMapSize, pointLight.shadowBias, pointLight.shadowRadius, vPointShadowCoord[ i ], pointLight.shadowCameraNear, pointLight.shadowCameraFar ) : 1.0;
+ }
+ #pragma unroll_loop_end
+ #endif
+ #endif
+ return shadow;
+}`,gme=`#ifdef USE_SKINNING
+ mat4 boneMatX = getBoneMatrix( skinIndex.x );
+ mat4 boneMatY = getBoneMatrix( skinIndex.y );
+ mat4 boneMatZ = getBoneMatrix( skinIndex.z );
+ mat4 boneMatW = getBoneMatrix( skinIndex.w );
+#endif`,vme=`#ifdef USE_SKINNING
+ uniform mat4 bindMatrix;
+ uniform mat4 bindMatrixInverse;
+ uniform highp sampler2D boneTexture;
+ mat4 getBoneMatrix( const in float i ) {
+ int size = textureSize( boneTexture, 0 ).x;
+ int j = int( i ) * 4;
+ int x = j % size;
+ int y = j / size;
+ vec4 v1 = texelFetch( boneTexture, ivec2( x, y ), 0 );
+ vec4 v2 = texelFetch( boneTexture, ivec2( x + 1, y ), 0 );
+ vec4 v3 = texelFetch( boneTexture, ivec2( x + 2, y ), 0 );
+ vec4 v4 = texelFetch( boneTexture, ivec2( x + 3, y ), 0 );
+ return mat4( v1, v2, v3, v4 );
+ }
+#endif`,yme=`#ifdef USE_SKINNING
+ vec4 skinVertex = bindMatrix * vec4( transformed, 1.0 );
+ vec4 skinned = vec4( 0.0 );
+ skinned += boneMatX * skinVertex * skinWeight.x;
+ skinned += boneMatY * skinVertex * skinWeight.y;
+ skinned += boneMatZ * skinVertex * skinWeight.z;
+ skinned += boneMatW * skinVertex * skinWeight.w;
+ transformed = ( bindMatrixInverse * skinned ).xyz;
+#endif`,xme=`#ifdef USE_SKINNING
+ mat4 skinMatrix = mat4( 0.0 );
+ skinMatrix += skinWeight.x * boneMatX;
+ skinMatrix += skinWeight.y * boneMatY;
+ skinMatrix += skinWeight.z * boneMatZ;
+ skinMatrix += skinWeight.w * boneMatW;
+ skinMatrix = bindMatrixInverse * skinMatrix * bindMatrix;
+ objectNormal = vec4( skinMatrix * vec4( objectNormal, 0.0 ) ).xyz;
+ #ifdef USE_TANGENT
+ objectTangent = vec4( skinMatrix * vec4( objectTangent, 0.0 ) ).xyz;
+ #endif
+#endif`,_me=`float specularStrength;
+#ifdef USE_SPECULARMAP
+ vec4 texelSpecular = texture2D( specularMap, vSpecularMapUv );
+ specularStrength = texelSpecular.r;
+#else
+ specularStrength = 1.0;
+#endif`,bme=`#ifdef USE_SPECULARMAP
+ uniform sampler2D specularMap;
+#endif`,Sme=`#if defined( TONE_MAPPING )
+ gl_FragColor.rgb = toneMapping( gl_FragColor.rgb );
+#endif`,wme=`#ifndef saturate
+#define saturate( a ) clamp( a, 0.0, 1.0 )
+#endif
+uniform float toneMappingExposure;
+vec3 LinearToneMapping( vec3 color ) {
+ return saturate( toneMappingExposure * color );
+}
+vec3 ReinhardToneMapping( vec3 color ) {
+ color *= toneMappingExposure;
+ return saturate( color / ( vec3( 1.0 ) + color ) );
+}
+vec3 OptimizedCineonToneMapping( vec3 color ) {
+ color *= toneMappingExposure;
+ color = max( vec3( 0.0 ), color - 0.004 );
+ return pow( ( color * ( 6.2 * color + 0.5 ) ) / ( color * ( 6.2 * color + 1.7 ) + 0.06 ), vec3( 2.2 ) );
+}
+vec3 RRTAndODTFit( vec3 v ) {
+ vec3 a = v * ( v + 0.0245786 ) - 0.000090537;
+ vec3 b = v * ( 0.983729 * v + 0.4329510 ) + 0.238081;
+ return a / b;
+}
+vec3 ACESFilmicToneMapping( vec3 color ) {
+ const mat3 ACESInputMat = mat3(
+ vec3( 0.59719, 0.07600, 0.02840 ), vec3( 0.35458, 0.90834, 0.13383 ),
+ vec3( 0.04823, 0.01566, 0.83777 )
+ );
+ const mat3 ACESOutputMat = mat3(
+ vec3( 1.60475, -0.10208, -0.00327 ), vec3( -0.53108, 1.10813, -0.07276 ),
+ vec3( -0.07367, -0.00605, 1.07602 )
+ );
+ color *= toneMappingExposure / 0.6;
+ color = ACESInputMat * color;
+ color = RRTAndODTFit( color );
+ color = ACESOutputMat * color;
+ return saturate( color );
+}
+const mat3 LINEAR_REC2020_TO_LINEAR_SRGB = mat3(
+ vec3( 1.6605, - 0.1246, - 0.0182 ),
+ vec3( - 0.5876, 1.1329, - 0.1006 ),
+ vec3( - 0.0728, - 0.0083, 1.1187 )
+);
+const mat3 LINEAR_SRGB_TO_LINEAR_REC2020 = mat3(
+ vec3( 0.6274, 0.0691, 0.0164 ),
+ vec3( 0.3293, 0.9195, 0.0880 ),
+ vec3( 0.0433, 0.0113, 0.8956 )
+);
+vec3 agxDefaultContrastApprox( vec3 x ) {
+ vec3 x2 = x * x;
+ vec3 x4 = x2 * x2;
+ return + 15.5 * x4 * x2
+ - 40.14 * x4 * x
+ + 31.96 * x4
+ - 6.868 * x2 * x
+ + 0.4298 * x2
+ + 0.1191 * x
+ - 0.00232;
+}
+vec3 AgXToneMapping( vec3 color ) {
+ const mat3 AgXInsetMatrix = mat3(
+ vec3( 0.856627153315983, 0.137318972929847, 0.11189821299995 ),
+ vec3( 0.0951212405381588, 0.761241990602591, 0.0767994186031903 ),
+ vec3( 0.0482516061458583, 0.101439036467562, 0.811302368396859 )
+ );
+ const mat3 AgXOutsetMatrix = mat3(
+ vec3( 1.1271005818144368, - 0.1413297634984383, - 0.14132976349843826 ),
+ vec3( - 0.11060664309660323, 1.157823702216272, - 0.11060664309660294 ),
+ vec3( - 0.016493938717834573, - 0.016493938717834257, 1.2519364065950405 )
+ );
+ const float AgxMinEv = - 12.47393; const float AgxMaxEv = 4.026069;
+ color *= toneMappingExposure;
+ color = LINEAR_SRGB_TO_LINEAR_REC2020 * color;
+ color = AgXInsetMatrix * color;
+ color = max( color, 1e-10 ); color = log2( color );
+ color = ( color - AgxMinEv ) / ( AgxMaxEv - AgxMinEv );
+ color = clamp( color, 0.0, 1.0 );
+ color = agxDefaultContrastApprox( color );
+ color = AgXOutsetMatrix * color;
+ color = pow( max( vec3( 0.0 ), color ), vec3( 2.2 ) );
+ color = LINEAR_REC2020_TO_LINEAR_SRGB * color;
+ color = clamp( color, 0.0, 1.0 );
+ return color;
+}
+vec3 NeutralToneMapping( vec3 color ) {
+ const float StartCompression = 0.8 - 0.04;
+ const float Desaturation = 0.15;
+ color *= toneMappingExposure;
+ float x = min( color.r, min( color.g, color.b ) );
+ float offset = x < 0.08 ? x - 6.25 * x * x : 0.04;
+ color -= offset;
+ float peak = max( color.r, max( color.g, color.b ) );
+ if ( peak < StartCompression ) return color;
+ float d = 1. - StartCompression;
+ float newPeak = 1. - d * d / ( peak + d - StartCompression );
+ color *= newPeak / peak;
+ float g = 1. - 1. / ( Desaturation * ( peak - newPeak ) + 1. );
+ return mix( color, vec3( newPeak ), g );
+}
+vec3 CustomToneMapping( vec3 color ) { return color; }`,Mme=`#ifdef USE_TRANSMISSION
+ material.transmission = transmission;
+ material.transmissionAlpha = 1.0;
+ material.thickness = thickness;
+ material.attenuationDistance = attenuationDistance;
+ material.attenuationColor = attenuationColor;
+ #ifdef USE_TRANSMISSIONMAP
+ material.transmission *= texture2D( transmissionMap, vTransmissionMapUv ).r;
+ #endif
+ #ifdef USE_THICKNESSMAP
+ material.thickness *= texture2D( thicknessMap, vThicknessMapUv ).g;
+ #endif
+ vec3 pos = vWorldPosition;
+ vec3 v = normalize( cameraPosition - pos );
+ vec3 n = inverseTransformDirection( normal, viewMatrix );
+ vec4 transmitted = getIBLVolumeRefraction(
+ n, v, material.roughness, material.diffuseColor, material.specularColor, material.specularF90,
+ pos, modelMatrix, viewMatrix, projectionMatrix, material.dispersion, material.ior, material.thickness,
+ material.attenuationColor, material.attenuationDistance );
+ material.transmissionAlpha = mix( material.transmissionAlpha, transmitted.a, material.transmission );
+ totalDiffuse = mix( totalDiffuse, transmitted.rgb, material.transmission );
+#endif`,Eme=`#ifdef USE_TRANSMISSION
+ uniform float transmission;
+ uniform float thickness;
+ uniform float attenuationDistance;
+ uniform vec3 attenuationColor;
+ #ifdef USE_TRANSMISSIONMAP
+ uniform sampler2D transmissionMap;
+ #endif
+ #ifdef USE_THICKNESSMAP
+ uniform sampler2D thicknessMap;
+ #endif
+ uniform vec2 transmissionSamplerSize;
+ uniform sampler2D transmissionSamplerMap;
+ uniform mat4 modelMatrix;
+ uniform mat4 projectionMatrix;
+ varying vec3 vWorldPosition;
+ float w0( float a ) {
+ return ( 1.0 / 6.0 ) * ( a * ( a * ( - a + 3.0 ) - 3.0 ) + 1.0 );
+ }
+ float w1( float a ) {
+ return ( 1.0 / 6.0 ) * ( a * a * ( 3.0 * a - 6.0 ) + 4.0 );
+ }
+ float w2( float a ){
+ return ( 1.0 / 6.0 ) * ( a * ( a * ( - 3.0 * a + 3.0 ) + 3.0 ) + 1.0 );
+ }
+ float w3( float a ) {
+ return ( 1.0 / 6.0 ) * ( a * a * a );
+ }
+ float g0( float a ) {
+ return w0( a ) + w1( a );
+ }
+ float g1( float a ) {
+ return w2( a ) + w3( a );
+ }
+ float h0( float a ) {
+ return - 1.0 + w1( a ) / ( w0( a ) + w1( a ) );
+ }
+ float h1( float a ) {
+ return 1.0 + w3( a ) / ( w2( a ) + w3( a ) );
+ }
+ vec4 bicubic( sampler2D tex, vec2 uv, vec4 texelSize, float lod ) {
+ uv = uv * texelSize.zw + 0.5;
+ vec2 iuv = floor( uv );
+ vec2 fuv = fract( uv );
+ float g0x = g0( fuv.x );
+ float g1x = g1( fuv.x );
+ float h0x = h0( fuv.x );
+ float h1x = h1( fuv.x );
+ float h0y = h0( fuv.y );
+ float h1y = h1( fuv.y );
+ vec2 p0 = ( vec2( iuv.x + h0x, iuv.y + h0y ) - 0.5 ) * texelSize.xy;
+ vec2 p1 = ( vec2( iuv.x + h1x, iuv.y + h0y ) - 0.5 ) * texelSize.xy;
+ vec2 p2 = ( vec2( iuv.x + h0x, iuv.y + h1y ) - 0.5 ) * texelSize.xy;
+ vec2 p3 = ( vec2( iuv.x + h1x, iuv.y + h1y ) - 0.5 ) * texelSize.xy;
+ return g0( fuv.y ) * ( g0x * textureLod( tex, p0, lod ) + g1x * textureLod( tex, p1, lod ) ) +
+ g1( fuv.y ) * ( g0x * textureLod( tex, p2, lod ) + g1x * textureLod( tex, p3, lod ) );
+ }
+ vec4 textureBicubic( sampler2D sampler, vec2 uv, float lod ) {
+ vec2 fLodSize = vec2( textureSize( sampler, int( lod ) ) );
+ vec2 cLodSize = vec2( textureSize( sampler, int( lod + 1.0 ) ) );
+ vec2 fLodSizeInv = 1.0 / fLodSize;
+ vec2 cLodSizeInv = 1.0 / cLodSize;
+ vec4 fSample = bicubic( sampler, uv, vec4( fLodSizeInv, fLodSize ), floor( lod ) );
+ vec4 cSample = bicubic( sampler, uv, vec4( cLodSizeInv, cLodSize ), ceil( lod ) );
+ return mix( fSample, cSample, fract( lod ) );
+ }
+ vec3 getVolumeTransmissionRay( const in vec3 n, const in vec3 v, const in float thickness, const in float ior, const in mat4 modelMatrix ) {
+ vec3 refractionVector = refract( - v, normalize( n ), 1.0 / ior );
+ vec3 modelScale;
+ modelScale.x = length( vec3( modelMatrix[ 0 ].xyz ) );
+ modelScale.y = length( vec3( modelMatrix[ 1 ].xyz ) );
+ modelScale.z = length( vec3( modelMatrix[ 2 ].xyz ) );
+ return normalize( refractionVector ) * thickness * modelScale;
+ }
+ float applyIorToRoughness( const in float roughness, const in float ior ) {
+ return roughness * clamp( ior * 2.0 - 2.0, 0.0, 1.0 );
+ }
+ vec4 getTransmissionSample( const in vec2 fragCoord, const in float roughness, const in float ior ) {
+ float lod = log2( transmissionSamplerSize.x ) * applyIorToRoughness( roughness, ior );
+ return textureBicubic( transmissionSamplerMap, fragCoord.xy, lod );
+ }
+ vec3 volumeAttenuation( const in float transmissionDistance, const in vec3 attenuationColor, const in float attenuationDistance ) {
+ if ( isinf( attenuationDistance ) ) {
+ return vec3( 1.0 );
+ } else {
+ vec3 attenuationCoefficient = -log( attenuationColor ) / attenuationDistance;
+ vec3 transmittance = exp( - attenuationCoefficient * transmissionDistance ); return transmittance;
+ }
+ }
+ vec4 getIBLVolumeRefraction( const in vec3 n, const in vec3 v, const in float roughness, const in vec3 diffuseColor,
+ const in vec3 specularColor, const in float specularF90, const in vec3 position, const in mat4 modelMatrix,
+ const in mat4 viewMatrix, const in mat4 projMatrix, const in float dispersion, const in float ior, const in float thickness,
+ const in vec3 attenuationColor, const in float attenuationDistance ) {
+ vec4 transmittedLight;
+ vec3 transmittance;
+ #ifdef USE_DISPERSION
+ float halfSpread = ( ior - 1.0 ) * 0.025 * dispersion;
+ vec3 iors = vec3( ior - halfSpread, ior, ior + halfSpread );
+ for ( int i = 0; i < 3; i ++ ) {
+ vec3 transmissionRay = getVolumeTransmissionRay( n, v, thickness, iors[ i ], modelMatrix );
+ vec3 refractedRayExit = position + transmissionRay;
+
+ vec4 ndcPos = projMatrix * viewMatrix * vec4( refractedRayExit, 1.0 );
+ vec2 refractionCoords = ndcPos.xy / ndcPos.w;
+ refractionCoords += 1.0;
+ refractionCoords /= 2.0;
+
+ vec4 transmissionSample = getTransmissionSample( refractionCoords, roughness, iors[ i ] );
+ transmittedLight[ i ] = transmissionSample[ i ];
+ transmittedLight.a += transmissionSample.a;
+ transmittance[ i ] = diffuseColor[ i ] * volumeAttenuation( length( transmissionRay ), attenuationColor, attenuationDistance )[ i ];
+ }
+ transmittedLight.a /= 3.0;
+
+ #else
+
+ vec3 transmissionRay = getVolumeTransmissionRay( n, v, thickness, ior, modelMatrix );
+ vec3 refractedRayExit = position + transmissionRay;
+ vec4 ndcPos = projMatrix * viewMatrix * vec4( refractedRayExit, 1.0 );
+ vec2 refractionCoords = ndcPos.xy / ndcPos.w;
+ refractionCoords += 1.0;
+ refractionCoords /= 2.0;
+ transmittedLight = getTransmissionSample( refractionCoords, roughness, ior );
+ transmittance = diffuseColor * volumeAttenuation( length( transmissionRay ), attenuationColor, attenuationDistance );
+
+ #endif
+ vec3 attenuatedColor = transmittance * transmittedLight.rgb;
+ vec3 F = EnvironmentBRDF( n, v, specularColor, specularF90, roughness );
+ float transmittanceFactor = ( transmittance.r + transmittance.g + transmittance.b ) / 3.0;
+ return vec4( ( 1.0 - F ) * attenuatedColor, 1.0 - ( 1.0 - transmittedLight.a ) * transmittanceFactor );
+ }
+#endif`,Cme=`#if defined( USE_UV ) || defined( USE_ANISOTROPY )
+ varying vec2 vUv;
+#endif
+#ifdef USE_MAP
+ varying vec2 vMapUv;
+#endif
+#ifdef USE_ALPHAMAP
+ varying vec2 vAlphaMapUv;
+#endif
+#ifdef USE_LIGHTMAP
+ varying vec2 vLightMapUv;
+#endif
+#ifdef USE_AOMAP
+ varying vec2 vAoMapUv;
+#endif
+#ifdef USE_BUMPMAP
+ varying vec2 vBumpMapUv;
+#endif
+#ifdef USE_NORMALMAP
+ varying vec2 vNormalMapUv;
+#endif
+#ifdef USE_EMISSIVEMAP
+ varying vec2 vEmissiveMapUv;
+#endif
+#ifdef USE_METALNESSMAP
+ varying vec2 vMetalnessMapUv;
+#endif
+#ifdef USE_ROUGHNESSMAP
+ varying vec2 vRoughnessMapUv;
+#endif
+#ifdef USE_ANISOTROPYMAP
+ varying vec2 vAnisotropyMapUv;
+#endif
+#ifdef USE_CLEARCOATMAP
+ varying vec2 vClearcoatMapUv;
+#endif
+#ifdef USE_CLEARCOAT_NORMALMAP
+ varying vec2 vClearcoatNormalMapUv;
+#endif
+#ifdef USE_CLEARCOAT_ROUGHNESSMAP
+ varying vec2 vClearcoatRoughnessMapUv;
+#endif
+#ifdef USE_IRIDESCENCEMAP
+ varying vec2 vIridescenceMapUv;
+#endif
+#ifdef USE_IRIDESCENCE_THICKNESSMAP
+ varying vec2 vIridescenceThicknessMapUv;
+#endif
+#ifdef USE_SHEEN_COLORMAP
+ varying vec2 vSheenColorMapUv;
+#endif
+#ifdef USE_SHEEN_ROUGHNESSMAP
+ varying vec2 vSheenRoughnessMapUv;
+#endif
+#ifdef USE_SPECULARMAP
+ varying vec2 vSpecularMapUv;
+#endif
+#ifdef USE_SPECULAR_COLORMAP
+ varying vec2 vSpecularColorMapUv;
+#endif
+#ifdef USE_SPECULAR_INTENSITYMAP
+ varying vec2 vSpecularIntensityMapUv;
+#endif
+#ifdef USE_TRANSMISSIONMAP
+ uniform mat3 transmissionMapTransform;
+ varying vec2 vTransmissionMapUv;
+#endif
+#ifdef USE_THICKNESSMAP
+ uniform mat3 thicknessMapTransform;
+ varying vec2 vThicknessMapUv;
+#endif`,Tme=`#if defined( USE_UV ) || defined( USE_ANISOTROPY )
+ varying vec2 vUv;
+#endif
+#ifdef USE_MAP
+ uniform mat3 mapTransform;
+ varying vec2 vMapUv;
+#endif
+#ifdef USE_ALPHAMAP
+ uniform mat3 alphaMapTransform;
+ varying vec2 vAlphaMapUv;
+#endif
+#ifdef USE_LIGHTMAP
+ uniform mat3 lightMapTransform;
+ varying vec2 vLightMapUv;
+#endif
+#ifdef USE_AOMAP
+ uniform mat3 aoMapTransform;
+ varying vec2 vAoMapUv;
+#endif
+#ifdef USE_BUMPMAP
+ uniform mat3 bumpMapTransform;
+ varying vec2 vBumpMapUv;
+#endif
+#ifdef USE_NORMALMAP
+ uniform mat3 normalMapTransform;
+ varying vec2 vNormalMapUv;
+#endif
+#ifdef USE_DISPLACEMENTMAP
+ uniform mat3 displacementMapTransform;
+ varying vec2 vDisplacementMapUv;
+#endif
+#ifdef USE_EMISSIVEMAP
+ uniform mat3 emissiveMapTransform;
+ varying vec2 vEmissiveMapUv;
+#endif
+#ifdef USE_METALNESSMAP
+ uniform mat3 metalnessMapTransform;
+ varying vec2 vMetalnessMapUv;
+#endif
+#ifdef USE_ROUGHNESSMAP
+ uniform mat3 roughnessMapTransform;
+ varying vec2 vRoughnessMapUv;
+#endif
+#ifdef USE_ANISOTROPYMAP
+ uniform mat3 anisotropyMapTransform;
+ varying vec2 vAnisotropyMapUv;
+#endif
+#ifdef USE_CLEARCOATMAP
+ uniform mat3 clearcoatMapTransform;
+ varying vec2 vClearcoatMapUv;
+#endif
+#ifdef USE_CLEARCOAT_NORMALMAP
+ uniform mat3 clearcoatNormalMapTransform;
+ varying vec2 vClearcoatNormalMapUv;
+#endif
+#ifdef USE_CLEARCOAT_ROUGHNESSMAP
+ uniform mat3 clearcoatRoughnessMapTransform;
+ varying vec2 vClearcoatRoughnessMapUv;
+#endif
+#ifdef USE_SHEEN_COLORMAP
+ uniform mat3 sheenColorMapTransform;
+ varying vec2 vSheenColorMapUv;
+#endif
+#ifdef USE_SHEEN_ROUGHNESSMAP
+ uniform mat3 sheenRoughnessMapTransform;
+ varying vec2 vSheenRoughnessMapUv;
+#endif
+#ifdef USE_IRIDESCENCEMAP
+ uniform mat3 iridescenceMapTransform;
+ varying vec2 vIridescenceMapUv;
+#endif
+#ifdef USE_IRIDESCENCE_THICKNESSMAP
+ uniform mat3 iridescenceThicknessMapTransform;
+ varying vec2 vIridescenceThicknessMapUv;
+#endif
+#ifdef USE_SPECULARMAP
+ uniform mat3 specularMapTransform;
+ varying vec2 vSpecularMapUv;
+#endif
+#ifdef USE_SPECULAR_COLORMAP
+ uniform mat3 specularColorMapTransform;
+ varying vec2 vSpecularColorMapUv;
+#endif
+#ifdef USE_SPECULAR_INTENSITYMAP
+ uniform mat3 specularIntensityMapTransform;
+ varying vec2 vSpecularIntensityMapUv;
+#endif
+#ifdef USE_TRANSMISSIONMAP
+ uniform mat3 transmissionMapTransform;
+ varying vec2 vTransmissionMapUv;
+#endif
+#ifdef USE_THICKNESSMAP
+ uniform mat3 thicknessMapTransform;
+ varying vec2 vThicknessMapUv;
+#endif`,Ame=`#if defined( USE_UV ) || defined( USE_ANISOTROPY )
+ vUv = vec3( uv, 1 ).xy;
+#endif
+#ifdef USE_MAP
+ vMapUv = ( mapTransform * vec3( MAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_ALPHAMAP
+ vAlphaMapUv = ( alphaMapTransform * vec3( ALPHAMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_LIGHTMAP
+ vLightMapUv = ( lightMapTransform * vec3( LIGHTMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_AOMAP
+ vAoMapUv = ( aoMapTransform * vec3( AOMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_BUMPMAP
+ vBumpMapUv = ( bumpMapTransform * vec3( BUMPMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_NORMALMAP
+ vNormalMapUv = ( normalMapTransform * vec3( NORMALMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_DISPLACEMENTMAP
+ vDisplacementMapUv = ( displacementMapTransform * vec3( DISPLACEMENTMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_EMISSIVEMAP
+ vEmissiveMapUv = ( emissiveMapTransform * vec3( EMISSIVEMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_METALNESSMAP
+ vMetalnessMapUv = ( metalnessMapTransform * vec3( METALNESSMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_ROUGHNESSMAP
+ vRoughnessMapUv = ( roughnessMapTransform * vec3( ROUGHNESSMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_ANISOTROPYMAP
+ vAnisotropyMapUv = ( anisotropyMapTransform * vec3( ANISOTROPYMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_CLEARCOATMAP
+ vClearcoatMapUv = ( clearcoatMapTransform * vec3( CLEARCOATMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_CLEARCOAT_NORMALMAP
+ vClearcoatNormalMapUv = ( clearcoatNormalMapTransform * vec3( CLEARCOAT_NORMALMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_CLEARCOAT_ROUGHNESSMAP
+ vClearcoatRoughnessMapUv = ( clearcoatRoughnessMapTransform * vec3( CLEARCOAT_ROUGHNESSMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_IRIDESCENCEMAP
+ vIridescenceMapUv = ( iridescenceMapTransform * vec3( IRIDESCENCEMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_IRIDESCENCE_THICKNESSMAP
+ vIridescenceThicknessMapUv = ( iridescenceThicknessMapTransform * vec3( IRIDESCENCE_THICKNESSMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_SHEEN_COLORMAP
+ vSheenColorMapUv = ( sheenColorMapTransform * vec3( SHEEN_COLORMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_SHEEN_ROUGHNESSMAP
+ vSheenRoughnessMapUv = ( sheenRoughnessMapTransform * vec3( SHEEN_ROUGHNESSMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_SPECULARMAP
+ vSpecularMapUv = ( specularMapTransform * vec3( SPECULARMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_SPECULAR_COLORMAP
+ vSpecularColorMapUv = ( specularColorMapTransform * vec3( SPECULAR_COLORMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_SPECULAR_INTENSITYMAP
+ vSpecularIntensityMapUv = ( specularIntensityMapTransform * vec3( SPECULAR_INTENSITYMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_TRANSMISSIONMAP
+ vTransmissionMapUv = ( transmissionMapTransform * vec3( TRANSMISSIONMAP_UV, 1 ) ).xy;
+#endif
+#ifdef USE_THICKNESSMAP
+ vThicknessMapUv = ( thicknessMapTransform * vec3( THICKNESSMAP_UV, 1 ) ).xy;
+#endif`,Rme=`#if defined( USE_ENVMAP ) || defined( DISTANCE ) || defined ( USE_SHADOWMAP ) || defined ( USE_TRANSMISSION ) || NUM_SPOT_LIGHT_COORDS > 0
+ vec4 worldPosition = vec4( transformed, 1.0 );
+ #ifdef USE_BATCHING
+ worldPosition = batchingMatrix * worldPosition;
+ #endif
+ #ifdef USE_INSTANCING
+ worldPosition = instanceMatrix * worldPosition;
+ #endif
+ worldPosition = modelMatrix * worldPosition;
+#endif`;const Pme=`varying vec2 vUv;
+uniform mat3 uvTransform;
+void main() {
+ vUv = ( uvTransform * vec3( uv, 1 ) ).xy;
+ gl_Position = vec4( position.xy, 1.0, 1.0 );
+}`,Ime=`uniform sampler2D t2D;
+uniform float backgroundIntensity;
+varying vec2 vUv;
+void main() {
+ vec4 texColor = texture2D( t2D, vUv );
+ #ifdef DECODE_VIDEO_TEXTURE
+ texColor = vec4( mix( pow( texColor.rgb * 0.9478672986 + vec3( 0.0521327014 ), vec3( 2.4 ) ), texColor.rgb * 0.0773993808, vec3( lessThanEqual( texColor.rgb, vec3( 0.04045 ) ) ) ), texColor.w );
+ #endif
+ texColor.rgb *= backgroundIntensity;
+ gl_FragColor = texColor;
+ #include
+ #include
+}`,Lme=`varying vec3 vWorldDirection;
+#include
+void main() {
+ vWorldDirection = transformDirection( position, modelMatrix );
+ #include
+ #include
+ gl_Position.z = gl_Position.w;
+}`,kme=`#ifdef ENVMAP_TYPE_CUBE
+ uniform samplerCube envMap;
+#elif defined( ENVMAP_TYPE_CUBE_UV )
+ uniform sampler2D envMap;
+#endif
+uniform float flipEnvMap;
+uniform float backgroundBlurriness;
+uniform float backgroundIntensity;
+uniform mat3 backgroundRotation;
+varying vec3 vWorldDirection;
+#include
+void main() {
+ #ifdef ENVMAP_TYPE_CUBE
+ vec4 texColor = textureCube( envMap, backgroundRotation * vec3( flipEnvMap * vWorldDirection.x, vWorldDirection.yz ) );
+ #elif defined( ENVMAP_TYPE_CUBE_UV )
+ vec4 texColor = textureCubeUV( envMap, backgroundRotation * vWorldDirection, backgroundBlurriness );
+ #else
+ vec4 texColor = vec4( 0.0, 0.0, 0.0, 1.0 );
+ #endif
+ texColor.rgb *= backgroundIntensity;
+ gl_FragColor = texColor;
+ #include
+ #include
+}`,Ome=`varying vec3 vWorldDirection;
+#include
+void main() {
+ vWorldDirection = transformDirection( position, modelMatrix );
+ #include
+ #include
+ gl_Position.z = gl_Position.w;
+}`,Nme=`uniform samplerCube tCube;
+uniform float tFlip;
+uniform float opacity;
+varying vec3 vWorldDirection;
+void main() {
+ vec4 texColor = textureCube( tCube, vec3( tFlip * vWorldDirection.x, vWorldDirection.yz ) );
+ gl_FragColor = texColor;
+ gl_FragColor.a *= opacity;
+ #include
+ #include
+}`,Dme=`#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+varying vec2 vHighPrecisionZW;
+void main() {
+ #include
+ #include
+ #include
+ #include
+ #ifdef USE_DISPLACEMENTMAP
+ #include
+ #include
+ #include
+ #endif
+ #include
+ #include
+ #include
+ #include
+ #include
+ #include
+ #include
+ vHighPrecisionZW = gl_Position.zw;
+}`,Fme=`#if DEPTH_PACKING == 3200
+ uniform float opacity;
+#endif
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+varying vec2 vHighPrecisionZW;
+void main() {
+ vec4 diffuseColor = vec4( 1.0 );
+ #include
+ #if DEPTH_PACKING == 3200
+ diffuseColor.a = opacity;
+ #endif
+ #include
+ #include
+ #include
+ #include
+ #include
+ float fragCoordZ = 0.5 * vHighPrecisionZW[0] / vHighPrecisionZW[1] + 0.5;
+ #if DEPTH_PACKING == 3200
+ gl_FragColor = vec4( vec3( 1.0 - fragCoordZ ), opacity );
+ #elif DEPTH_PACKING == 3201
+ gl_FragColor = packDepthToRGBA( fragCoordZ );
+ #endif
+}`,Ume=`#define DISTANCE
+varying vec3 vWorldPosition;
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+void main() {
+ #include
+ #include
+ #include
+ #include
+ #ifdef USE_DISPLACEMENTMAP
+ #include
+ #include
+ #include
+ #endif
+ #include
+ #include
+ #include
+ #include
+ #include
+ #include
+ #include
+ vWorldPosition = worldPosition.xyz;
+}`,zme=`#define DISTANCE
+uniform vec3 referencePosition;
+uniform float nearDistance;
+uniform float farDistance;
+varying vec3 vWorldPosition;
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+void main () {
+ vec4 diffuseColor = vec4( 1.0 );
+ #include
+ #include
+ #include
+ #include
+ #include
+ float dist = length( vWorldPosition - referencePosition );
+ dist = ( dist - nearDistance ) / ( farDistance - nearDistance );
+ dist = saturate( dist );
+ gl_FragColor = packDepthToRGBA( dist );
+}`,Bme=`varying vec3 vWorldDirection;
+#include
+void main() {
+ vWorldDirection = transformDirection( position, modelMatrix );
+ #include
+ #include
+}`,Hme=`uniform sampler2D tEquirect;
+varying vec3 vWorldDirection;
+#include
+void main() {
+ vec3 direction = normalize( vWorldDirection );
+ vec2 sampleUV = equirectUv( direction );
+ gl_FragColor = texture2D( tEquirect, sampleUV );
+ #include
+ #include
+}`,$me=`uniform float scale;
+attribute float lineDistance;
+varying float vLineDistance;
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+void main() {
+ vLineDistance = scale * lineDistance;
+ #include
+ #include
+ #include
+ #include
+ #include
+ #include
+ #include