From 321b5e070ebd42edabcc19e005b2a4c07504c376 Mon Sep 17 00:00:00 2001 From: Alexis DUBURCQ Date: Thu, 19 Aug 2021 14:45:41 +0200 Subject: [PATCH 1/8] [gym/rllib] Fix L2 reg not backpropagating gradient. (#401) * [gym/rllib] Support obs normalization for PPO spatial regularization. * [gym/rllib] Fix L2 reg not backpropagating gradient. * [gym/rllib] Scale spatial loss by observation distance. Co-authored-by: Alexis Duburcq --- .../gym_jiminy/rllib/gym_jiminy/rllib/ppo.py | 72 +++++++++++-------- 1 file changed, 41 insertions(+), 31 deletions(-) diff --git a/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py b/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py index 923f3e361..c88d1209e 100644 --- a/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py +++ b/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py @@ -21,6 +21,7 @@ DEFAULT_CONFIG = PPOTrainer.merge_trainer_configs( DEFAULT_CONFIG, { + "sensitivity_scale": 1.0, "symmetric_policy_reg": 0.0, "caps_temporal_reg": 0.0, "caps_spatial_reg": 0.0, @@ -57,18 +58,24 @@ def ppo_init(policy: Policy, policy._mean_global_caps_loss = 0.0 policy._l2_reg_loss = 0.0 - # Convert to torch.Tensor observation bounds - policy._observation_space_low = \ - torch.from_numpy(policy.observation_space.low).to(dtype=torch.float32) - policy._observation_space_high = \ - torch.from_numpy(policy.observation_space.high).to(dtype=torch.float32) + # Check if the policy has observation filter. If so, disable element-wise + # observation sensitivity. + obs_filter = policy.config["observation_filter"] + if obs_filter == "NoFilter": + policy._is_obs_normalized = False + elif obs_filter == "MeanStdFilter": + policy._is_obs_normalized = True + else: + raise NotImplementedError( + "Only 'NoFilter' and 'MeanStdFilter' are supported.") - # Convert to torch.Tensor observation sensitivity data - observation_space = policy.observation_space.original_space - for field, scale in observation_space.sensitivity.items(): - if not isinstance(scale, torch.Tensor): - scale = torch.from_numpy(scale).to(dtype=torch.float32) - observation_space.sensitivity[field] = scale + # Convert to torch.Tensor observation sensitivity data if necessary + if not policy._is_obs_normalized: + observation_space = policy.observation_space.original_space + for field, scale in observation_space.sensitivity.items(): + if not isinstance(scale, torch.Tensor): + scale = torch.from_numpy(scale).to(dtype=torch.float32) + observation_space.sensitivity[field] = scale # Transpose and convert to torch.Tensor the observation mirroring data for field, mirror_mat in observation_space.mirror_mat.items(): @@ -119,23 +126,23 @@ def ppo_loss(policy: Policy, train_batch_copy = train_batch.copy(shallow=True) # Generate noisy observation based on specified sensivity - offset = 0 - observation_noisy = observation_true.clone() - batch_dim = observation_true.shape[:-1] - observation_space = policy.observation_space.original_space - for field, scale in observation_space.sensitivity.items(): - scale = scale.to(device) - observation_space.sensitivity[field] = scale - unit_noise = torch.randn((*batch_dim, len(scale)), device=device) - slice_idx = slice(offset, offset + len(scale)) - observation_noisy[..., slice_idx].addcmul_(scale, unit_noise) - offset += len(scale) - torch.min(torch.max( - observation_noisy, - policy._observation_space_low.to(device), - out=observation_noisy), - policy._observation_space_high.to(device), - out=observation_noisy) + if policy._is_obs_normalized: + observation_noisy = torch.normal( + observation_true, policy.config["noise_scale"]) + else: + offset = 0 + observation_noisy = observation_true.clone() + batch_dim = observation_true.shape[:-1] + observation_space = policy.observation_space.original_space + for field, scale in observation_space.sensitivity.items(): + scale = scale.to(device) + observation_space.sensitivity[field] = scale + unit_noise = torch.randn( + (*batch_dim, len(scale)), device=device) + slice_idx = slice(offset, offset + len(scale)) + observation_noisy[..., slice_idx].addcmul_( + policy.config["noise_scale"] * scale, unit_noise) + offset += len(scale) # Replace current observation by the noisy one train_batch_copy["obs"] = observation_noisy @@ -259,7 +266,10 @@ def value_function(self, *args: Any, **kwargs: Any) -> torch.Tensor: # Minimize the difference between the original action mean and the # one corresponding to the noisy observation. policy._mean_spatial_caps_loss = torch.mean( - (action_mean_noisy - action_mean_true) ** 2) + torch.sum(( + action_mean_noisy - action_mean_true) ** 2, dim=-1) / + torch.sum(( + observation_noisy - observation_true) ** 2, dim=-1)) # Add spatial smoothness loss to total loss total_loss += policy.config["caps_spatial_reg"] * \ @@ -284,10 +294,10 @@ def value_function(self, *args: Any, **kwargs: Any) -> torch.Tensor: if policy.config["l2_reg"] > 0.0: # Add actor l2-regularization loss - l2_reg_loss = 0.0 + l2_reg_loss = torch.tensor(0.0, requires_grad=True) for name, params in model.state_dict().items(): if "bias" not in name: - l2_reg_loss += l2_loss(params) + l2_reg_loss = l2_reg_loss + l2_loss(params) policy._l2_reg_loss = l2_reg_loss # Add l2-regularization loss to total loss From 6817bb21b4be0ea2ae36e4f63a54dbff5e6b4cd5 Mon Sep 17 00:00:00 2001 From: Alexis Duburcq Date: Thu, 19 Aug 2021 15:00:04 +0200 Subject: [PATCH 2/8] [gym/rllib] Raise clear exception if observation space is not dict in PPO. --- .../gym_jiminy/rllib/gym_jiminy/rllib/ppo.py | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py b/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py index c88d1209e..500b9b4b8 100644 --- a/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py +++ b/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py @@ -21,7 +21,7 @@ DEFAULT_CONFIG = PPOTrainer.merge_trainer_configs( DEFAULT_CONFIG, { - "sensitivity_scale": 1.0, + "noise_scale": 1.0, "symmetric_policy_reg": 0.0, "caps_temporal_reg": 0.0, "caps_spatial_reg": 0.0, @@ -69,9 +69,15 @@ def ppo_init(policy: Policy, raise NotImplementedError( "Only 'NoFilter' and 'MeanStdFilter' are supported.") + # Extract original observation space + try: + observation_space = policy.observation_space.original_space + except AttributeError: + raise NotImplementedError( + "Only 'Dict' original observation space is supported.") + # Convert to torch.Tensor observation sensitivity data if necessary if not policy._is_obs_normalized: - observation_space = policy.observation_space.original_space for field, scale in observation_space.sensitivity.items(): if not isinstance(scale, torch.Tensor): scale = torch.from_numpy(scale).to(dtype=torch.float32) @@ -294,10 +300,10 @@ def value_function(self, *args: Any, **kwargs: Any) -> torch.Tensor: if policy.config["l2_reg"] > 0.0: # Add actor l2-regularization loss - l2_reg_loss = torch.tensor(0.0, requires_grad=True) - for name, params in model.state_dict().items(): - if "bias" not in name: - l2_reg_loss = l2_reg_loss + l2_loss(params) + l2_reg_loss = 0.0 + for name, params in model.named_parameters(): + if not name.endswith("bias"): + l2_reg_loss += l2_loss(params) policy._l2_reg_loss = l2_reg_loss # Add l2-regularization loss to total loss From bcc5515e528016fe6d99e730c4d3891de5057f7a Mon Sep 17 00:00:00 2001 From: Alexis DUBURCQ Date: Sat, 21 Aug 2021 22:34:05 +0200 Subject: [PATCH 3/8] [gym/rllib] Add spatial regularization scheduling. (#402) * [core] Minor cleanup. * [python/viewer] Properly close opening viewer if raises exception at init. * [gym/common] Check that simulation data is available before plotting. * [gym/common] Fix 'play_interactive' not disabling 'is_training' flag. * [gym/rllib] Add spatial regularization scheduling. Co-authored-by: Alexis Duburcq --- core/src/engine/EngineMultiRobot.cc | 12 ++-- .../gym_jiminy/common/envs/env_generic.py | 15 ++++- .../gym_jiminy/rllib/gym_jiminy/rllib/ppo.py | 55 +++++++++++++++---- .../jiminy_py/src/jiminy_py/viewer/viewer.py | 1 + 4 files changed, 64 insertions(+), 19 deletions(-) diff --git a/core/src/engine/EngineMultiRobot.cc b/core/src/engine/EngineMultiRobot.cc index 96dc33cea..724b642e9 100644 --- a/core/src/engine/EngineMultiRobot.cc +++ b/core/src/engine/EngineMultiRobot.cc @@ -1171,9 +1171,9 @@ namespace jiminy { stepper_ = std::unique_ptr( new RungeKuttaDOPRIStepper(systemOde, - robots, - engineOptions_->stepper.tolAbs, - engineOptions_->stepper.tolRel)); + robots, + engineOptions_->stepper.tolAbs, + engineOptions_->stepper.tolRel)); } else if (engineOptions_->stepper.odeSolver == "runge_kutta_4") { @@ -3378,7 +3378,7 @@ namespace jiminy vectorN_t const & stiffness = mdlDynOptions.flexibilityConfig[i].stiffness; vectorN_t const & damping = mdlDynOptions.flexibilityConfig[i].damping; - quaternion_t const quat(q.segment<4>(positionIdx).data()); // Only way to initialize with [x,y,z,w] order + quaternion_t const quat(q.segment<4>(positionIdx)); // Only way to initialize with [x,y,z,w] order vectorN_t const axis = pinocchio::quaternion::log3(quat); uInternal.segment<3>(velocityIdx).array() += - stiffness.array() * axis.array() @@ -3756,7 +3756,7 @@ namespace jiminy i, pinocchio::LOCAL, jointJacobian); - uAugmented += jointJacobian.transpose() * fext[i].toVector(); + uAugmented.noalias() += jointJacobian.transpose() * fext[i].toVector(); } // Compute non-linear effects @@ -3823,7 +3823,7 @@ namespace jiminy // Convert the force from local world aligned to local frame frameIndex_t const & frameIdx = frameConstraint.getFrameIdx(); pinocchio::SE3 const & transformContactInWorld = data.oMf[frameIdx]; - forceIt->linear() = transformContactInWorld.rotation().transpose() * fextWorld; + forceIt->linear().noalias() = transformContactInWorld.rotation().transpose() * fextWorld; // Convert the force from local world aligned to local parent joint jointIndex_t const & jointIdx = model.frames[frameIdx].parent; diff --git a/python/gym_jiminy/common/gym_jiminy/common/envs/env_generic.py b/python/gym_jiminy/common/gym_jiminy/common/envs/env_generic.py index 093e7a1ec..e804d5e52 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/envs/env_generic.py +++ b/python/gym_jiminy/common/gym_jiminy/common/envs/env_generic.py @@ -784,11 +784,17 @@ def plot(self, **kwargs: Any) -> None: # Call base implementation self.simulator.plot(**kwargs) + # Extract log data + log_data = self.simulator.log_data + if not log_data: + raise RuntimeError( + "Nothing to plot. Please run a simulation before calling " + "`plot` method.") + # Extract action. # If telemetry action fieldnames is a dictionary, it cannot be nested. # In such a case, keys corresponds to subplots, and values are # individual scalar data over time to be displayed to the same subplot. - log_data = self.simulator.log_data t = log_data["Global.Time"] tab_data = {} if self.logfile_action_headers is None: @@ -900,8 +906,10 @@ def play_interactive(env: Union["BaseJiminyEnv", gym.Wrapper], assert isinstance(self, BaseJiminyEnv), ( "Unwrapped environment must derived from `BaseJiminyEnv`.") - # Enable play interactive mode flag + # Enable play interactive flag and make sure training flag is disabled + is_training = self.is_training self._is_interactive = True + self.is_training = False # Make sure viewer gui is open, so that the viewer will shared external # forces with the robot automatically. @@ -948,8 +956,9 @@ def _interact(key: Optional[str] = None) -> bool: if self.simulator.is_simulation_running: self.simulator.stop() - # Disable play interactive mode flag + # Disable play interactive mode flag and restore training flag self._is_interactive = False + self.is_training = is_training def train(self) -> None: """Sets the environment in training mode. diff --git a/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py b/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py index 500b9b4b8..fcfba8f82 100644 --- a/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py +++ b/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py @@ -9,13 +9,18 @@ from ray.rllib.models.torch.torch_action_dist import ( TorchDistributionWrapper, TorchDiagGaussian) from ray.rllib.policy.policy import Policy +from ray.rllib.policy.torch_policy import ( + EntropyCoeffSchedule, LearningRateSchedule) from ray.rllib.policy.sample_batch import SampleBatch from ray.rllib.policy.view_requirement import ViewRequirement -from ray.rllib.utils.typing import TensorType, TrainerConfigDict from ray.rllib.utils.torch_ops import l2_loss +from ray.rllib.utils.schedules import PiecewiseSchedule +from ray.rllib.utils.typing import TensorType, TrainerConfigDict + from ray.rllib.agents.ppo import DEFAULT_CONFIG, PPOTrainer from ray.rllib.agents.ppo.ppo_torch_policy import ( - ppo_surrogate_loss, kl_and_loss_stats, setup_mixins, PPOTorchPolicy) + ppo_surrogate_loss, kl_and_loss_stats, setup_mixins, PPOTorchPolicy, + KLCoeffMixin, ValueNetworkMixin) DEFAULT_CONFIG = PPOTrainer.merge_trainer_configs( @@ -25,12 +30,37 @@ "symmetric_policy_reg": 0.0, "caps_temporal_reg": 0.0, "caps_spatial_reg": 0.0, + "caps_spatial_reg_schedule": None, "caps_global_reg": 0.0, "l2_reg": 0.0 }, _allow_unknown_configs=True) +class RegularizationSchedules: + """Mixin for TFPolicy that adds regularization schedules. + """ + def __init__(self, + caps_spatial_reg, + caps_spatial_reg_schedule, + **kwargs): + self._spatial_reg_schedule = None + if caps_spatial_reg_schedule is None: + self._spatial_reg = caps_spatial_reg + else: + self._spatial_reg_schedule = PiecewiseSchedule( + caps_spatial_reg_schedule, + outside_value=caps_spatial_reg_schedule[-1][-1], + framework=None) + self._spatial_reg = self._spatial_reg_schedule.value(0) + + def on_global_var_update(self, global_vars): + super().on_global_var_update(global_vars) + if self._spatial_reg_schedule: + self._spatial_reg = self._spatial_reg_schedule.value( + global_vars["timestep"]) + + def ppo_init(policy: Policy, obs_space: gym.spaces.Space, action_space: gym.spaces.Space, @@ -40,6 +70,9 @@ def ppo_init(policy: Policy, # Call base implementation setup_mixins(policy, obs_space, action_space, config) + # Initialize regulaization scheduling + RegularizationSchedules.__init__(policy, **config) + # Add previous observation in viewer requirements for CAPS loss computation # TODO: Remove update of `policy.model.view_requirements` after ray fix caps_view_requirements = { @@ -126,8 +159,7 @@ def ppo_loss(policy: Policy, # Append the training batches to the set train_batches["prev"] = train_batch_copy - if policy.config["caps_spatial_reg"] > 0.0 or \ - policy.config["caps_global_reg"] > 0.0: + if policy._spatial_reg > 0.0 or policy.config["caps_global_reg"] > 0.0: # Shallow copy the original training batch train_batch_copy = train_batch.copy(shallow=True) @@ -238,8 +270,7 @@ def value_function(self, *args: Any, **kwargs: Any) -> torch.Tensor: action_mean_prev = action_dist_prev.deterministic_sample() # Compute the mean action corresponding to the noisy observation - if policy.config["caps_spatial_reg"] > 0.0 or \ - policy.config["caps_global_reg"] > 0.0: + if policy._spatial_reg > 0.0 or policy.config["caps_global_reg"] > 0.0: action_logits_noisy = logits["noisy"] if issubclass(dist_class, TorchDiagGaussian): action_mean_noisy, _ = torch.chunk(action_logits_noisy, 2, dim=1) @@ -268,7 +299,7 @@ def value_function(self, *args: Any, **kwargs: Any) -> torch.Tensor: total_loss += policy.config["caps_temporal_reg"] * \ policy._mean_temporal_caps_loss - if policy.config["caps_spatial_reg"] > 0.0: + if policy._spatial_reg > 0.0: # Minimize the difference between the original action mean and the # one corresponding to the noisy observation. policy._mean_spatial_caps_loss = torch.mean( @@ -278,8 +309,7 @@ def value_function(self, *args: Any, **kwargs: Any) -> torch.Tensor: observation_noisy - observation_true) ** 2, dim=-1)) # Add spatial smoothness loss to total loss - total_loss += policy.config["caps_spatial_reg"] * \ - policy._mean_spatial_caps_loss + total_loss += policy._spatial_reg * policy._mean_spatial_caps_loss if policy.config["caps_global_reg"] > 0.0: # Minimize the magnitude of action mean @@ -324,7 +354,7 @@ def ppo_stats(policy: Policy, stats_dict["symmetry"] = policy._mean_symmetric_policy_loss if policy.config["caps_temporal_reg"] > 0.0: stats_dict["temporal_smoothness"] = policy._mean_temporal_caps_loss - if policy.config["caps_spatial_reg"] > 0.0: + if policy._spatial_reg > 0.0: stats_dict["spatial_smoothness"] = policy._mean_spatial_caps_loss if policy.config["caps_global_reg"] > 0.0: stats_dict["global_smoothness"] = policy._mean_global_caps_loss @@ -339,6 +369,10 @@ def ppo_stats(policy: Policy, loss_fn=ppo_loss, stats_fn=ppo_stats, get_default_config=lambda: DEFAULT_CONFIG, + mixins=[ + LearningRateSchedule, RegularizationSchedules, EntropyCoeffSchedule, + KLCoeffMixin, ValueNetworkMixin, + ] ) @@ -356,6 +390,7 @@ def get_policy_class( get_policy_class=get_policy_class ) + __all__ = [ "DEFAULT_CONFIG", "PPOTorchPolicy", diff --git a/python/jiminy_py/src/jiminy_py/viewer/viewer.py b/python/jiminy_py/src/jiminy_py/viewer/viewer.py index 1e83a1acf..afe1c4bc7 100644 --- a/python/jiminy_py/src/jiminy_py/viewer/viewer.py +++ b/python/jiminy_py/src/jiminy_py/viewer/viewer.py @@ -510,6 +510,7 @@ def __init__(self, Viewer._backend_robot_colors.update({ self.robot_name: self.robot_color}) except Exception as e: + self.close() raise RuntimeError( "Impossible to create backend or connect to it.") from e From 3150b35f16dc3e5c8a1686f5deb5ae714a9fdf1c Mon Sep 17 00:00:00 2001 From: Alexis DUBURCQ Date: Sat, 4 Sep 2021 23:12:23 +0200 Subject: [PATCH 4/8] [core] More stable solution for LCP solver. (#405) * [core] Shuffle constraint solver iterations iif necessary, no matter if constraint set changes. * [core/python] Fix bindings signature of some controller's method. * [python/viewer] Add height map rendering capability to Panda3d backend. * [python/plot] Fix missing grid for single plot tabs. * [python/viewer] Fix viewer compatibility with meshcat>=0.3.1. * [python/viewer] Increase meshcat recorder timeout. * [gym/common] Add flag to 'play_interactive' to ignore 'is_done' state. * [gym/rllib] Replace L2-norm temporal smoothness regularization by L1-norm. * [gym/rllib] Remove regularization scheduling because irrelevant. * [misc] Fix CI dependency install. * [misc] Fix unit test gym. Co-authored-by: Alexis Duburcq --- .github/workflows/manylinux.yml | 2 +- .github/workflows/ubuntu.yml | 3 +- .github/workflows/win.yml | 2 +- core/src/engine/EngineMultiRobot.cc | 8 +- core/src/solver/LCPSolvers.cc | 36 ++++++- .../gym_jiminy/common/envs/env_generic.py | 9 +- .../gym_jiminy/common/envs/env_locomotion.py | 2 +- .../gym_jiminy/rllib/gym_jiminy/rllib/ppo.py | 45 +------- .../rllib/gym_jiminy/rllib/utilities.py | 25 +++-- .../unit_py/data/atlas_standing_meshcat_1.png | Bin 0 -> 27598 bytes .../data/cassie_standing_meshcat_3.png | Bin 0 -> 9751 bytes .../data/cassie_standing_meshcat_4.png | Bin 0 -> 9975 bytes .../data/cassie_standing_meshcat_5.png | Bin 0 -> 9757 bytes .../data/cassie_standing_panda3d_6.png | Bin 0 -> 7811 bytes .../data/cassie_standing_panda3d_7.png | Bin 0 -> 6679 bytes .../unit_py/test_pipeline_control.py | 3 +- python/jiminy_py/setup.py | 5 +- python/jiminy_py/src/jiminy_py/dynamics.py | 4 +- python/jiminy_py/src/jiminy_py/plot.py | 1 + .../src/jiminy_py/viewer/meshcat/index.html | 29 +++--- .../src/jiminy_py/viewer/meshcat/recorder.py | 2 +- .../viewer/panda3d/panda3d_visualizer.py | 96 +++++++++++++++--- python/jiminy_pywrap/src/Controllers.cc | 6 +- 23 files changed, 181 insertions(+), 97 deletions(-) create mode 100644 python/gym_jiminy/unit_py/data/atlas_standing_meshcat_1.png create mode 100644 python/gym_jiminy/unit_py/data/cassie_standing_meshcat_3.png create mode 100644 python/gym_jiminy/unit_py/data/cassie_standing_meshcat_4.png create mode 100644 python/gym_jiminy/unit_py/data/cassie_standing_meshcat_5.png create mode 100644 python/gym_jiminy/unit_py/data/cassie_standing_panda3d_6.png create mode 100644 python/gym_jiminy/unit_py/data/cassie_standing_panda3d_7.png diff --git a/.github/workflows/manylinux.yml b/.github/workflows/manylinux.yml index 62756c1a8..4ceab5afd 100644 --- a/.github/workflows/manylinux.yml +++ b/.github/workflows/manylinux.yml @@ -66,7 +66,7 @@ jobs: - name: Build project dependencies run: | ./build_tools/build_install_deps_linux.sh - "${PYTHON_EXECUTABLE}" -m pip install "gym>=0.18.3" "stable_baselines3>=0.10" "importlib-metadata>=3.3.0" + "${PYTHON_EXECUTABLE}" -m pip install --prefer-binary "gym>=0.18.3" "stable_baselines3>=0.10" "importlib-metadata>=3.3.0" ##################################################################################### diff --git a/.github/workflows/ubuntu.yml b/.github/workflows/ubuntu.yml index 1fdcad88d..49eec3a1c 100644 --- a/.github/workflows/ubuntu.yml +++ b/.github/workflows/ubuntu.yml @@ -52,7 +52,7 @@ jobs: "${PYTHON_EXECUTABLE}" -m pip install --upgrade numpy "${PYTHON_EXECUTABLE}" -m pip install tensorflow "${PYTHON_EXECUTABLE}" -m pip install "torch==1.8.0+cpu" -f https://download.pytorch.org/whl/torch_stable.html - "${PYTHON_EXECUTABLE}" -m pip install "gym>=0.18.3" "stable_baselines3>=0.10" "importlib-metadata>=3.3.0" + "${PYTHON_EXECUTABLE}" -m pip install --prefer-binary "gym>=0.18.3" "stable_baselines3>=0.10" "importlib-metadata>=3.3.0" "${PYTHON_EXECUTABLE}" -m pip install "ray[default,rllib]<=1.4.0" # Type checking is not working with 1.4.1 ##################################################################################### @@ -121,6 +121,7 @@ jobs: --disable=fixme,abstract-method,protected-access,useless-super-delegation \ --disable=too-many-instance-attributes,too-many-arguments,too-few-public-methods,too-many-lines \ --disable=too-many-locals,too-many-branches,too-many-statements \ + --disable=unspecified-encoding,logging-fstring-interpolation \ --generated-members=numpy.*,torch.* "gym_jiminy/" mypy --allow-redefinition --check-untyped-defs --disallow-incomplete-defs --disallow-untyped-defs \ diff --git a/.github/workflows/win.yml b/.github/workflows/win.yml index 4e8f73e83..3ed4e40bb 100644 --- a/.github/workflows/win.yml +++ b/.github/workflows/win.yml @@ -50,7 +50,7 @@ jobs: - name: Build project dependencies run: | python -m pip install "torch==1.8.0+cpu" -f https://download.pytorch.org/whl/torch_stable.html - python -m pip install "gym>=0.18.3" "stable_baselines3>=0.10" "importlib-metadata>=3.3.0" + python -m pip install --prefer-binary "gym>=0.18.3" "stable_baselines3>=0.10" "importlib-metadata>=3.3.0" & "./build_tools/build_install_deps_windows.ps1" ##################################################################################### diff --git a/core/src/engine/EngineMultiRobot.cc b/core/src/engine/EngineMultiRobot.cc index 724b642e9..6a3329deb 100644 --- a/core/src/engine/EngineMultiRobot.cc +++ b/core/src/engine/EngineMultiRobot.cc @@ -3047,19 +3047,19 @@ namespace jiminy // Compute normal force float64_t const fextNormal = - std::min(contactOptions_.stiffness * depth + contactOptions_.damping * vDepth, 0.0); - fextInWorld = fextNormal * nGround; + fextInWorld.noalias() = fextNormal * nGround; // Compute friction forces vector3_t const vTangential = vContactInWorld - vDepth * nGround; float64_t const vRatio = std::min(vTangential.norm() / contactOptions_.transitionVelocity, 1.0); float64_t const fextTangential = contactOptions_.friction * vRatio * fextNormal; - fextInWorld -= fextTangential * vTangential; + fextInWorld.noalias() -= fextTangential * vTangential; // Add blending factor if (contactOptions_.transitionEps > EPS) { - float64_t const blendingFactor = -depth / contactOptions_.transitionEps; - float64_t const blendingLaw = std::tanh(2 * blendingFactor); + float64_t const blendingFactor = - depth / contactOptions_.transitionEps; + float64_t const blendingLaw = std::tanh(2.0 * blendingFactor); fextInWorld *= blendingLaw; } } diff --git a/core/src/solver/LCPSolvers.cc b/core/src/solver/LCPSolvers.cc index 8e264e2e3..db05aa836 100644 --- a/core/src/solver/LCPSolvers.cc +++ b/core/src/solver/LCPSolvers.cc @@ -89,14 +89,38 @@ namespace jiminy https://github.com/dartsim/dart/blob/master/dart/constraint/PgsBoxedLcpSolver.cpp */ assert(b.size() > 0 && "The number of inequality constraints must be larger than 0."); - /* Reset shuffling counter. + /* Adapt shuffling indices if the number of indices has changed. Note that it may converge faster to enforce constraints in reverse order, since usually constraints bounds dependending on others have lower indices by design. For instance, for friction, x and y */ - indices_.resize(b.size()); - std::generate(indices_.begin(), indices_.end(), - [n = static_cast(indices_.size() - 1)]() mutable { return n--; }); - lastShuffle_ = 0U; // Do NOT shuffle indices right after initialization + size_t const nIndicesOrig = indices_.size(); + size_t const nIndices = b.size(); + if (nIndicesOrig < nIndices) + { + indices_.resize(nIndices); + std::generate(indices_.begin() + nIndicesOrig, indices_.end(), + [n = static_cast(nIndices - 1)]() mutable { return n--; }); + } + else if (nIndicesOrig > nIndices) + { + size_t shiftIdx = nIndices; + for (size_t i = 0; i < nIndices; ++i) + { + if (static_cast(indices_[i]) >= nIndices) + { + for (size_t j = shiftIdx; j < nIndicesOrig; ++j) + { + ++shiftIdx; + if (static_cast(indices_[j]) < nIndices) + { + indices_[i] = indices_[j]; + break; + } + } + } + } + indices_.resize(nIndices); + } // Normalizing for (Eigen::Index i = 0; i < b.size(); ++i) @@ -111,6 +135,8 @@ namespace jiminy bool_t isSuccess = ProjectedGaussSeidelIter(A, b, lo, hi, fIdx, false, true, x); if (isSuccess) { + // Do NOT shuffle indices unless necessary to avoid discontinuities + lastShuffle_ = 0U; return true; } } diff --git a/python/gym_jiminy/common/gym_jiminy/common/envs/env_generic.py b/python/gym_jiminy/common/gym_jiminy/common/envs/env_generic.py index e804d5e52..e85f073ad 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/envs/env_generic.py +++ b/python/gym_jiminy/common/gym_jiminy/common/envs/env_generic.py @@ -869,6 +869,7 @@ def replay(self, enable_travelling: bool = True, **kwargs: Any) -> None: def play_interactive(env: Union["BaseJiminyEnv", gym.Wrapper], enable_travelling: Optional[bool] = None, start_paused: bool = True, + enable_is_done: bool = True, verbose: bool = True, **kwargs: Any) -> None: """Activate interact mode enabling to control the robot using keyboard. @@ -935,11 +936,13 @@ def play_interactive(env: Union["BaseJiminyEnv", gym.Wrapper], # Define interactive loop def _interact(key: Optional[str] = None) -> bool: - nonlocal obs, reward + nonlocal obs, reward, enable_is_done action = self._key_to_action( key, obs, reward, **{"verbose": verbose, **kwargs}) obs, reward, done, _ = env.step(action) env.render() + if not enable_is_done and env.robot.has_freeflyer: + return env.system_state.q[2] < 0.0 return done # Run interactive loop @@ -1107,6 +1110,10 @@ def refresh_observation(self) -> None: # type: ignore[override] .. note:: This method is called and the end of every low-level `Engine.step`. + .. note:: + Note that `np.nan` values will be automatically clipped to 0.0 by + `get_observation` method before return it, so it is valid. + .. warning:: In practice, it updates the internal buffer directly for the sake of efficiency. diff --git a/python/gym_jiminy/common/gym_jiminy/common/envs/env_locomotion.py b/python/gym_jiminy/common/gym_jiminy/common/envs/env_locomotion.py index a6ced6910..a61822642 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/envs/env_locomotion.py +++ b/python/gym_jiminy/common/gym_jiminy/common/envs/env_locomotion.py @@ -391,7 +391,7 @@ def compute_reward(self, # type: ignore[override] if 'energy' in reward_mixture_keys: v_mot = self.robot.sensors_data[encoder.type][1] command = self.system_state.command - power_consumption = sum(np.maximum(command * v_mot, 0.0)) + power_consumption = np.sum(np.maximum(command * v_mot, 0.0)) power_consumption_rel = \ power_consumption / self._power_consumption_max reward_dict['energy'] = - power_consumption_rel diff --git a/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py b/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py index fcfba8f82..10aeb73e8 100644 --- a/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py +++ b/python/gym_jiminy/rllib/gym_jiminy/rllib/ppo.py @@ -9,18 +9,14 @@ from ray.rllib.models.torch.torch_action_dist import ( TorchDistributionWrapper, TorchDiagGaussian) from ray.rllib.policy.policy import Policy -from ray.rllib.policy.torch_policy import ( - EntropyCoeffSchedule, LearningRateSchedule) from ray.rllib.policy.sample_batch import SampleBatch from ray.rllib.policy.view_requirement import ViewRequirement from ray.rllib.utils.torch_ops import l2_loss -from ray.rllib.utils.schedules import PiecewiseSchedule from ray.rllib.utils.typing import TensorType, TrainerConfigDict from ray.rllib.agents.ppo import DEFAULT_CONFIG, PPOTrainer from ray.rllib.agents.ppo.ppo_torch_policy import ( - ppo_surrogate_loss, kl_and_loss_stats, setup_mixins, PPOTorchPolicy, - KLCoeffMixin, ValueNetworkMixin) + ppo_surrogate_loss, kl_and_loss_stats, setup_mixins, PPOTorchPolicy) DEFAULT_CONFIG = PPOTrainer.merge_trainer_configs( @@ -37,30 +33,6 @@ _allow_unknown_configs=True) -class RegularizationSchedules: - """Mixin for TFPolicy that adds regularization schedules. - """ - def __init__(self, - caps_spatial_reg, - caps_spatial_reg_schedule, - **kwargs): - self._spatial_reg_schedule = None - if caps_spatial_reg_schedule is None: - self._spatial_reg = caps_spatial_reg - else: - self._spatial_reg_schedule = PiecewiseSchedule( - caps_spatial_reg_schedule, - outside_value=caps_spatial_reg_schedule[-1][-1], - framework=None) - self._spatial_reg = self._spatial_reg_schedule.value(0) - - def on_global_var_update(self, global_vars): - super().on_global_var_update(global_vars) - if self._spatial_reg_schedule: - self._spatial_reg = self._spatial_reg_schedule.value( - global_vars["timestep"]) - - def ppo_init(policy: Policy, obs_space: gym.spaces.Space, action_space: gym.spaces.Space, @@ -70,9 +42,6 @@ def ppo_init(policy: Policy, # Call base implementation setup_mixins(policy, obs_space, action_space, config) - # Initialize regulaization scheduling - RegularizationSchedules.__init__(policy, **config) - # Add previous observation in viewer requirements for CAPS loss computation # TODO: Remove update of `policy.model.view_requirements` after ray fix caps_view_requirements = { @@ -105,9 +74,9 @@ def ppo_init(policy: Policy, # Extract original observation space try: observation_space = policy.observation_space.original_space - except AttributeError: + except AttributeError as e: raise NotImplementedError( - "Only 'Dict' original observation space is supported.") + "Only 'Dict' original observation space is supported.") from e # Convert to torch.Tensor observation sensitivity data if necessary if not policy._is_obs_normalized: @@ -293,7 +262,7 @@ def value_function(self, *args: Any, **kwargs: Any) -> torch.Tensor: if policy.config["caps_temporal_reg"] > 0.0: # Minimize the difference between the successive action mean policy._mean_temporal_caps_loss = torch.mean( - (action_mean_prev - action_mean_true) ** 2) + (action_mean_prev - action_mean_true).abs()) # Add temporal smoothness loss to total loss total_loss += policy.config["caps_temporal_reg"] * \ @@ -368,11 +337,7 @@ def ppo_stats(policy: Policy, before_loss_init=ppo_init, loss_fn=ppo_loss, stats_fn=ppo_stats, - get_default_config=lambda: DEFAULT_CONFIG, - mixins=[ - LearningRateSchedule, RegularizationSchedules, EntropyCoeffSchedule, - KLCoeffMixin, ValueNetworkMixin, - ] + get_default_config=lambda: DEFAULT_CONFIG ) diff --git a/python/gym_jiminy/rllib/gym_jiminy/rllib/utilities.py b/python/gym_jiminy/rllib/gym_jiminy/rllib/utilities.py index 455a6b1e1..fabf8bdd2 100644 --- a/python/gym_jiminy/rllib/gym_jiminy/rllib/utilities.py +++ b/python/gym_jiminy/rllib/gym_jiminy/rllib/utilities.py @@ -309,7 +309,7 @@ def build_policy_wrapper(policy: Policy, action_space = policy.action_space # Build preprocessor to flatten environment observation - observation_space_orig = policy.observation_space + observation_space_orig = observation_space if hasattr(observation_space_orig, "original_space"): observation_space_orig = observation_space.original_space preprocessor_class = get_preprocessor(observation_space_orig) @@ -552,16 +552,19 @@ def train(train_agent: Trainer, # Ascii histogram if requested if verbose: - plt.clp() - plt.subplots(1, 2) - for i, (title, data) in enumerate(zip( - ("Episode duration", "Total reward"), - (duration, total_rewards))): - plt.subplot(1, i) - plt.hist(data, HISTOGRAM_BINS) - plt.plotsize(50, 20) - plt.title(title) - plt.show() + try: + plt.clp() + plt.subplots(1, 2) + for i, (title, data) in enumerate(zip( + ("Episode duration", "Total reward"), + (duration, total_rewards))): + plt.subplot(1, i) + plt.hist(data, HISTOGRAM_BINS) + plt.plotsize(50, 20) + plt.title(title) + plt.show() + except IndexError as e: + logger.warning(f"Rendering statistics failed: {e}") # Backup the policy if checkpoint_period > 0 and iter_num % checkpoint_period == 0: diff --git a/python/gym_jiminy/unit_py/data/atlas_standing_meshcat_1.png b/python/gym_jiminy/unit_py/data/atlas_standing_meshcat_1.png new file mode 100644 index 0000000000000000000000000000000000000000..666a0ce358eba5d383fdc3a4af21d99ea48e52c9 GIT binary patch literal 27598 zcmYhjc{tSTA2&WNCoK|Eb~=u-mNn~0%93RW*%?XpeK)r0g9?`9Y@vjGFsF?H!*wZLzuMXm3grT+Bm$n~eQ3 z>!`R|M6d*9{)yMyTthT5UHQR5#Dj#{_hKaMgIX#DD!^~{)PEZaM;ps zkHNVg4Vb_E@1Omj1OE8$!-pjAMyWwMPgqb+{XVs+y5>>``Q2R z`imXX%52^U! zpWl5gIA52@b$CCR3dQn4lAYu<&i>+^d;e*LyZgn_!ia6#ucnTGhEp_BXIDBEJ>SG6uO9*IVhrGIX=0c}ppG5I~`B8h_ z&-ZwWF~_KTLvGxIcj{`nmAT_jxOzsOOQlIpwQ`^SOke9ju1qu_>(TomZC)~*L-Xe$ zzqmM>Pwn0q#Czi8RSSlm%E~bRh27dL!Ie~yHzmEG0v#JYyn<1?GngA0y}cpr zGT?ngI6|+asPE_DQB@0w_Kpq|r8@aAT+*)Gj3Y+nts=Z5iji(~XRpsFs&?bGdi?|` zNDQ*ho_G4{GoOA!l`b|@yJTaoFTGfF?m=LX=d;o}a~<_jo5DMhxn<<(>FE#iQN`fx zMaa3zpZ}FN^FDNUT#7^@;p8uNeKgR49femGi}o8)AIhoPwuMp0>s)+pTDJ=mmv5ik z9ea|%+NtO`u78PzrP{W+wz(OxJolLU9-@$>l+3qKohGcCrn!c5Z}23Hwej|!YMELE z59X+c*GGOU>gmm>fb6rs2$-u^|2n-6`}BDG#)S)IZppolIC;#q_sp67hsAi5eTbcf zV5y?FxA*Gua$Fn<(Y}Vw=t}9GEiEnWO%Xf_^xfa2`=3o(eok3!6;dj@X>*do2AaoVI#!aNsJR zQ2ZcS-`*-KNH4H7r;Lo49(L5y6bm8^6;P>E4^DKJ(|Dtr%gYM%d5BUv?A+C70qNrn z(*6^AN!le8JW4%$$G`$5IFBfd@>~8LeVs_7?d+5_Ef&;C@-m;{<>mEh-z$sz8p|1v zSz+mHeghWn9ytWQ76R{hGG#ZgRV=#CIQ;Tu0~cJjr?(eW`Xdx7!17}LD*xkdzt)zP z@Y$Xurb_~nl9C6MXphW%bx5las7NIDZtNY#pn5A~hro#H5KU-nQzI0%u{Bp$ND%G2 z!HoqzyFJBMG46RMa(|nOxA)oEzn@-K0vWpG!FE!~VyjPkdS#446)`FlEv=Qr)EdCy zSIXh2qQKo@?)&(lAkJN~#wOH4Pc33sI(e3aEwZOtcj#M>+A~A)pD|y3wl(`+39*0p z`}gmsvN;Afa4UGH56z2PBrM9dc{9OrC#-EFRI>M`{ilwOqiDf{$B~hYaH8G8vN3x+ z{kH982w&F?T-)BU%FrJwB-0--)WsYKxH0jNOqiEY? zT+?(|#rrdFH1f_sNdFvP04_DP`Qt;5?xAZ}Q8}b$2d+X=X5yI}y1xjGwii?|7Dj9YS2~m_vfMPuwa-FOYg-3HD>hZ;{vN`$kk8-{y6uW|bAfmpfn_H&n zJsC=y3eghA$aYCDQDdv;H=!szWmG4x7~bG30BIKjg?C7oAP2<;*wJR0u@N`J$zKy&F&;>OO^6AGvf3UX+&?z(*=cx#Q2* zOJk5-AhSwQnKGn>g$N=Z#os$DCV>wE9}($?xIOhKg`?grJh2*2$#TjJKiP>N1RbVx z@1Y)Z*GEZxVGF$p*?}!6rZzJ(6YLzuUeVDWlVHSm@1{(XLXukK{*NF#LSxWnCbr>~ z+D$0lC+HsK*RRLYT!AY5Y~w$F?yh%TvJYQrn3|drO)yXBUsUG`qTGSYb%&LC|r`qCXs8ygCZ?&0B4<^~EXy4uMqOtAEkF-M~pumA5fRmj7e zHkJh!I-9@$o$A14m4!&lw8=10RaKqxZW?w4o2(Lr0*`e{RUT$KHTJpDi}C1jny^Y{ zrju2g@SwBY+2_~JR@=3JjT77DfWn*VHCKDYzhCoFAv@)kv3K)d>fCz`Hn_6P*YACA z$)le2)>Y2A&a9_}exs}7ez@OOv-n94JQMx*tWufV5?2KrMOk2330Boj^RLg$ywd9j zO0%wHSEwIS;*@H!1cVeTb`L_*jDOd)=#K7qcWWTGI;GZ26&s+|Ti%6&VsY{fk{CZe ze&_fH#vIiYm1H@_O++Cj!|c!QnT*%$slvLigiiZ<11RKc$ShL}EgE`!Ma!5&E6d4& zYs|gDA1jF|vv@Y9@ybLTX4)m~Ec79#p;#mxENG!LmG}Odnw6eHLb_?9TIaz%Ie_+} zEMxE&rq(}(uQVenK^kV-_Uc#t1)@B`4_uh8QgH-TDrge zY9oWwQ4DlfU3PY`2QC&&p2+6}B`2}?9dV6vG3=I+Vy}r_6$*tN9E^{1vceXsc_`$$ z~d4{ljOSHmrOrC$~l6lj-#+u_hc@3q7+zvyzo7HSzk&2{FAHRkAEaeCkJDo!3I zhmkb~U0q28^y&QcsJCgt=bpa~A}1MLJ={!>>4@NI9b2OXP3Yo39&KiK{7|JZo!NrY zphlWE(&KN9j$B`N;JT_cgDCVO#5%mxE-5-XAc3V3{rT5Q6VY5Rsn^l2{JM}{Mj;%m zwLEk%gs5bi4J<4O8r&OHCLIX044jt-98_wb3i+65Mg;pumC4yUvXe%-0)>;RCzk z9za^HqGAd6M2fB^+V%SROJLQc&OX;k5m;GS$yBw@D)p%Qtz?LM#93AGSF-mqjh>j8 z7_v6K5~xzpC5u>)I7hE%PVYe6c78^Kwsn;&|G5^KRmKvE_Q8Cuj(*xj^ z2fxcomZ|37ski84myK3|r7V2-#zd&wZ!BxgbA#IGQ?xH%8%gdv1%}gWw1OCqH~z=V z_zu9VO6sW{k8M&k=j3K{Kc!u1nfk3!Y1<~gRe!NLVy6Gl3z4sAF3j^a+RoUd;^qOl znEI6d_}bvLvpb_P50!N~N}YFj{H3J{HVX$^nzzcpCi0TB&6-iR6@tWlFFVnRki7_y zV6iC68dOg+GW+k+NPsU>gAGPg!G$Dw?Vn9b|wMrDxKlVk61Y2sHutg|o23L0u7-${{4A53hYIP&HI_XWVsQdCl%{y13=g6|)q2L6!#w*0!9Wl^t2F zNGTxwi9%%Ig&UviY}eDh>B8K_XUO9?c?Y2YGjxAjq@TUujuM zg?MvfjY>iPP*r z^*jPDCs&$5LX`XnG|S*>kISeazKRu#mFLeSH6Oa;fmLQ)vG~!J!6)lNOL{O|BlXUFA(}Tl z%js{ojK8xjg-k?CzwT(AcZzSf2j#8qJR2d)b1Cm)mnd@=s|?i@x1HrAXD72CD|7aO zh%P&E{mVyDM-7J0{fzI+{CBT-3Rs_cn98Ymx%3eSD2{D$)&m35DdcsxfqDz2!0i&p zCcf}WmQ3f2jr1rR#jP?5S1iF(fhw++-Z!^s2I;iWICJ6dZE&jVx@pX3PO;T^*+_Lk z3o6sH=`mRjxIn~@KuM~2>ez7HlIyclSdn(~@K&pH9m3c5-?H~3S`Lu)OhC?Fi}$$7 zFHys)DNEOL=KmQ;H~AoXK0v(6iL1xp-2U*v*zigZCOr+O{Lw$0`vL!;k5!hLx0SW^ z#Q3MB! zvNGp(yrNZ8UoSuYGayk^hGEej2vHJ9(moMkcC@&2&;JP7PT#GL4xNVjidT3d~!-6$Z^@es(L z(SQ7^Fx@OxzE?<6i4&WBRnl$N8*8OgQY_o4qL81P+}7`iL06MeqW2}d!r-zPSvEhu z^2x1%#fuO)+li~s&OfzMC~%R51)#sX-{8M}*^xh~`l zsbGB;8{g}?pa}YjCJ3dDN0md?osQLj-Gq!Vv47IK%pw52%08t#hOCunWq`$UO)>7=k$Ff0z(0g(*M;bCw^TSpVWgyTwm%Q0KkeGW~XB<1P~l|OpoFXf}%gyAEV!CP4%$U1+<&%<_&B&tH=kJ;w^Xuz+@DJJ6mX<%KreJAr zU)Gd4qH2}DRP>saYg(XWwUq4qN*%@8K47=6vTZ~n!v^zphuYXWE$%6cJVQNw#Z?oU zqX+(a3#X(th(Cku;wq3VY4+-$=>Q>Y-S51 z+ZL3G9eEgkuNXZjNiHDYD*ZVG?Am*PfuQDm?(jEvSE(cEJuV%42(H+$>Z)$g8;rwBWRW|I)PWhzUXk$?h9Vt#8LI#*my6xsfG zV*Sd$pHHrvjc!F>IyyX3Gumz*Rl5hNdP!^>WLq%q4W$*#HxDn1RMG9d9u$1Gba9 zde+rXFC78F!rRLW5G*E**BRoo<)fo!gvRJ=qNMXdFH0+?FtIFh0Wsy+b3?C`HC55V zhB@scRUadW*jh;#Si}7ZbSSo{yy~NGd;9U;`KM}E|6=D_#bwI^mm`J59YOV5)%G1x zGhbqqk~2-ZW*#bj-Hb%a(+YYHbu?Hr5S5Y`1Kf`kZk|}YV$@xkGkW zw1(Xqwv~Y}Q|8t|7>1}u`DMm z&Re#hLN}hI2_FMAo^HQ<;Xc!5uJ8+T2+4x4{g?RjKBr}Gnc!@k@2CZ1$y5E4nI=FX z0n4!oqCGK`*j>$AEn&S94tT>7*7NGtB zJ{{W1%UMh8XR@UW5pJa*INrz(Al0l=R#(qOw6({+-96wfUcS-+n$f^!N`_2AGTgR^$e{i{VGcSejoE?6&;UT&$T-n$%8EUug&86Ku zm)y!{Oup;B(CIIe@2{96K9JBo^-Tq>)iMs>(oV@R+1lE|SKHyrt0?t>XJ3)_s7lkx zp~bA7YtcX(k(vqivR7j`wZZMJt@l?$I_RjwQKkzQF8H)=Xaik>MpwB|n!%H#O`%Y# zDG6~Vw;9mEpGyPpA1E3~B?vL!XX~pqK(*U8dWzn!ATR2{g6hRhO?4bAxpAcyu@1{F z)J;GGp;*G?WFVhQWTah)Ki=LNh1UYgrU<8X6``S${GmCQ+E>k?#g<4>S~Yh~{HESA z^@+TuHm?L;=Z;vl~=2kU4_Dg`<6kGLKO~Xs9$FOOO}+^XI?g z7PVJ2ScP>rA1f*h%F7%;v6+@a>NlO-yanc8MUMWAlh>6E9jB#xSh&xAJUD;oftDZy+Z`)nLIJ_(+ov)Lu z^9m1h_qpMBo3X!mQVD0aB5T%tJ0SG!B)R-#(_f^as z!xiGKTep^&Cx?cTy$C>5TmZ`|6k1qRgg4Cr+SEL6fxH?QOP6&OC=vRxoJ&`dlx`2IPfeWK!si0lZQGbFuA4V8tjJ zdDOmk{G}>$ea$rCac<2c>E;YpyAz?@0H0oN3n+!7@KW&BMFc!eSj!kJq?rGHMn^}1 zA`QgV<<-@t!{U85Xj^>|1&yp zT7?*vWSoEAxz#%C`ZilTdG=>*rBd>&lD9k$y4ls3Lj^jbTPY7?s+oXgxo8LQS@b&i zzxoV5^JiO>eUQ7#siO8}IJjifA3@)ii=8izb(llQ1jw$TL@EZ$RxhUt#~bF6-x-$U zek+X)qCu}M5Zf-j_~L%#sMXkq1&cH5OfP`DCZh6cF8T7OY8wlTY9%!YQg1_mw-(9|M7McMRNIz4kDG{P0inNysfymxcDa3&|Ay1z10 zrorE^WccT$svN?UkARVPWK-j(PoJ8bt!^n52w1&xnV3(>C41M|X z+<}X>Miflx4S%mLooB}Q0Xgh^2pE!PN0fYj<;3RZX3;@kk!98>Iq)hcCw^>f`!Z6c z;IdX~;cdeBI8ac3PD}tb1~h+B9?oPIB`)Tt;#}gVD#`I*$lu+2wjb)q*~l??$~s(; z$PPTANI3`F)HN92*4heHR4ixu(Xdl83>3Gu<>id)R*haqpeuOD^9afEBqbF8WGP_s zXH+oIki&n+A6 z@3GpULleL~VQqzRi%UUW()*0|LQ%eyUM=Iws;c-0e7$r!Js=8ddYnGBt36o=u4T_4>j&K-2-e*e}jEZ`2~;M%xyt>xynT;%>wvI*@; zzd>CrS**j+gXEHCDW^tEv1<^*Ze2SIXm+!C3JFnBQ9%uh3=gNzbiDvrN;W5AdswHy z5a^AP7@nk_g~PWlx6HQa0EKk}yn+iY1cfcgErZ1)p*Su>?)=!chuxp;Q=uNzl&A#+ z+?WHMATIyH{=w`+sV6@rl;xrpuC4gM2uBrl!^4N&HW1ZDL@u-kQ z7B=T*EPjXiNS>;6o6mn8g_ifB6lL|R!+6Fj z4ysNZI2`+Z@ptNx>rzMa9j!qWbE{}GaT2xv&IPBO<~4fQ=Y`*&Afjha@+ZIqWv8qj zY4&@L4?n5&cT|47_xop>WX}1zWctJS2PMO=s%xca%fT&xG`kEN;DF9sG7Rv!G;@K_ z0VB!;LS$FilYofm4&G(Dl|1{+fz|X@pKX>AOr7gpfR>cd+b^%$yB6{De>(Y%)|f`& zxFvIzmZb~&bMHj-7(6svRjjKxjF8RQZC8(sJ8UAX^!Qa0lCmyN21(JC6q*qymHq&h zZu#)&BHFHnB`gpJ6w+;R#YQh9k(vyXu#G!7d6>rzOF9YB2FKHlI33+^GGl?Y?qweL z_uQK2x25&_A5dJiVVYuQC_J_Pb*t@@H3U4%2~BNXH2}(fA*q@YeA2rRVt7AQ^%-t) zQBOx4XKZN90oLF9&NM??^1X^{XOl06^{=j=(fWpq<Ws>2Q)^L`O+jFni=xEy4{{94j#@+*q6E1GReo~1Ww4T^)sQ8cUB>Ig8nXVmGCzawm5i-wcaB!-=xBDI^;>eKa`M@@cD6ms7P%KxG90 z)O-GQz$3TZt6Hg~p#lCIXHVLNm8wedRY?>vb}m2vAa|;=B%%0Wf3ET^UAfX9kEI{r zwgEVd{(QHIH|SV!$tioUKM^D#!QA!v@$2X+NzA9?6#zsdLsJf|LSd(8r2$YxVG6KB z&>5uW3S@~Hb zKB-JVv6HMrlKc;s@u>{PMh5{;7TOs-dHwU(KYY!dG#8n;)M`fT!0&fg@8+MH`28 z!6TTN3c5?oAuE4hzBn1Zw6oE6Wht1=@QXYwJ1YzHdMkL@g(09mxZT7D6=@||Hlq&e zfQnSR$IINAlVz+erujUdmBmlZ0&!Yx|BQm3n5IjTsJB z{w)V6M@ap3X~l)1;ownuDr^MW4!2%0(uK^h!d4c3FS zNFojJ^(5XjVLv;X4^wb%0O7Q+0*FxM57rMzVt_B4CJfHUWL8K*6yjawCsrEWa*a8h ztb$Ec^l-x|a1j@@%YKbaR#@{VJe1B#pK3MLzRl)@_?gs5K)OM ze$WdJ^M}TFSNXtu5(z?fg{7ZdPKMr|l!W9v4F4>Uf=+$AmLSBxvB)08&qa2=xW5t; z%dnp|KpuV-xUS>=CPTC|khRQFa>`>V<9qqQqfDEA7E6_CaU<=H!a`)evSvpvH&HRo zhI&esRx1f~0cu#=z&jv?3-`Iok5Eh~N$Tw!m6sC3!#OMhUCtCMS~gae>zbUA zk-KzhNq|X()y=x!Z?nuX`S-Y}X0~Uhoi3*5ZTX`oWS@LpTQZW`L`gyv8il-&a=GO6 z;dZniS1v52V@$^Tb{)tJy>NJkwP%rY*)Q&&kYx-PRJ)`7eX6%++ z_%Ty;(dtVMS!?!zprp_4>+CXWm>P2zxr^$G-uNeZ-IKubyi*?5bq#&eS0T^lk7uT* zXVRrF1jT3a^$4mg=ET?ZtArFJsq9RHcnc_3z-%9^4~*U=e_Ie$v$42pomr(9RM=Nr zNfxj6fB!X2z`XqRBV&W2%nBjJ=>m@AI8Ea@w6}8Qp@n@eyudod>!W0a=mYvGCEnvU zdTs=s|5a!NyjFdh|4?Q8rRp|#%mWg5bp*Qzd z&q#Qdn;bvGKu60-Wl;Jh6sv}shr!CP#j4@DM&7_-glSm;E7Vh3wA}qU9Kd!kj)`eBnc_D1zu4yDx+W4CYf^f5(Ibb;0}i(1F9XWY>)l| zmXAw70IqRGcKH>HMi~wo>mWb%I3VKS6=7$zu;xdhXC)5>{kOT5WKdY*i<0f-H&K%) z+qYJv>cD4C_yv}c9djkTesswTCg-quRiaxHVV~^_h=L#fCh|6yy0vV0;h#dq z87h^;{m79eE#t+6Tl|m3%2R{9p}OXV%EB*;B|*QL*xwIB;c+!3ELDL~-uq#7k{7z9 zf#q;fbE2b{`{b^9P0pXEeP!=6S^Du^deK!2*JB|KZ;An*JvqSF_i?VXl-(njn__Z? zRW;#`7T%x4-EDXq4g4z}n%e&<6c7~tIguuUfd2HeQ#||J5=z{vjM#KtERx^+*1@4{ zr;Gj6D4Kkn>zf1lDJ^4z8|ku4W!YAM0sHaw`fcxk-krgd$M2m78PWte)D1W}PG++k zmgU*~I!C{if?38Jy$FpUyP&TRxalQ^lyPYW*I{x1ELl~^KY@3JX?m$aq$rY$s|%!l z>>9qW(UAK)gW)03GsEyQ``8?CZXo#x`TP35PORD1Q7KS}bW5K7L7_%RN7J>kwQNu1 z#~(BA5$bG~lX7xhOADYRd4tX%nWc~iim6|IQc@C?8l)VtdkbbdFCWZHj4Zhm(WFQl zHM(mwoD(Y(_ozz(#L!|#FeeLtp8q|{WYI6pjNJk-CsV>A!vx6d**Aoab&!6w#Nx%^ z7T%sx|BYs&X=^&KYD%$-fAfPb1Vs*3~ef?e#qk|Bqd(`*nvh`(1C7l=+Y8+Uz_yyJJY zc}V_(8%zbl+GDHW$S5B!fy$J(&~yD5!cd1YkYouQ#2Y9mO~ z*u%NA$=CU(FFN*ZMx-JfRrKJT}r9`l`KtP%dWZ+AGA}Hm;$cue_cVmOwKKpJgfc z4&C%`iaDAJ*`(71*Q(YoI_A7}eo}w$XemkS$UJg$t*~LW{tU5s(pYb>$`)~CakMot zG4WJ(1Bx=Q0J#gW2@K2Ynws#Q3Pc2nze{@iK2n1f)Lf44)z#G!YTIb{u~^8YxfkR(QqjNe1&egz&Up1#$1v5ikmxXbf6-3P(v*S2vFS@6}vpL;>Zb=DHTYTTecB%mI( zjP_QdnY#xI!$Qso32m%weCt5ge3$ETk9`uZ~h10fcVjUKH_qQz; zv&w-bWK?u#6c^lJ?KShe;m3OKVJUHv_b~K2duo(rrLrNm!;N$1Ycu;*_dgQ~T-I(% zN#(u2Il|6{4{B;^ioSNXL?}UMDjuGV=G1!Q*h|*GoC>s4Z=4fH=eVc)?GyP=U*|?Q zBX0>E)l>blocw=Y)yLoKdvx$7{9iy2YBZZyczOofoSqEc-0$NrUqioHqgPXsO}Cml zY}ZaF67BmyO`zCeZM>T=66muXi)x20KvLUQy5M0^%B)hrFsUjgMjjRtLMwb~Zhu== zF0{qZY_2IvnsC%6ngHtd;gFmiTp`CGaHE}q)=kUMpO1?(arfVlvTk@W)-Kkq%-Dn+ z$~hrN%_AZ0`~$CXD>u4kKo9GC3OY-bdE!(IeGitiih2FREI#wwKwBwsjhAytHMOn? z5kHG31t5n#&>an4;jH>uPAbp|KAZHaD&(fc(P&AypyaJvcR<`4bf*`mDmLw>oI%_l z8oGX0IVqR2bemP{YvW3{2eIw@BO4o=sYDBUq(!OotK1?VL-<-S@2V%#cb<%E~wVJ%HhB@{SM|mhn*E2+KND`4s9KPY^sBUgPU8Q{GcSpx)91`GZh_ORaNC& zw@0x*0#=~i6Z`7+%A>*BN<4)dju{eRLWtD4&o56~<3WF|t^C80wq)H!i|qBgVKtM7 z%4{WJYZuzsQ|7&m!%) zOZ%Hi3TaImrF~7e)VyWiKItm|Ra(1-t#@PS8hdIrZ%m9_q|aW2TWZ$j4#6Y@I5Rsm8W4U#PWWSeeV~gBAq-7T&r>|YA@_G%kULnKK;-&1*>tKw zLz9Jt1^9^s!d7nLN-(_+d#42$$9WQCG*pC(qvI@?sb~(PewbbM@no*P#bhKPteE{g z5f((Ml6bC;dqCR+>SHa>_p zUMiL<`$G&w39lZ9^s-3JJ|9NG-NYwo_a&a+iLKzNW;cf6q zcMYjxQ8%XITrwOQUbBEGTs^!dl;t$_$**gxHRaC1An>CAfsVemh#v0xd{;A&iZ=N` zT%)&335AEZjBRd?R#<>1F@NxDDrBv?y84X9HKF9$K$QX-lF`&4Eorb-W7lL5;5o!t zYHK+~|MD~9J@%e4M?r4Tbrve2Ahgn6Db_tqNC;+hCFaAG;o(M0h%bAd&6#Jowtl-O zXsaJJIv0hwzqNka;?0R@m6-auqP}?4?KQjL@8#%tf6b9gyNO^Iu~ObbNl_pokAN*# z6uASM#f1IgynWQpxC>B^O!Xp3szlwiry(Itj=4!_wH)D&<|enGTlj+&|EWUllA4+t zW1IFMWUpXeft2BwFh6HhXi(U>FBZ*~kXN7GFF}S_7j}RV7z&NbEXXu*;M$=xa3KWV z8-=8se}Mc7n)f*i$WfE$@;vxwL8cZ2&cMExkdSDD8-*CLg7||ZW{C#M`s&&mEvzl@ zX!sArez8bPTpYkcGrpfpuosV(%U%Q1Iy^kQ+;%7sH7u;FprG)3R($@%<6M~7iDz<= zX;baFJ^1J2y{A%ObI`Lbd4HKM%dOt@X$n~&Ndb3{l4Tv{nB@c@@6k*ub?+1%OWHYF zLLDyQjMT5B&d<*SND9KAEG)ntuQJCBbe_*gTCPdnL`pR^-lQZ3$iV`foSZyRBY6{Dd^M) z$UNV+P7JxKgBer%D~PZ6T-SGL=BcfzT40-0?d|O)4vtc1WN;Cs1I#9JN^T0i+U~pe zT{Z@$AkU6dMpUN@X)1s3Ie&B_1UPV&xmk0>kPsjz%mB%JpUF=kOVTsz*H*UtML%us z*RN~G{yt8AR6^G#3#8vGMr8*B`o^Zt;1_lIdfv3gTNI_0|DxlzPVZOfWDX6N0 zjwqU*BDzH8YK%D~%11$w6@vP$KP6#EY|ioiVH4wI<;O?qd^hDyY>x~_B9DOWqUbXX zoS%~6#m#w)2J2HR5YT?n^@f55mOv1*9o|cx=Q!wqvgb^V>R3ZeyUOpUtM8?!s2^G? z#uORcX!N3m6f%5QmQaP}fo@9}1`CKPfi4_+J^I1Q^>82q5!WuAIW-kG11bv6V~4z0 zKJ5C17;}<2i6u8dlNHqfxpLZ`8a3}G8sZ?!ceZ$zcPOwD4+Rd=2=<*-`F=& zZIiI527^onKCOY|k>l8uXeltv3cv7{kBKQ}mG&{^wXJ|rvP1eBs=7M245Ufdw?JUM zs%aV|Ld6n_@s#*DFMJ$AIMx;PGG8m zg=PRjJqO_ki_Bb&4q{P7ND8BVd5E<q`e2pY$3z*@{?A6}GJ>WF0MH8&6%u#qG$bg8I zE`+r)(ItdTIAXkMA6r{NwrF9&nXebH-P%g9XX?!>yk5GyOjEw-D&cb(d8YQjD@5+D zzlr9*}m&a|LCVd-$bFhC99k~whK99n*Sph5zE zPvWM&YV=CcE&;+T7$cGZX-!4uk}2<&>I%B*qS}itheDDcAHW)*zvB$k`<}}4tSIBv z4ZYO|P;LFq;3;psO)2BeIoX+WoQphH7-D^1hqJk;m=I`h!;X_*3XquH03&Jk=s@!C z?nGk_F!knK=eECsHeCcY9%N0jKt#FD1-qR;1?+!dUBhtl%=bAbLh`)91OxtfX26Sp z7K)0Bf?GThE6=g{T;=VzQ2NK;NWGVq6{DKMY-?}%A&+ybUV*{G{@Tan3?tgp8j*t3 z;XCA>C(b2J6O8Z?_w8xHW1?P2vIDUln)#=Qz0Hn2r9HCK)}iJ_M>aq*W|b6RTj50d zG%AV;fVmz13ft_z?DIC{!Jb2g#2WLNl>gNGzFNt%Ckc&pl5{B|%OS30yDBC$4PVHg zf7Q9_k~8Ucx!{YJ%d5fOTCpVtt2qD;0o^29IxCnf)+&n}G2*KPRXYCpKEJ}Wu-S;1 z&yY9b&=T70IoSR6>$T{4HZhUYiN(^et$Uk(#vGhHQbK=XxA=NxV5ZpbYpK_C^=Bq3BtDvdo-Z)?it@pBzDR6po{KC7hFaU3?szm&3=^SSToZ~7td zJb;de+uo-FabOKJV>+0#G$=vruT-mx9SR=Fcslh|c~@QjgnnUe%s~xf*te;2{mf`O zwab2-=hAJc^pl0%Z+t#B{U8_cH_*ANnmQQo-M%^f(STI(idswE?=lXcp(X0?L|O*1Y>SC z6+3MOa%qEE*lkOjBW)f!shrWJuP7?VS?^Qk>hEY)K1eV@E)%j_u#D`4P+ zg@rN+<2?oJmcN}#uOAp?Vv7E}efZv*V>XeXpEZv@M|YJs(aYQz)Y*WY^A=bY7Lp}? zG^@@q0hP|%yE=%fcJbkvD&hh@C~%S$I_ukZuLJ`?a31wtUzYydXTdSW=J-}Qox(8-`gC=mF8SXwgp=D`+c z$F3F#bXr=5?ktc07X&6oGWJDfzVtZ~X+e}1xGTWyZHBX23l|-_I=ULdSGU@oBm8da zy$52vbjQLwPGTBQ`@`pd{E|E#TO%|gN}XMhQEy&Cy)y-=^vEu*gWV;4jb0y`wo$Kr zCCwIvS1m|(vH}w+L(3vlh+4^jrQhGL&D3uO?Z^>;2uTk>W5Jm0*^|9~0ueiT zf{aC-mKK=ZA3nLx7Sux&=yA zC^_!n(xru-_hOR@C-P$eo`-=*pP2WxTHmYvP8 zX9fB6T5=HmzCf{E(qNZtVbv93a=K|iouyXTgQ4vlgKduK!^3vBTr~Bala*o?1G_Vl zsog#zy4@q)M192xE7fl(7FF3Y>Mz0jk7z@b{s0ngD?9FE@~zOy^69cBuGkHNPWt!r zWotLH+{m%Tjb5Bu!_?xVQIEc-vVB{&*fVDu?us?kzB-=q%g>6_e6eksfcrc3IDZ3h z8JH8@l<7)V+e0CLF~7Jx#V?PMMJ*^N2XrS2sD)Ke0)00O;byG&gL8O9#Av@ndvhn( z##{MjkI5Ic%bgY1Ks+q-M}e(WC=`rO04tec&2(MweLZ59>Rq$7m^cNH6pCh5H!gXM z_dvD)tQiV5O?cSqdfS)Rvr4lYpF|U+nQf}Z0GI_N{9oa|f$XdT9>B^$=g2KXOSQ&9 zk%tjb0ZKU!mv`?cA7eY_AP!OkX8TjXNx}cK z0NzIRYaZq^VP4K`@x|Y2D}gT0&%W0#C538{6jIqA#;`0YoCmBBki32F`*yENMYyTW zWOx|}gaKFeM`+kPWW-InuZx0Q_HhIf#5VWQnsZ54wpJS#W8R(k#i1~o3mKZ@jhEK7EoooQ|zH&Ufx?Df=ieBg)t7CeH)t(&Y3s7!CFN z|2q5fcqrHR|LL@z5-EjjB^^YWtV5WiGsqq)WJ|J_CHvl~4n=V+DcdL-k|KmGLr9}+ zhoOmKkUd+Bo#A^u=v%&@<@b91&VT3Cc%J*Y@9VzrYk9xl7k2|4V$>6+MNe}tEA9E5 z?+^aH!aN7x-OsxD*kibZEHHHU zqO?EY>&z*-j%=~~x00w01v(}4el}4%BlDBsTs|y2gp{V=oq{H4}ke z>fk7FB2~;f$-0ti^D8$}feQ^#>LKCN6nDNz%ZA{aJ@ds}S#-y?FVQD^FuXD}ArEWyV_$6_|Qu~s4eCfhbdgSqN?2}5rM~-rG{&Q1@ zRap$|pFcHC4`mml`R+9oqg*nI0i+)!0&BA!5=Fw?mtr@+m4rz$`|!>-SjEQL5^Ho( zM(ksaT4GK46+1gM6*85n5*_y2?PfMv>0UXJcme=iH>Ig6GCmLeq3E*wp{D1fLyB+E z9mhT97m5YH%!|jr-+UtlnGr43!{MXYIL0OED{}agQq@D|x}~3_41-+SZYSXRa~@A~>u7Pi6*LrXow_UBw897nb%vLYW}cHS z_M@8Clv-g^2NJ)YXDxcCvi8ze)bA;Xi)Zg)mP_{*6KCo%$Ch|CIePX7<*_#ma{ig9 zrKjP9^+}2qwl)wG!P-l55s4$8$Mw`xT@A=b8sxPxjN_Bn<W>^BLzqO*4c|;QgGFDnz2GZOV{<%vyVr(V%R*t~tpK4|woiL}| zYT+3ador96lJji%&AxyMclWfp&eD7X$E3oY9Yq?#(|*2(uKOkLLa9q<*l)s+JFkhh z+s?FKF~D8?Q#Ye!>X!Schw&`i{T?rW&u4;-6>4vyJOzW!^OnkJT8+JC`sZ%=K77e! zXSq;Rk2R|AP4pwp{q>=GeUFM6y#tFWTp~)W)5^USr&Gv70H_Z+vu6vGSb(+vq31rH z7ATsivnY}^mjc{KAO&_^jjCPfSWd1^zEjee6Hp>w=sTMU3B=uhPVj;SFU+S+#$#rwm&-EE9^H5Po>sm)v|}m`n|E>4 zMX^9CXA8)tGy}RmnH$2cnw`P-EO?w!CPm!Nx~G)bL#t*PfAow zu|Kd3(;t3HU+VqPHJ{sU9=MXvdu+$eM%$?x9Tt^|yAQXaNXbYro6F@L*gW=hsKhMppe6@U9L&CM2}92^ zghKS&Bu6w80IzPGSquzBBn+jhr#Ea*)KTP3blZXAUL}dvpRRGx9s`P$fLfDe9&-7X zc@?`Z=tk8Zix1^JWs_!hfvxIWG_N5)zc_c838kfvP6~4PdZ#?y^2F;Bk@9*-oFIvg z_|)|1g|tq)g#*JZzsy~~dU#@YSB;@Gqd_40UeSq#I2twtE0-42x=xLx8>t&G%#NiNZP$90lV7O11l ze*q|7sU*c6vVH)6lEp*NOO`)cv^PSK_@Y+&L-#$JT9u(suZyS;-wBY@(gYnm(}m3XP^Lvjsot@g z9H9{D;8eY|sy`ZLTOM2ht&~G*dt-OLN}Y|RMGnlPrM1hH7z?@GEGxQz8gYAeEaY

+tYc^TPUtetHboFkdyZj+@L5Mj~ zTx0H8po+j##zMB}b|9KSne8)&hSsz*_7Pi_n;oN%;A7BaLA>DmdDg5?5_M@CXn`!@ z^GPvhRB>h#(oGsmRX+aWu{d3~tHkKk=&!+5bQi|?Aph~k-m+y{lk?nV&UZtPwZcte z-VS&NIF-$Zq%C}DiZmcfq8_d40`>AK^5qw0WG-I*qQkCSr^)u!Yf$6(QbD|@LW4-W zRPDQKeW6Ov%ubTGq0D&@9B@O2S&ChpPdxypCAFdeNb}Bx+f*GmAHzjD+v*I;q(+sO z|GMCS=6L7w!Wb9{P$rg5<(<(jtN&jur}UQLAv2#hf9C?#4cs!4922PR(B&%~Mg{W> z_~;L3nU~pR0I3?*^VH6sBPfgt?%n7M$ll+)gf*ILJFyF8-Du19c7A>_++(HnIw+5Y zR==59xYbxfqq+5hpEIk-8BU`4E!NN;zIdEs!&T5XDdcdUaGd{m!<)9dqs!x`kpqzhZ#zZyn19ox82v7t17@i{vfvG#>mzyO0>5&qy zBh^#+2{SQdMY)k-c0gu^B=12G2RrXgrc4S~h}O^wTcQZ^qiiu~Yv#qMKYgn5-yX5@;N#j|-4q>bU+%tU&B_i3a@> zU8g6urme~Xp~1cD9%eUd|8%0xSUvs2mAyevEI1ee zE9Vc$Y`LM1$d$;>2RCdh|2E{1MVtW%nc@8Nfj&ofBHWd26VqW4$X{%w+G;skmNJ(yP52ikzr)OnKOpXOVW~hv*U1u~s-nT>MsVgh+@-20yF0BfkrQ2|-^NsOryQyN=bf2of|ISYs{AolKr z;#OGCTxk|Ne{PS$Yn^d$nzE$ zzf25}^#2xmP?V55evwhG!~uKR63sDqyy|erM0t)VAv$wRT=Ui`-Wzm83q%&w{t7m? zk?0a;Jx0Xa5a zHvj+xfXgK_ZUUMC2AL+D%s>GD|fJzQ?!JRUO(9 zI9uFF1a=cdn?6%#*a14}NCj@{jQlu2T(qxgH~&gh-}Kl%+V2+(Hs#%&9xqEvOQ@X` zUWd}6m4gGw@f}cxjgpp;>etCaKcXR?^pEX1+}?@pw_eIOU>62cw9{Nc@DGZ)0cC;R z6d{t4ph7meG*1@_`8vJOQ4BX?Jfu7f4LO*DKN|4ApZEjy zdkgY#K9NDm_!!8t1APGY&-AX&S-Lz$0yh_H30B{Le+ZZcQ`2uDUqpg`#Eo<|;9Vsx%Bfb0(}O+;?Ny7J)!#m^h% zTy1S}0ySU_F2tyz*jtm#v8zTgW0>a;nQL=2-^CK8h|Q@MGbxBP*g;VqjiCn~z$+ql z07#Z2$QvJ;Q{Q)N(+w5SZKPZg2XJ!{9+TIKcAIbDLfUcazPsJV62#&6FhX&CefX0d-vK+*pARP+2yU z7_dFMsHQyDGcgC{W1khqEGUiw0oB99!_5}hTJV4Fcu}>z9sW~GC-%QB;6e_E2AWxx zSrot}SQO_D?YIdMKY(Kigrk7=%g+b0g4$lf0h@67ylMud>|?Cp47+yqDgsn^`Eqn@ z%naZ{k_W*GozNWZMeZ3xR1zN(%6v28gYXeTwA1vnDAdt>=DWBn0RDm6kkTGR=@N2p z%jZcLi)#!ckZKMdC9G+gdg#KrjJUoJ$Ux@}hHb|%J z_=POVL*is+#wDIrWI>%r;^-v-yCTqCM2-~5XG8ps1K#YOEfyTWNCoY$3*`-Rh1-UK zqplX&PV_av-8?ktCdc12RF1MQA2Ti^gtvc>@OF)E%e9=HsV8HMv*z}M&hBzN8%aii6{$*p< z{GtywcO@YANdQu>!8FhV%92utu86ZnK(xXe9-0i2KIhf@yaU=Jf;nIGEDLA?A3+~Z zkL3VeHb4>L;N+ppcT%YmS`s1rw+Po!2}eMx8G|KWwYc^&H#-|9(sQ7mhb)O*`c_$0 zRb^b@Xk|1*^Bo7Z7Oqr&+R5!n?bhXXrqan;gl3k2Z<|eVWqEni#Bu)ymxO>a_^*>I zm230taPf)tu*4?e(X0p8G)NiE!lecI+yfC4UXa5rpzgkTY0rTbvMQ$*=mKiJ=##1Og#~eSO5xfNF|h!m zen9JCwvEvNfPh12KBo9QB&zZ;a@I!L#F~-NHR8n2+A&rx+>3A=2QBl%aP#?ripwpm z+s6jXw(A_1KsqYUI<+}l<|u*r;YV4EU>}fzNO$xjJPg$)ORDWvU`@xpp=`qFAh2f0 zH@Kmm=4!#;@o2Ly<2jLI^6~Kob4?`x(O|*=&#!?#`)1FDAR;01e+4kRh+M^Tm^X2OLK773zq-lweC{&a-X)KG0qskL zsj)F#&H(H4Cad6SxfCn70UUyY?a}r2Wc0`Q7%RY^NV%Qx&(5|5QpSi%-T({ACTFM# z)s?WjNd*p=cf#Y?Bt;$uIS;UYDWBzMQlBz&-9L7eH1@X;@Pm=qXGJ-6xIYoAcgy!l zb7A8qj16Mt1$XTSyvMw0Q!16{isrV1OL)!~i4kP3r#_>JP5qxzhl^%C?LZT}q?NRC zatF#hzRpD=MB3DI!hC56E)89_aTfg)biS%!X9Tbt3j-mTk|K%sv5!Af*buB>cM~r;UdwD#7)Cd8;!ya?#)kC&kw z?8r}xzG!lBVal${@tUw~=C3g&(dBYOneNX2cv20Pr+g_f#nv%a00*z!?bPo3H(UDN zp5a0^&@Mzsv>*J)g@xxhQX6+)ga<{A(mb5px{5M=y~{_NK|Yy^E$#c9&+roTFIt>5 z>F(CQty-Bu$$Wik>>c|4uDr3f5S~%&o4`vTP2x>UYWMIZ5`ukaE|VZZ+HF1MCWcK4 z-TLjgD)>}c9mWPF868)y5ghw1NiLdXEC#cu5)I+sO6Ma7xzUBcPNfcEw4MH*60BMo z7@t+`doD}bUs&crV35a~O(mpVfh|upV*|wN)GKeiaZKK;SN}MsAsi`s|9(%l4^E0) z0aF4BD}0;Y7VLx**SxrnIAIZqDnr`}}|4fa$H?GVIQJlBqIBv=R-{ZV=sTRJ(7gM)Zq1+e%)m=wk9eWXJk2c!oPVjQH_1kz z8L{5A;_9RUG>~ZF|GDSIf9n|m;u_FT;waSepq0jvw@81AM|G<$G7$XjYKx31JNUO} zY+wM;S!4a38-9;K{(kz!f9z0k54GC1BmZn4(!)Y{?HMUr&|c$v4~u&sa)pfJKaM_k zzc4Zk_5a-9qw&Mf?LdBRozV*VjPR=U)*tJGk(Rjq(|mzdAWcNp+Kc4xT^-^14RhIA z`*U-WtBAAmV>p{uJC;E7jXY%S)f=7&I}_&VdoPpIJCW(ogInXr&*M)Z6YzccjL%pg zOR(O1Wc|4jr+%6*aOHl?*ININ_0g|4M~V9R*BfScgW0Sv zZewc{i9dG0Iv!tJ$K3t?2ayli(3@q=pg7j%WkV+y*wFCtm)AbtT0{@AzXuy;`oCH2 z>MJ+?e7*h3nu)z$HQDuv&OQg`_P-XkZiAP@khUw|Cx647LNNB@yTPkLto~=4&i#w+ zCp)T5)j$k*eYbo!akMHjHR~px`@tMp#`T6akWl$y1Z$(Ny#Rs0zby2c0j&+7ar^4l zS)Z<`x5y*b`_BBk9a*>K@K0m6=daq%%%0NYyWBoxxk+OG2+(K8+MIGAH44WnAU&kgY*Bi@(rK+Z?>fI znjx+qX#eMHUtK_qW#iYrP(~JWz2{DDx(m{f=s!>Xy0x$EDC=FTyXd>ALjRbb)@9uk zUvVId_5GFqX7tb$;>Y{{OS_}BZ@p^016KGyEZ>F`V9m6$44KEzsJB%K&dHf<1$ZQy7@m4zZZZ2 literal 0 HcmV?d00001 diff --git a/python/gym_jiminy/unit_py/data/cassie_standing_meshcat_3.png b/python/gym_jiminy/unit_py/data/cassie_standing_meshcat_3.png new file mode 100644 index 0000000000000000000000000000000000000000..3d21a3c6ee370ef9770039061dc83afb946ce805 GIT binary patch literal 9751 zcmaKSeLU0q`~P%Eby{7;ODM7;K%L^g8fl$Mzk{FxbJNOXtp9346jCbSSzy5xj21%$6{Z{NACKk=cPe4(Y;XJ$E1BaKV$0Gxq(9NQ8^M4Zy4vZvn6=) zpGkJ?dwd15%2&y7#qO%FfJqf5q~&jd#po;{5inSTdB%Y%780=@{4eEf*hbhkll$9X z`|SRDRtkfiZE=x+ZBTu*eJAYn^H+z?!eZ=<@4#S<8|=W(g7}?gz65OF;~)0JP9M84 z3WIG3?9~MSJqT91tb>D}kpHZMZRq+U3)}YYsRj5u0#Lm@(YOvKeJB>}by*HjE`7Bx z^nXy^!`%X2Ny-4qxdCAPF0IYrZ}G7npUDL~Ul$We7ZY7wq$u9$trpnc>c9p-xdD*3 zsjLQD-+2UWC4K-s^|-tq?3c5{RRVU$QoJ_*ob)#;O<5AK+bZJos=l^`!O9^1y8io= zt4w7Kd|L!D1)YEOjfPkz@iv>msZ+K9u8tXqAFLi#Or*%`4WRmWiZmdwNz6c>k$CH5 zy>IfmyRrjz8V-H+-PRD-hk$%mMF*X4b?X?h{KP*+UJj;UufL$ZAkw?KVBZA(uvOw4 zm(W%aedrM00aDNCL284vep&nhq_%e!rvPtSwd;Xy z*90UX<~q&*Jgi6%>k6_8l9=CgXwm=83iM`e`KhU0-#&+EihoLTy2V7+j`#S|^f&oJ z>+M{B1Xc)NGd;-EAW0N$bC!U;{s3v=;ux@#@65tOUTnM2DOb%*Y?0sTZbz}$_zy#5 z*K8jW)w^Fphns1gXw)t{P? zLK3`<_!6J&-nYWkr;_9c(Q2Yp3})eV0ao-JhA_U>BM1A_(pU-+#$qvqlW){lI11_l zXF)WDq$Bf;s6>)?T=p?sM_NK-D40(^!F;s2h>l^yv-S?ZoYEFHs(K2xz$Ow!0>tFC z{BpQdY~xf!39XPxq%ngL9!gkCA9{$+o}S>SurRyrZ!|H#KG^ugz-@O-Md%2V(p~MB zH7+G3W!hEgN7pjtUBeb-I9^f-Mm=W|3CwCgz95=jZDcVuH8rq8reJy~TTdUk><#M} zsHF-N$gv8c?4kDgIy^q-@SJ{j$(HIs6YI3D3_*9#GF<_n4FX9rF_*rsDe6ERAL z$U@e57WyUzLm_D}f`S9Ienn!NKFxgn>eVxENMX!Ob5P?HzC)TYl|uT+kQiEWtu-3E7>@+AGj^nwW3CJZfWd!BnE{-9s6lvS-_6wkr?PD^Q6SO z$s@6jGeHb~P+t)qFDoZU>*<*usMXAF&v?OH9<&wp`2>!8Vz{1hO|Dq?Y~6^Z_Ld)O z3R7_*f)tD`40ve)yLDQrQjex?$Qx+KHRa~!>QfnEBZ)L8v|o?ci7t0BRjJrB+D|`y z86@&j+-oZ;G?(2#FKM|x*Q#2wz!zlmYqOctfuFu|s0K@4LX#$KL#eoa_U1ny z{jlG^-$`espW6{atWhdG9RJBbY_v7CElr(4Mr*f~qasHXDiVKpygg}`I@4SKDm=O6 z8G}t-SC#J#HnuWOQ+F1AmZ#|8%m8cs)i|>PU}uBqETutvb3IHY|DCt+LqjtTCZpr1 zr>8fV5E~ntb67I=jK%geHOJQZl|Ikxy;~%$t)u2M8Su6MH@95+#a>gV$L7w1+LFrgaqr`RGPJJj_({LhTUTZnM#bVWswt;P1iU3$Te&ZH1lYpQBR5-)-b zZ;K!gEiXqPvD&Di0R}^9i{wtk@D&i8o)GA{=1H;?Ypi<-jmhIz{E8xKS<4@ZTJFk@ z=5*V#2Wl&7Yr~m6#cs*+M0w?(i-`o%z2Y`A(}FH}=g3>WzJ+@2r3(4oWnhL6<8AJ2e3CzeR__jX+HNE-8T`r2k>+^KJ7n~Yyz>fopSl+M@%V>(Pw1ecuklyjOvfUzj--&Ic^~(# z8yu`nC?sm9xQ7P?UBQlWxm=(_nDL#47d}?BeccC>$Mo7gr3Nn-bg2ap1IIh^OwxL2 zG$wI+xzKC~W#cdv{iHp_TqXGDDk9DC7_ECN>5ff}MVaqpYx%nmQcsRVWi_bmE_tAw zd?{<3>{Nos_r1dtPLVTZ`wv#;cX@03xw^TH6xR&xmW?yICEDnNZJs=vhcqnmqi1TP z2t`Hjl0p$ZlS3Qr5R)A+3vnRGA#o!t-)?rhCN)GW=tZ?jVEVj708A zYGyK-adB}K``OCo9qEp2L%Mq%m&ePFUY_7FFqAgOyjp2^-bd>#R>t93jQS|OM0iw# z%8@MrQfA#86H(9dPB@$fWFrrF2zc6fXF)L45a2(?Ag+_y7EqRI_ssrsk< zCqrn4H6(8Bcp(Bw4M7dn_2rciH3R4L**w0gs%mbh7i+F6XsLgQgn3zCUr#0*q+gbd zZM-o)Tz0I`k4`8flcI%pORm3ZoSsHFAdyH12NIfhQ@){n?mF-ajBqlvpNi{bNX*P0 zXju2z&y+&?i(TKP&r!dzcT0Ya;n$4G0@fTjs+BeP=j-cRb93-W{AZ3}UR8BGlWuB% zsf$JV+W!goI53Bd{9TFX=fjJTEhPz0h{;(rHD}ct(P!@6!tO60ru#iH9)jXY0RnjU z*RRk0=q=YZ(l1Ati`o$L_m`6=s>nfv&@eY`zq&}@$g-7b+-y~@uqR#UCxQ4KWK^?~ zvBISwf6`ApSw<1NsuK8RabxG?JT-LWBM3KYj{Uv8|FoH)tkbNFRjN=JR-qso6Bt-Q zVCEdg<0pS`Y@TMEC=MNclky>muTB8(se*P&pPph8sbZa#@yP5;cw77DeS-;4)#_$aWz-`_xk|#O5D}Gl z@oRmP5lQC-30zk70m8e^S)wj=C$$pW5fB*FG=OdF+9HWYqmft;Qdw+v34xHG(!t?! z6LQGZ(xWlW))!qQK4rZOdSMWO0_%V+L_2w)MW%@l+A93Bv7@v{;G(Z{; zCwV)}$LHwi>Q3gLeTJ6niQ=5E_T9DN6-be9J39G#%)Xy`*SIvhxp|0D%{q_b_1Xt5 z$%}5XvxVkt4BG+9Ck{s~?t7JUI6mj);u58r(?toGip|D+eojEocMVw?cTH3(Bvb(f zgIk&q=*#^hF*39OnXuR`Vfa)^MmnS(bL`ZUch2b>?Ep2q=H;SUpf*0+{6Z*GX{;=3 z@h*mU-}z#wXhrlQbNOpKgEf{i7G6J_?hH(`MIOUh5F0J-1=$e?Squf+*k?#xge&)tzKYZQ7W$ele46W#P!$eGLI-9AG z1LqUD!<-b$YT-hU4CT>>s7LH3I-_6F@Gk>WRYgT$z{n>rt&Gcu2E#t|?blbygSYjJ zRUcn>=lvJi4Wvr@)a1rUBb2A7a^6QKrz0DINRK>Ro9d3NDPVJ^=9O+yBS+GM{2yEH zc8nBWD7I%41STqZEEdQJ^tne>@;bd1hS2Qb^_6c&W>=Ir5#eZk#r0wEh|(A@C8sMH z`RVQzmd45np^hHRTw0DYWwFp)_*`9wJL=~^<3z@ESGkUc552J_kw{IS{DF<3Q0jSC ztgVgLtM1=sBDZtfR7>|HOAoQ9{e7a_S0{O+TN*W5i01vqG>cg(YJ}NwSbyoLV|u{OD|`7D zhu6b?F|cd!ew>u)(fZN@gDPLBm_%{ zX5bGtxc%TF(MYWP4Q=j7GqTV!wX*IeU+<2)U5vxw215)c=^#~1`$f;g*H^WD@1Q37 zRkGX9FvV;~V0WyE=in+XYYlb`^<#%;h2|D~xcVT~z3=VY^FB=(Pl?I?#LB*@Ygl)6 z%F0}Kp{?h^S88)6DqG_~y7jAAZOMAuijEZCRCP9fArmx7oIY|ZwsH6ipI%*@sq1qz zBRjNvLh$;Y_o#o5Cfm1%Uwzf>e&~KPnc@r%t)JL9iP(#y@Jl012yY| zQlx*kI-Y*n+&z4v>!o?#s* zPO;o!i`($n;=qQ_WW=tHF%wg8htO5p%B!lXk`KPJW%McdosZ@#Xg|zW9^B~Q2oDyn zEGcN;d>2tVL?HYmEqw=+{P%dv(@RxEGZh>HBkaKG<#s+dIaEv_WJS&kg^kA+=!|GS zD_K4vCu|%SN~8@oU9mo~J2Bssz8N^T_+FYAzR&U$_PiXb{}An4e}xAE0Wbn^%ZtXA z$Czvp7gNnC5h?F?j^c~>?ZEKdE{r}npPTPpZMbxIj_dp^B_t%o(wI(NDgG0+LFa|E zp6ia`CfWIUHrAYNI9u!EUT0O}x4;dVtja}2y4AB@9FEtgUJ!d&Wlar@L!)Y=!G=tE zVf!r0)-vK`Udl&=q3?DUVX=2Ht&T6ObM0D+VbWruipJP>S$l^VhpS z)ZaNz?S3Vz9j*J-1g3bJDN%YwIrKk0!3GL^;iAXLe#2!G2{Y^c7i8gGHy)uW40itW z&)ohshlC+OD&{`Qi1Ba=8D|$vJCxB!NKah)SrEwNpHJ z*5y*G9)l#{i0aT$H_{koQFoKvba5bm4JsLzdor{{7M0h{lb@p`7QNQNT`uAAy6>oR zk|0!N=I`<|P+Bwsg;X=)V{nwe|L|2$7w>Y+IAtleB3g3T?aLrTR6MA_I2AJ6&sagN zr+n@fjUe4WHW!C$4 zyihK^abN@XyJk&O*6&K|P3-O!1vmV#1G~q?d%A9cqNRtz)d__(OyI~Hiq(zix#MgK ze;MVeE&BR})5I1`JB9ml<}v)^Y`M~XfbZ}_$t|BgeQIGMu`CL&e}qBlUHKAKa32V# zCs$cXB!tO;DAiW6^iifshKj4p8egjQb&g))C#gr{3Cv`g)OZQOFq}0jrUxSK+>~Ir zo3AJx78F!jhBk0OPl^xlmNu>6GFUHcwMX8pTMSj42V{?QEK9^BC3l-&9umxhd?&?{ zUagX+PpyC#{*jj7H8E3$a(;s5g02EcOT05a`P*ULvF_H^Aj&;ZM{rpZJ5vSA7>+r0 zc~?x*Uri3E0b#Bv9NbORd3`EhAoSO%TQCuM58K|r2((dy#1o21ZRJ;y$n?vHvRAq( z@?n@5DUFuBcKF$zf{+MuzIQpCd9CQ=@{irnHf-Fc^Gd~ zHOwp<6n7N`>tz-<<+kkAQBdkQYNU3K$80QrFJY1=C9`;Z-`$NX*E?f3!s(H6SVfg# zN&79V-YjBoj>_+g5XDd7f+hH;)kUVqY zZHmj9NhxFcGEG7B2k9P-|B)UF2ND2%)ixXKXqhU=z8aMriq3@v#Cw;}92Qz& zx4i2!-JCOtG}sE{H}HM}KbgwIKbr*|(Cj!gWvw726bx1){V%5failX}Cj| z7Py3sEWU&fX|;nOu2xPhK{u^$wy*Nm#VPLH3mjgbT8Ll%D^nro8u-VUNm9D}YTIVA{8U^YgklG&30%dJg6QU%f zUi8>}>&$PUtTM4q9lfs6Qhq~UF;ug#wfw5rL3JUCjd34Pd2@wWy%}g8+_gJQ9D6H&co>;OAJ-ACJkxlYt51Z%$fkJ8R{A1m&$D z8pWEB!UU9UxndBZ(NP?-ZM#MHg#pBf)h(Qw{0B@Ea#p|(`BmsGNTYvS@_|KrPqmn0X;08M)Udlw3{orcs zM`17q2J|t)NMdMdkaaicYG~{z#`H+ErR3!tCLU8AOsMJqXc%^M@?mTEdpdEG9g9p@ z0 zi}%X_y_k0Vo$xFrMMYWpueY3EN)`T;)QrS}hko>vrfxtyFG|N?CaLbA8v?p<;-X-Z zcrzm(xv$;_(QC9g%yWF{?~1`-PQtEfq(A7E{(TfAI`Hn9l|a^FKnlz9r3u`@< zR$4s%wy^c*w50JS+#WTLSV^(my+2Ren`_m15bY1u}9p zxw`r!?y}OTiiBdUIDU2B9XDJU>2kLJ>XwiyZDm|Y6&B71miA=x3uO?yPe0fwYqwFy zG=XrI)l|3ipJ};m%>V(|qTl+AVhFxLzhPde$GGaIS9|BD+_+Xj4XQTD=s0S9)fNbp)xT#s4 z_N5?0qcGd~Q3Q#nJyqLdBT%dzYHB^BM@e{JI75v?__bMJvwfm_V93p5!^Hbs@a zf8iLZ;F<|q?L_a4Mwil=0@$m=;#hCp&Ec` z(Lo9`?ON$C5!iQWp~##bCDE)B3cgqtx9O3rtZcM^CN8Kz790s$%zN}(-PY;r7H2n< z50cTLfq{WKdz@+mM)T5~>=&Lj9Ljr>Q&f&8T&)cNP3N0-zZUM0vC{=@__mYjmqEX< zdE^$o8g#(@GVbook+UyVTb7I ztthj_&z+t9HrQggl6F^lEvvtG$Z@jOZ^HHil_|B(U!!LD&uVjnAQxofh2W z0?o`Smfm!Ff#y2em%2r}3Rsp0xNRlD$5?mJyY9QXs41r@#ccJMB$h-N6z=ht+>G1Q zFbDcNwj&4fDgzeA{rG)Gh95#qrxT7M$LZSap{Q%Y!ByR#WuI(}J^#DrjDU?1`IA7a zj?+YiNA}Ktjy>O{8cHw(m58_w2z{tlQ2BMAbj)E;+H21A2=fw!nNqCUxW&tvL!ys0 zPJ&TPN?uAqO1nUv!eFuo?8!m=$w5zNqCk@!`I^47jt&xd4ko8l(a;GXlN}Awhj zW$`zqr70?fi*puUNKi*I2KuQrPA!(L(R*xamEt^M*o%@fizXwQ1=&(QR(Ny1UQCh% zgoy$-fJu9t-2%|RHPG=|XYD^Q7(9QQ695n)z}VxF7_f~!{|yF)5a(48@!!xbgrq{y zEy#<%fv{r0_MMs-9|xi08&V1Z*lW-@1WFej`)4m~9~Od=*O1j@F`oV18NS0Tp+(Rc z#4UdSm9C+xyTkxFgvT2(OFdyRzd>L%gyKU#@z2CCFa%qdo)vBe+d|-K{4cM-ZXj>^ zhQ^wTA=iI{#}ID23eg6O(f`A1yMagnMg*YmAs`P^=b}~}E`#-sb&T`;|82%Uc*31@e_QvEhX0evZN(`1J4lSHvV*h>oftAO$kbPd z1RyJ4H36^ffd1N|yDDJo)d7oD{}GR699y#+BVPr8%714_tF{Xv`1pVOA~bOTky+Iv zwC(>b?f=ym$HaPFomzlS3Hjoxyu@QB|K*GSZRx914v@wn4U9eC14MmDJP)C{#_Iol zhX0Q%LaGB-50J+N@j%TgV=W*Qtjh1-MAya@)+S4K6pK%K_}|_oR=QoMv3T|c8jJbP z5d*~oDUfY_H~aG4))41we)!$c2jl?X&%QuQp{Ed+tE|#}KqR^M3p54-`Qc+pAh0!6 z6qSnIVKvx6Aq<*j`EGavioG_!1n&MelmwZmCM1_L;+Y_b`_*U&88@WH)!~=_%|i2` zFQK!3H~RtkBsBZtY78uLbr@%rvUsBAyOE@|5tUMr(j&hN3!`7C9$?@LcFD->9O10X G?f(Z{O#koz literal 0 HcmV?d00001 diff --git a/python/gym_jiminy/unit_py/data/cassie_standing_meshcat_4.png b/python/gym_jiminy/unit_py/data/cassie_standing_meshcat_4.png new file mode 100644 index 0000000000000000000000000000000000000000..eb7ed383f6c24062e116e045000f58e2ac56073a GIT binary patch literal 9975 zcmbulX&~EK8#bPzn6~IjON-9*(W zz3CF9rRi0~wqWZ5^<95Laj$F&dI#`1gmaWXtuH>mmQiPr*F5ox+4UHO`?k(RL79BN z#5VU=R8j&ijvhUzy|fg6#0~=aTho!6F9?S~-aq^kDNq9cpD%2ZfXF(#t4l$C{ZBLa zSp0GiME!x(Mu@trCiv;&m!gNh{PN&LAq3LA&lL=FKIk9{P3_^IrHb&y}qR6!uWq)ULGK71*D$gg@ASnz;IfU0Wp*r$DzzZLDq zS~Q%!`9Jq%D$v zEgnb-qD_C6@72D~y8i!hfvmIFWIlSwrL&U2+G30PD*s#bilcH6$V0J$)<~5q3oQJ_ z%&q}eV1keC@f+Ck$q$B`)%us=z9@8;&W29{D~KHJi!)W*WXP_AeEZ@3uM9u#v(Eg- z@g?q@wx=-{zV6DM*#;t{X$hr)OBswCn;55bRA|xeFEktThx1}WCtr3i;}}ach}rj= zM2SZFxm2nQeNkxay+R457N=E1S@&?kIeu>8)5f?)vQB3!W2J+wuzC@`#EguC-EgcX zE||xTH4r761W*kek+-@`^V?fn1I6H#XlRhg{a6_DeX zQWR6E++{}mQDirXU{!_SM_+Y9@cT&NDy9LmWf&+`fm3PV7mDIJzwJSkX0z_e3pf;}jR%!nNp zSNW;t46Jmn@i&TBx==6K#@>rAO4?qY8ICYvO^~m-{Urn|p+n83o|aS)v7{f5@TKn_ z68?Nmrpr;cPB-Hzq6-WCO5c{EE+5&M8!>XM zkok(itEi|zp)!c|QP)U1nDEA{0^G{*elwoZ5@E20-Th`LuSeRrX}tHKOz*8~L%e;% z(d-!3(9mBKg2a~L9D2-HvUcoMH&{jG92r6A_p7}e*)=>o9APp@rK)U_-rtT+b0F!+ z;2M{h@r(NALXx@ZZh6eq^z<|z$I^mB53_5PRA-Ponzrtp{&fd=^x2AwS~Snw%UWM4 zsWrw7o;_aXEo8bh&Zd(OUUu8N!{Uj1P?6(0C!@G)SB_=PMG-=d^-OkGpqNzp$~=5^ z9v)82VJt)}GW{zX7D{k~5&Pn8Z|uk(xM|61=csMBgzL7kqLNxK805Nq2R5B@16!PoeFwHUF`f4?`qWM-jZjPYOnY^a8WTZ!38{jT0_L zm^8*L0FBXZz2Ri*V>McqjaRR(K95}XgP0$LZjngoQO|MF9E)ru5{U$Ysd93Abwivm zDxYCzGV^zdxp0!=70u=$S7Tt5gk~Q&9KP_JjA!QS_EbM+{#jKVz{C#@4#v&*`FqFA zw9dMcbXtb1jDw%Jrup^RVQg09Am+cc?`x7!ErkYBu~gC}qdY~6s|9|{K7XXJ)qA||Dk*kf&tkJF{`UIZRAe*HEFD`DJfoplm-Ah+Ym4NFS}#cA1EO@zw& zux4_#AtBnH!jCcIDpTu6ODU{$KQ||`X`4>@;e`s-sp=;t-TPC|;2h7pT;oR(Dq9Gw z7_M>^-mqxJ?;8_`4bY)2?bSg#$_T!Vi_4*e$A|xBRu@(F8W|Wo1x}z(V}`m!GxE3X z!tX1GcCgv(v1tM4T?eoJwE`{ZP3wi>b(e?kzZsP`Icedwd-v{8Q&(8k+jO(CFD2QJh$8ako8~YDp|Q{`j4)s@#{<;dDtxvM9g2lx@6vc2~#usHy!9nq6CF1 zCQbSrdH=ts!WcX>Ajq!gf=zZ-PK;5+s){B z9E50_m<)B#9LeFQ6J|EfY7N~7H-nU(Z`Ejfgs$9|Dt46kn7wQQugkcj|M8M;H?I;$ zh*{pIq_+C^Xm~tACwmZ&2-M4wOKc$@cj+h}+b6&Vcg&=-w1u8llhe}_ZO^BFI53$Q zFEpj%c-V{+EGQNeQMxMx+2$=dU05{NZJ<6-g^w+a7@_v@?67Dv-2r+q*3rs|j7Gig z>FEhIVmoiDuPg=Whh&ZHz04_ot4f$h_FwbN@FUWZ-Hc%B;lT23*}eoX^b6hs8$OSY z8Kq9v>Cp#E2Y2%K)9@Ds2E$Of!=6v4hZRhD!|y_@!bvf!^B3mYM`uS!+H_@;@cq$2 zE%D|}3Z~yEZiXL;_xF#!c65&knTkeTHl_ws^~Or|Ipmf=kcf_DK^4LAR_RTQbB!PM zc~a{VbVvgS7dEe&BD>Mv#6hm0{+o@7iHRlkw0gzLN-GfWS)9fh72@ph>SDaXPLosz z<&~!;rd+F^}m8k_B+_lN6-$lV`liJ z9$HA};XT?saIS@h)?hHHetkiDIo%Auu(UTtX%6rhza`)J;fl;v`q=YV7WSb_I@;&~ zr*m!@>3&&zIueaN^v!A?3~-XskJ9o7U-nbkJw487inS)2!?D#!MWL`bTqeRJpP|G+ zr(m&nt8F(x)!j?m_Q+DshGS0XF?DgpB#=JBWHPD86{Hh5FCt95po;o;_2~gwL#!sCsA*DI!JI0wIy*YdQg!V)_)-q?oV_n>>-lWaH;&hd3gN>>6kqfh9HPt`Z zT9xK#XWwh{MmSMggW~yYLYw&lA@m?o5R6KCI%`6ld&h82feUiR-rnK-DA2ip`_>Q% z^2N&-Gdt0hVz<2TyKNEMtww&o={n+dJy_?lyaE-=mcHAApvf&vN#DxHk_XPPi@31i z=OrQW3*KX-$!osNBwuBa?5J4%#$)*T0cPw}5epNd`u8{BI4~THt#dnXHF*-t(38Cd z>Y8Tk5?eh-+w#bxk*LQW7>|1{6Ya&ER^P(b-;xI2TgS6zl;Vp6TioY;5kxZKaL4T8 zMsxmagXr#nTuv}DFkjf|dupE1Z8e`@YC-<=Oi}WL^Wmc5#BkQHyW1#$fXoenX*f$oKDu zp4GnQGn~0T#;uQnb+q^O~%+Y z-79su6yeiFJc%n%P*CWYq_*^h#?QTB!uii#4#&3~irQ^Q2F=sHW(t& zeCMW1n7*zqTmAgY{Nk4&d zxEH0NPzR$X6Sx+c$kkV4409f5eK$UkjEF60V&1t_l%8J|+VJqaRlqsuz&AHREvN44 zNaxo2qa)UclQL27&)8x}Z_qdS0owwFYkw)dE>W{n# z6EwP<1g8`@VYRI*`+~v>PFyxa3ZA>YB|O%elvhx2Q3zY#LoRcvS1QBQ4j#gQ#Xxl_ zQoZ36KO-qLGC#b9L~56sC-drW7T6=>y6fCvEHZc_(|4eL|AzXpj`L;&K`lh}+%AiR<1!@!AzhNPVU?9)p0x2d(S&T z6JdyrVYEAj9cdGP|Kc;X^*k&nI5;@3(I=llYxx~^ksO?ZS>9lel>f&bgajxBykOdv zd!g24V^#yqD9`XK{c{CogkUPLTPW&x4|!#F@f8FzdSF`^chA;!s-O;+4RcLLz`|jp zu=SWtPww5bl|MCs%59P=3&;l7U{V`=u%V7Xpy}AaC}l;1R}6BYcOToyOn@u=J8+eo zigbVO;+7#NodC}Mt1FX?71dr-G)c#XNJpbkf!DkhUEMNlK3lH1aw9WT6XObP*C=l+MMVc`^{#j6@H|v;@2Xm|*+a3;3vd; z(XQ5c9GD98G=up#IXO`fZwWvDqc)JApBqTt;c7zy_jdBwix5_RLTKklRfD_w&tWyd z6ZKcDHNiU>W54C)*KgzOGB%wq5k&3x7_a9Z$vSIm{?cIQrupoRpY-TeN2Nc3t&qXu)C|l zE#z!f#t$WT3k+z}VDWpi9i{i`lwwCJCW|UkBVA#X=;&xzVzhf!L%Ltzd8b#@#!gwW z?+kH_U`^zRACzNDi}ZtWSI^MObG;m}@o#w{b!#oUa2E z8{0r1Dy4lNEGTTn6VzLecb25hD<$=HVMvoi)*XBPk`P>Mhv~;bghZ5vN2qzR+`?hRU!=L1LU$o5#B1v~gaf zRVfM;qA>p0&ePeYBV|HS%F&8$WYkqQ8yK*ge-k43iw`ld12sb>tFWcz@kVDSg3+%J zNlxw%6<_U>J|ujb0N*7jEG#TIa7l)Hik7696sf#B6VkXX=IlVrY_=X_c`#5^= zdjC`WguS<#kK9)1P@)xeW3>8~p_}O|ZZbg*RI1t4N4sH%PaEG96krEzdDJq?yRZKv zF!D(SmM|aNRN-3qh;Eu5&5im_>!G4eZ?0U^MYkZUvBB6 ztd33IWlsmLdK=aoF7|etj`G*_fF77$35vOG8_LLrbS}xFNv4KvDnNj;6ZLJSLY3-z z#VW&*HnXs(eNHe60;W(IGdGN;6K8{PiF4oB)R{IYUx~e;oBmRHZWH6P*z$>#(M1T?@|X2N z?)KYN-lzE?)>lP>J}X`3B>a>>_V0m-8=asO$?3_Ua)pNP7x!z_DHU2bt3j?PiW|M+ zA$p4hqcoTr6(x8@lAmpUw6i!()qBcpmMb;=PrD^QLZ_*}t6|HYiwWH+=Jy>I`-IwN zUU^QwhvunR;h^KKln{BTrX|p{$(g_5F{a~>yas=+3sLbuD|y9iF!f+w$*1|D*ri|Ok)IimSmFT7^)?}9YdaNw>NI()W{7=5{id7aCT<}Jh+><*)F1xu0n zISK279;iZnF#Tx`C=}|zU1&!?Hm~#2NRm?bQ>8=K%b>Mty|tkCUrchjgmJ?iGsx)# zM+fHmM)eG-jRrEo)E)%P33xrL(Vrj{$X^Ux?+Zz}F=#g=bAmFO@6g`;p#Cq)hWBwk ze;QZW2Ol*%TKq7WS{^_Ad-Us>2X}OzS0k5!Q+DTbAe-B_?yU;wnr_-Yw&hVvdq37umF|7i7usWL=n6tH zLlhAty-pc=Qvb+_!eDCLbe0V)oWkWtMdrIWk+E!bYYw7G<4n~Jxj=tR`2GrQ#iYvN z*tf=YkzJ+w6*)ddE3K2E{ppUFz9||@-)80~`mUjs164Ob`^luE8egfDWMNeb?En@G z>#JGZKD>+44dg+g>Q{V@yx?I@8$(WM1zX4louh^&B{(@1r7a5M+%h8bkyo{&x*yz8 zFgj}OhBLLr{baCPo{H_nyduc=0u%(;f|}t6x~yXzne`Rd`mvqW{O3B4Fx$#e?xCf< zpfWV#^u4(OoI@krr||AOT0G@YTXL9oLG}Qz;pYta84z;C0eCCUL!xmL9z?`xKeu+C z2?1AtVlDozF;}~-+{E0ia?IcM==xtl$5#&($vt)FaHG-nP0m&4U6@{7=HS;<$K=&>mscSK87FC5RM&XmRfaqCYlMgzV;m2Dr*@GU~ zVR4@kNv+&sryF?NRTu|1L;APjS(MJG8Kv(x+i-wm1lJP?Feh>~B)jtx;rRYK{oqWW z+Rj}z91DBVMI)I_yFVFfG_Ah3%55vurx1ne@9$@7=sp6LFJ&3=59bQI_*=`ACz8*=~b6s|3)u3bCFnIN)Fy zRw$_lfRrG2IHRS^Jj8Tn#GhDVYFpLwI4vsEta{Pc5FcYsmsh`G2u{R^KPq`kSv7x^ z?J@9vt^-jK3{q{WmG%mIQUZSTPY(D|(~rA{*4V>e2jGw!YMa4{E0cIsuIYJRBRe

S@3)NYzoZoTQMw@Xne55T^U-`qbDzaO+HNRr9rteK59DCcVY;uT<=* zs_=AD<<;4j+q&X5itgFdk{8%gWtz`ndOeLe>K-3o0Mg`O7hS!n*aaW|WI?&SGQsXL z)Mo^I&j`+||0#O6cdfwN*R;t4qI&N?Cx>DN==*LTZg%&z%e$9;Vkib6GeMq9`R5<9 z25$Fb*;~u8rqTaQybP=qDBk#9w1Z~hltskJetLThl{o_Szo0{ccQ zWj4NV6ld}t&+%w(v~%_V*D}NJjImRBM4aIbh$tve{O*(%kzDqx|R;u0Su?`6DXDmY%e7royG z<8aT$i^xUGPG7N7(3VsQdxs@eKA~NY9!MZ#S$Vl{t_h!HaqC{MQ_&F1slWlRruyXV zJl3yFf&_U+&YMfGJ6Wr#YXeG?(}ngR`4&5L&Lm;%Y&DBeC@~BYXmJtp&;;ZKcPbVa zLSwqq(4KY2JXxj!!FJH?AFlAg-7T09ER9$P#!7sz4w7L&YQjr@GhUX8e#l#d@V0i$ z!+`$U>>b${yUBB++C*FUM!Pn6X%V#Emy6H}s>>Y`Ccip_$OpNS-m0y>Zwn6#0|y8S z^`cr=Pifif7sU8W8!DJ-G}R9DI(N%^ue_nqCT_@qqBy8ORL>ZscV0t4c1uf3G3>h> zJdz;G!W$YHUC!3%07Z&kUZ?7cD93|PE)I^L@UN~Ykxn=Pqh!WSp`FKW_i6|RZ>x-v z%&9C;S$omqgWkVIUKfP{xUB>fws~Ei#U5}#Qv$VP%3T?zg1%9+xOZ(G)d%kubYY*{ zEx(tHce)|t`_F+Z@`r;nBL_k2f#ZBjaQtVTqPe+ra7%)AL# zI55Q*?D}k~@h4O?;q+%5TvG(Cett6s`6DLY7#g@~_0+ zq`dy)a?TneC|%5r_#l(`N%8PSy1s)l|FV6bJD?|gHnvU%Xt^ zF%i?@!&J`gXvjzJ6npy@mvF|4Fn(|-fE@|Pj&Gn1iwJ0Mm3EoN4HMQ7|;5zm&shI8S(0j%`@jT5mWuG!WX{Z<{@MS^^!$9&*<)SUdZWck@Ij)-xR|Ce$9 zJN-q(arwY}5z|UQLHCi|0TTEp7KDhfvW8Z2Rz#KfprAGE7r$y3u-+Quf{N`EPlW$e z^1o~A|2pf}oSHSPAF+nk#Kiw}jDX_-gn!iM7ruCl_|yN6HBraW`Mv&LuSUM}`JU}_&iS0rd7lSATbgg% zvTq9v2HST2+*unKOyUO^Ox%96IC!#q*KQRU?9jydvu7?vWHE+ae!EUf-Lu5HJnV$z zhev(N8r%BrfL_Xde2S{=!?AZ}uMgiy%*!#?kxd+0XPF#;#&(3z3U1k#b+c=N1` zbaHRXGVjbDWdBedE=tjOKPH&Kb{Dqe-hT&+)6K3F04a%H3q6{id<7UR_W8t{W3V`T zi@Pvb)51^pHo~@BY?6ZgV2^oG4uhFYYJV>dduwxW18lQ$qd07Hfh73u>B((iamr>f z*d4v2lHl)V4EXO6uyVsrS25Uz%17J5L*;N-oa?4U@Q@r2s9uzjg`HO4s|p@Q0m^qK zH`PjfOL?l?6MS{b9#Gz&DgoR6;h8n~8xm{lzKwvrh{%VZL`0!Qiy}@M1!92Hjst+Q z7$9F>|2h${PT4AAC3>*_;kHl2FL5&vJq22O$m9!^{YzVcXb-?k_9qD9uwU~b{S^O} z5>kphA^q2)b)_Krp>L9#fKAXkHbCm<*F{>Q^ee=!oYn@+ShiF0{lZhfu--vfH zNb-w)q4hzTzzcu*>Uxl?eSj=cySxSV0~(Sv@>C)4lW*JtFY?`WDIqt5cJ%AssRlsK z50Qne0Qvs9hbq@fC^?(ssQX81V?%iDDcz%=RctMI@Re9BwYYe7A%_P-EDQ#>T{1v% zqeU_H7{5|Y)T+N_M5>@0IH0vuPBCe4w!D1K3g=y{R$KxpmWGmZ6;nE39zL?x+AkB4|OeOHlH0DVg1{ ztlD7gnp1Xsrh$P$wq;@2Oi_`3cE=6(z?z1Jc5ejgMto^q8TiI}S0{fE<>4UFk+oGe za0$>5x;bsTk>PPF{eu8W@zSD9jL<^{KaVc9crT~A50p}QIdTiBV#dEIs*e6PysScW zLQl4}wKX-J;dR^~_-IG?xTLucu((N&9~T(0DtX(&{bR6f;Tq!+Y6j1HWU1AWn@qGi!ZI|I-1|JioT)l$q z{gdfrE}RWm^L1In*;?Q^J{EK{{_HEEKa2~~sr_Bf4c6xg^9#wP+1c4q>U*|s>L*6u z3gMP|hxD3VV&wSEEjIG121;75pV}{NXJ^M6#`kL?FtiqZTv5^B$cSJ*T)0AmgMa9X z0`D>e0f#&>tROQ|b|PniwPm#2b9B*pgct9@eSfdmE`VyRN~$>gkQK|t_hVgh5Vi`L z#E%3F!!M_y!aJivH9S0AGX6{<**mY;ZTI^wuf^3FY&d?{WhK>x9-?U%N-NIT)YIz%(pQA`3#&eUNpDkmf)_(jg! zlAJneI6@t}O*}Sy)a^pt#;mg8;bH9`Ls=sYxrbNzu^3vXA^Tz>xi)Chf=I>AtY%Wz zJRHz7GcydcH(?8JZmdq<9w^aPOEvx^japflY;SMxj9sdX#K@U;N%u{2c?j|>g8`)5 zwkdwVIRRF92Jom0rgfyc>!n{T82?A%kAnu;9dd-Zd$b&sK%Tn%e(_1uk}cVHu)ift zs(?o?t1Dw0VrS|UPDe2YtAX-XYMF|ql{Gcmd$ux%YJ+)8jH_7Bc?rwZliM2UgD%nT z75wb5A`@(XreYMi;ML$tZhx6`^mw8Ua~O{!5D3-Pp{n7j#=2f1KKgSFew0Bf6~*bb z)6vl(Rm^gt7?#2~7$0tR-_|cn6Y)!X-v$boRB`c0V#|2z^={>= z1;ZR;cSA*-ovdk>W;@B3JEHr^eh4l$H$VPz|L88irN@Kb$jU-3t7-;~k>2j^ps1jL zP)^pKjv5^*rdA`wa{?gO258mD(97)ccV*qpZ;ucO%^eD6HE>5X!+XtK z$v@^&hLDBifsqkQi3>`B4};=|Zrg^AeIF~uBeXIAeZvc*STulvIQnF}Z z$IGwK{KMIL>8r3ioVQ6`zw5+Vgx~FNi z5KqIXF-I&(-u0Zkuvrrfjd9~%ldC#K8h(5Qf!iW$`Z|g}33R4dHP|aUe{zYQvNOj>&reyfg(=VhkXJ=<8 zB4Yys0|jd(nP2jTs-1zzt81Uq_5^)g{6+d!Bd+>U&C3qhHnb#0GK(bMU-X_!URTeOosH?_>P& zF|2d6D)QJc^*ddo2v8<)(olYN8Htb0A|135m35*YeZ?e7Sef>zOvNtttYfm$Zo4`i zqLZ`JpG4`olh4j>e(U7ToLuR?a3P#pk2-3}izRCU$0zIMg3so$z`Um~7Wgv$u~VeX zoRx(oCBd)OBr%??Z9UUDUyj$>UYHGNf_GtIw z;$puS)s>Z%dV6Nmh9@UeHI3U*QloB1(i+9z9LJVicc=uJ3|ML)^0{Acz^a>p{(=0E z6Y$@49MTEI#cnxV?Aq#L*3`gI?`-LyL3myEKa&ZRSO?T z$>9VYzN^!rtc<>Gc9_~4!9q@sb4%O&^2B+ANDQupe%+x4htp|y%TMX6Fe3f1-7?u= z`z$+6h10~F|5^TRmE^__f=2I>X=yn3aj9wNS~{_N<-IV9n?wYq0VpqQEGkc4#?T@$ zaQ*;wXzfE<(yh5lxyMCC2GKXs?&I^iqzaJpFpZUf3*XoQojt>3Tq?FE8lUct-+0$R zUw_|kNjR-)hx}L~-09$rYP}*k$?zJ|WcGAnWQml^GD(i`|&X!O9oFDQzhL$gt<5)NMD%_tquoYXFQc+FQ zhVv&=6raSf>Ulx}ZsEq#n|BNbBiU;2)=hrD_7ULxCEV#Nfoj8#; z`BLY2x4T0Pk(grxN?ExRSN7zb^RITMp@w*C2}709OpATsppP$fS#>Dx>zk6ZwQzC@ zKq5m=#cM(5BzcBYp^6V2dowFp?DNZ^4Wf(E8~4h8B9KV({lb*)R@jUnysmFBI6ii+<0w~||b%EzQ`7v1ePFMVj6m|{vwhhi9bpWq9X zk9!wPs(Kq8DqY6yiEEBEa)OOTO5d90lOFUHH`#|~`2ut{pOcKSsRD;aP$^JC%pJ&!T^ z+M;5R9ugKFo`=D>J0OuNIsc+X8uW)m-8s-m?~32}Hq)=pC*e-bgWRiFZeR8Q^QChB z?0_d1oG`h4;G8te>q;6i7>VcjILn#7uBr+N418j&`?$Ew7qC1g+#8%KrbzDY?v7?P z=L{gTFvvo6!_qb^xk~7McU)Gg*8Zv z`0lnnxVqj!A{$=6e%;V8Ecj&U>GfkNFprsIWj_ujUoESEU#aRUBGaoREkSWh=Xz%p z^v?`ume_-Lr(DIF{FSCiNG&7(+HLNG?@MwITW+!sb;don`c;)wAgPBN)Lxp87^-nn zh+cgiB6oT-@SpOW*%!XqC5h>Ss@4X1&lMITPuYRHkgN854Qgr&V32rmpIrDstSF9kNTc0)$awP zD!ll_KMILA+0SmBMEp{%){z6xu>tk4rGZ#=_N~>9iHh5Cr**-mM)Y$#v6qn+^tBZ> zg+dWkRL?Z_Y_+@^6BzhO=GLkKt3G(4-LNxYq+XBzx__qnfa~S{M3~gC1>j(k=bpIX zywYY<9a_6$nUQV~3W{W~M~XN@B(k3s%OQ@e=?F!my z)MzE(_KkByXqf+51x_0fo#F}Bhy=A4DT5N*Z7uv-_``st*sgZ}q|Ti9Ndh z@o?ZKkEHAVg$Ii?6HLzXThZGpH!&IR3^^8eab2DMytgfojaqV)b;pg zc$r4I`T%NCM=)AKl$bji#LnR}8l0%`r704Mj@lga)<8H%)a}zEuF%y22n+JJlVHn% zk$Gxj_RmIa)e3fs_0iSNCRR(^{{+f-ImGBk$+(vBa!=RSioZ`~MTwJ?O#v zzsJlZ+fs#8abEa2!jK7{=d*)5l@t^}0o)fl%;JI{$@r%0r&=pY_8GF@;v}EiEm4HS zIvuM9Fr^=xxg$e@DdB4zuAdPGIw2TZeADP>EZ^>S(x=r1Vic&|n_PcJPcAGhfS4Y` z2`G&`3B#20%tn*rez8F~ieGfOezqm}o!j}{6(=YBE#6X~?gw_vsr1DtBPoS)*IM?E zaY^7Zn<`PR8}_|8(aS?;hjBSgVYEtQ&OUm*Fel7!ap%>8F)*;){*--VE<&P&+}9BY zvo|!Kgn3$tOD%8AYgN#dSDJnN@XD{s$*rx08%LBzp9AB0()sEawn#0%%axR}ue!%^ z70cR9+F$NvYMnLBPxOFwT=737-f?Btm!G+Eo4i5J8LTsN4 zY*{xd>pNsp>fKXYq;z)zF_pyFs%JSvc8Ykexbi!Rm?wHbE`^z2eKI`C?!8=T6dFxy zD9zZylFrM>2BHUDeOU>@#j&(LZnC{nZ0|^7GFQ@GT_ioWmhZ^!PE!nOkJ))Xi6BH7 zjaDXcN@0qbpmj8>pr}}86ms0hL$LPI$;h<>eNWn6^^l2cS6hYQQU|ylHN&-C9+dab zC`1=hS)IIg*d4DRN!ik(B5;M-muO=#?2kMAuxeqpxj)yVY*(KvJ0Ap)i;D}DO6?R~ zxH~9kWwx7xsI96iOK84^p=Dcoo=Sg_vdX@Dnz2zv!MFDXIK1-m@^TLsaB&~Sq(HOP zzADVq#kn7eoLu3JKUN~hRwJ0fo!k6aR7M!BPVe;LwGiZf3<*63ypRvwif+1KOLASK5fX`nE|KpTdpkf-jl<7g+ly1H7GG-X_<;S9d{7sRECCnZ zWooe1#7-9YV|-nlX~rdRFdoU*uFJTnj3D_GWW=+`Z|L3eBCHcAIw1 zaO#RXjnNo1q;w!{rV8+ktIR2e!NCGhJ}_ArSSmv-K`h>xoFg-2T3p z1f%c@eIXW}-t>Az}st#-$2zxT0W&sD!PI!e2i7OJ1^J=7<# zM}s@4{Y;!Gz*uCDvZg@xP@u@@c5d%l6{IQ^Q5cF8^<}|FYry-o#oa~|QG4}tWg;zD z>v`wE#8qTcpj8}s?B#yf=NSch`uaXh8A4k{32;w&*Y@w-z{yVSA0d|c{-Zo@BWbez zwrSB!6sXe9AkprArU9qY4eMQ=r~ArZvz~}<9s{-GqJaD8exJVUO%Tpfy*-@iX&>i) zKb)E$ojI<(8hz4eSmevjo{#5(0ky&5_NT_UX5w7SO;U4 zLqW$))U$g4PQdwyEM%(abT9&0pVR4*y?8M3c}u=s*1KWaU3o~2T5pU1SN3l{H!=$NDlXRkIDM6pVK*-y|Gr+_@bjd+mtn z>Di=Wwb+|wN$qwAZ?LExr~FEt`Q1Y<+kSYzU$R6zt02Q?(bGqAX?))@LOMpo& z>&+hyE{AoXK~wvlLCx%k+AUgE>TSa&lB#IuyN$UGaP`GlrPcc4k8Z4kmz+1qT0$8q zw#0|(rj$BfwcmA2lqQ(-Vc#3Kp4Stl4S>3IoF;1y`*XXDZQ+hPipik&i`E^z0cjb$ z41fc0Yr_xMm07uc^b%#O{1njJ|4}PS>@Lt%)iH9$)rt7mCgfkWdwqP^;`LBOA6=P=HOHl5>7a5noHB(G#K{$6-Zy$!gnH%H6^)qG}?hbvH zlzoY2z9PG)Y`$&kwE8wjudM^#E008KMJ!SOEW4UM;}+a9WQz?QkE8^GCEN?guwy>7G16zx8v7VABdWYngo$9YdfqgTi0f5%7V6T6}pS)1q1 zerOW!IE|qJPzn(o>Bj6dY};Q#l7Gb@Oox>QHSYZ*R2lY2M==eVIvGibSrlrut97#f zS>P9x6VR$ptq%3He+Z?ni+&>);k(& zNLN?)cfGo-?$vRWbzBQ55Ws4sD~9mp`B={3=T^zg*aZXlGKZL!-*f&*=86mL3|9DO zLn?`DT+4k!91_^-7*AB_v6k+pISb8&f>(SeaV1lL#d(fCa}?5W!nZ%(ngC~4B1^bR z%|x|E`LUl>u3#%tDw5tD5J^s2#a2CxWw|Fj}W8`A+pMEVSjqYm5mR+YLJnY5)MN0$u=b_S*FYZ-yR%;^YfP3&GnEunJYV;GzoKyp9+` zKqmyQg17>R>c_*d)9MfcxsJr4`2Jsu zAly?m;H(IUhA>qKyM*9r2)jh<0MCPMKJ+(Q4587gRwCfj1md-hM5l|OZdI#;BGmOO z%>Ca1@O5j+gEl$rE;yY3niBAk6Cv^-34Iw5fKXV79>nV#dJt#~=|M^sjS;L11Cd={ z1=$rcHUxV^CioV1|Ele}EXn%-@0UYAfI)%vp$5qE>o`9&*l+>`aCj0lNC4Rznl1nr z&@T}GSBbuvTY#nuh8zGy{TjmM*RgR(&95U3>%$OVbzR@ye}mm2c_Hsu=P82jRRb;o zK-%Q%`gH^wLgg3Cw*2q8g>OaxPPG9r{?dth(cprJ&H8K5PD8|1aiYlqG&BzJ)iw8$ zVL(@rEuQ8D{f*xLJw&nYn*YbR#QG2hw40E`-+<$g#Oq!T*(Tl$;Ot))p#cmG+kWBe zmcG{nVfU?<)_{Qe#*x;2S4AZI^M8-U^|*jM1KLN3?Yd3B4mo_a_J58=Y0;3#zsDkE zF9Z_=*m^8Nu>^V7H?at912ht`J|gi|)&DNT{}GDoTlfDzy#a;Hx`RT~AuzC=_9KTy z=Ij1Ct^)Zol#eD8cL7xoe|1(U5H+COBij1%D>1+kzuB6vGb-Q2A>>35>-Dh+Q9Ak0 z!xDd~ny3si2`HL@EulCBBLx2|Ew0aRtS1F1H$iR*%@+mD|DAjPpZSes(E!a}%`IPI z7RrW@o{+Omz1$Bn_J8!yuWGGNDM4>SUa~%LQUE;iE$GI7p$v%vQU3Q)C!SF32W5R7!~g&Q literal 0 HcmV?d00001 diff --git a/python/gym_jiminy/unit_py/data/cassie_standing_panda3d_6.png b/python/gym_jiminy/unit_py/data/cassie_standing_panda3d_6.png new file mode 100644 index 0000000000000000000000000000000000000000..9b0fea73dbd1f89a0a45458ef9c6442348d16371 GIT binary patch literal 7811 zcmds6c{tQ--=E0RAv&i{WQk5aArm2{jL0cDNTO7Bl6^PA*v4{N>?b>A6lcUtW8cPv zgi*Fh80(m9*-eZwm|@=EOy|^dp6hw9>;3z6U4GZxzu$d-@9%cs_xJvMVy|D*-~WTe z4zsc<9^lR8s^7>U&{0E!%eps%pDmL^AKzo753N$D+Ka>F8yCnI zE{MAQ+1u&ZkY5fyE}*z*|N7e1Dj|pWDXj9Si?RoPllt|iJCAt{G9vdyX~{-;-udb2 zf%Zl6et22WmB8O`R}5A(D0YSrUH^n{tgi>$XJG4z6lDY}#8CaXv4=BS-G(vE)P1~= zV^!;8#0dJlj+;ed5L5cuJfL@z%k(`UP@qh+G-&THb-a-m_XdFuJpLpC;`woG&qdj2 zC`jIA^D#Gi{-9g<~*NIi-6YtzyWUP2dsY{ zIRrHK#^pmnk1yr@?Fn%m5Qygqr%%Jl1M_6`0fM z+X&7?zi>nW-k5kOMj6p$)SID)vyCcWAr{(u$C`0??O{#dCYjoe?YYQgp={_q^jh-+ znJ_gt)urZYIEA6*b3*}JU3x#=`VM}x!_Zt0CXk8T?KE|XC>1?C6rLaxdG>vFCat^E z2eByg*@b=LgSq%ar8+#qr*g*nWwAz&?PgEYyFubiriuBMeW|F_ka3g~3$z!`z)@ba zwiz+9uC=3tQ>Zl3h^0q@U#X2}@>CrfEgzSlBB{JfDz3GKuErzuD9nW3iKA@L8>M|4 z+n`7r*!&Fj8Da~EMqkk#v&2-BER$>YwS2IAI*XfyTP}LndUT#mnv&UNP&Bu*=_nI+ z+Xbx%dofekBdP8-rbO=WfRIZ#MLF&l;Y+BrY7%3o*QZEnEYoSe5ghlHu@i{5F*jfQ z&;k~CteXd&KDR@rfFD{JDtLIAn=92pk+Zmts}>p9TONnTY|MPHiBp@CqHK>vVt89} zPN?6~8zn~;==Wf{75g52-9za)UXwYOY+a)rM16^)2|-59d@(%*5RLLZGo{KEBsc>iozT_*Qidm=ohA=Ywvw-;bo7`ESjiZf^Nai{p+S^Pc>NEvzuNQrs ztUE#WdlLS7sS$@e4}sLy)M)Jf$cUKgmnlZ#*yZgT%cCvX&i8!P;^&Ve| z!)>MJu}&DI$mNBp#{J^swR}*>1GBpu)HU(e*G|wqCI`CE`kF4C`uawjpXnhXA)y9a z>W3GXW_xl&cj$w}XXjH-yjPc$R6F{iRA|y7!@{FLUc&3ce1IjE6njuEBQsM>Oic8s zRu(YD3AdacKCzY6xWR#PD9w>4b?OMZ=%Cjc8qFWm%wn;YmOKyXnI5{ZJy&3Qh)=hy zqC(YhB3F8)SCal-9+jX1N6J70mty6RS=rgK`9;01XC)HbWe}`T3ez^_ghj@T^QAWM z;eLLI%8P4g9P@CrF@@1t5m2k(hD|+@otMW5N4UAY{}**iZ=)A=lZY=Yx|?u>P88yoq z=hJ;&9pT#);`ipRuGb&9f@^C5MsQMkr+zF>#krq3x|LBo!edV2k?R`%n0#^ zaO7=s;O~Gn8$a(FJrw*XG^fx(yxw)CLzR%#>teI#CHmCEqWmj!F#TL%p~Xy;QTej@ ziht4QbMz?+!)AW0J8{c?!mnR%in%*isb_l6;`779bqKtjpmhb6*+^vqUKYguQFM^{ zl+zHNIZUtS{d;nV$FF9tKl_Lk?%Z%`Q1YyQfe z6%}CproDGO^!wU1G&D#dCd0$ftxBGQFTgRH`!bGh%u-9oLmdjWQcuLjzXco}bWwXl z(e47HfD*pQjwk?ko;7~j{drT}?0)quS$wL3iPCTMT@s7v4rN-YX;K-?f-S0(1;6eG z;AdjN_FQJ#FMj&D*E4kYXQ}DP3*2V4nH1_Uy$~x(Keu9v*F5jl)KFEsX=97vEBZPf zov*r5u+=crLrxYN;=&0kN{yIu?QAr<0^CW{627G4ooP{_PPK0|YfTpY?);?-H@0L@~-@f|v<^>`w7H)3-(r(k)(Rt#H zTwZaSVb5;YE9<#Hyt%ph({3iUiTWW5S$)#D?@nkkI7e*!{GeC60*3!aat_q}d7Zyy zdhrh>*}blvo~%yy9h)1@nvZ9xp=-^`yNLsNY+d*Y7LD$&zSLR+Y21#e44VEFo@co| ztri$6N40R=-ifFkT@KJxoFz)#ncM%UMLzEB8R1FU5)Dyha7mfx8M?Smq^A50E9Zp~ z*9d7V=Ya*u=8r9g#i*$~59P4|HnFLZW{a(EXTPPmb%E>5uiHfQ6^1kP$=(cL6Ol7P zzCxqP-inN_LQh9{Ib_fat&QRDOCs1@g<3fWwwGy}l{Bh{kS)$>A~u^%t9N3wh_ts? z09RbniP&XrB_<}GHSRmR%wQU%2tR6>@D2X*sW}iYy~qkgNPH66_uH7t44NL~<8PGu zDj|>9-ngFLM`064^D^m978$6gXFq9@5>*_ibF0b-r!Xd(JwA88c9b5D@bKtt3vld; z;uW}p7%7)5ChJTP`NCe!Wi(ewCgY%$ZaO+!2-X&pHGJGqLC2fS+-f4}&;qjelPFuO zBTtp(QLL4ZYmRnHU@0%`)1S3j2K$w0j%srZB)!q zQn)*%G2F@Gq`_o}Cx47?hEpR|5%sFtK|FBEaK9Y8IWqZ2>>pWyC&@!iW$faY$dQo| zO~fwieX5*K6-s2%e$@e`Jw4cqGSN~)P+z8*C1yVm-7OxpT(^vGo7brte)#mn7?lCh z(9j|prTj^u;(to?C>3t`pe6~Hx{7<_pK`Y&J$qKYKz@N9LdcSi#+xl%nXQz8?9|~} z_>WsIMl?~c{8sPKR3Le)R`ew}+`QcP%*?wnm1R#-?d_NK!N}UGs;csG6{+#(VAbZW zS20)mlm%j%=cFOB5pcMLf_lATho$6P+=Cc}c0Tj|H$}PSee+uDA1=X>rKP1!+Y6Y% z^ucr)lR#}NkL6A6og%+aZ=!~Whtt#3v$KydoRPDQ=sV}K{HuP==f7g|4yKoa!{JaU zl$c%EDzXw2-G|n3mGyhH)A@8QJ8WrOaw%~e2g;r>Sb z_$d?`ZP-_ZK83wsIjj}3?g|`}8Fc2(a?a-7S(x~Pt&52#oA3%>78e(Due}6!qS0$w zjBxhaOeaD7ut=fQKEXoU1DP`$_j}G71HNW3O%LsVbjbrtWnyn(2Ha08E4!q&jiO&w zfF+HOz@|Aq`B-~e~aIfdeniHcuS>Pa$LP0V)< z4D<_+rr}fvir!5Hia&foWdcPZ?{z~957>b7gndWv=@_?{Q`unX?9o4Gk!21E*}1u= zJN?59LsL#LGbB=<5w}O)HiQN&*q`yG+=apVY;MrCeCGH%94GA2roejX!#=o6uQD2< zX$29DrRlh2JGK-N?-Nt)zCI_~PDV@UJ*k&iOgC$!%3=9=%~fXPJMBl{iNjh%pz298 zTX|a;kAp{akCF4`+QPXiU8T^jTJC&a!+66=b7(2N?fK-tPS&PWGPfi%XR-$4FqG!c^fQ45(^=nNv7F25}dcBa~NlO??UO#eswVfnsv_ezWM7vyk7U)ZOv~wn~dDZTxzM^u^Hdm9mGu3 zo1GHAbeo+G4I9&0Pm{K;aB>#FG*1xc+S*^`%-vG>)FTVi_X;*j4mC$t-O@xCYiMUTIM}xhv(jt!zB8er2^S|J$NjDQV^lbQ^;fe~HXM!rb z2YSoIh&1cb$=_!yXW<)YS;3C5vW=c(hIIJdAQ6eWn5-XSEj4Kcl;LxXkvSl}Usdal zmVHTCQAJGHSx4eYC`X8n>u(NulBJtPgYa z4G~eTp(S#ggs!xo?$6bbK+F?zIt{*F`+yY37oC&;^H0@I*!qo=W;cX^Ea?RMDVH4a ze8Z!A!4#&Sm}urHmvjEy`|-)12=$FK-l#M&4Y}cCWsiVkuYN6`bicAC%?wxqrY^hn z()Gx9qvOE0cVnhT!=wdb)6T%+`0KS6L?)6sH99)+d20~Cl3{j_cS(EGB?%s5D+)F;b8UHA^C){UZ>FUi zjedJ(U5h%dyxVY#s*(4n=}gQinZ|8s)5^nvy}AeXHuoyC$Q+|<>tgp+PwN}&xTDK% zc-!_`W;zWo2TGE6YQweh()IdKoOI9Wqi%GO%8S=;01;cp!B=z-$m5}~FP!r##IjQJ zx?TU+G2KIYhQ(;96_Q9yq}xyteq}7z*Yb^k&ijRn;ZJY{JtYKNu?M9xXJMV8$I~u} zL_?>C$d^MuHl2#Rpa)#$KI>ywl@nDCraNhWF})?Q5Z@(T9ccU|_uOGSnxC|TlE2h$)hO{-MrA<=FsPNq>B^@qR)FukPS{2 zhxHufBz3+t_cp!~=@(NE>PJ?S_OmpZA0cwX#06r6PiB(fP$=MxMBFOx@fJm@vA?z` zX#KtnjdYLnVG?2vGQ@2*bM3sOqz4lb0o*6w`T$z$kk^wpq0RaGB@83fmD;=$XU2I z)}~5E$^g`VsccXHG^Xu%)$|Y?sfg0d?fLyuNVSZlW6FtQ^r^UfS-}LA#wMfoAI2;= zPUX|J$CAg!*0oA|T`!xSeZRHDjF4&v&RC$Zmq-K_fLk|@t}$m9Qzp^?UGTJ`VbASG z9iSuJwsLqWK$DQ=Tsf~Al-wmv2aqNAt_PoPc`zM93sqAu2Vtv7Ar21B0HUEmkT+`C zvk>Qfqpv4dC{rK<&X(YYV_`ta9 z6g_^qcM*r0zEoRI$U%R!3`M@IPRf6Gryz*^CJGvL>$m<4^V=oXz|B=O`VC{pu|285 zUq#f%SDQ^l(B^v=o7M+rwF90`_}=mK28t0PO*1!%6fy_7BU_}?zD215^m! zwc!*5bGa7NQ!rtiOO$C$EI(=R)8KvJb~jwDDRps`!gRRJQH$@*!)A#1eRW+bntp+eEvJ&LR9fFc)7*IxT1EYSwDYe&HhXo z$_pmy7f5@F-Ka3weWO@9G6MgkM}BGdtU-{fNMf!o)Q z@!vRR>asC12!X3o%ZBfKE_vkyBr>pDdjy`fbrus!7+uYM&s(GhEMP*1)_vtF5+u)s znpT&rZaAVk6@6$SewDYVdRYj4Te)z>7TXMTxXOF57b_d%) zXYQ7hEN4CN6)g<8CnzyF%CWNB^1u#oH5-j_I`Y)#s%=Jb+yry$TAT6JA{FnuzhZ}% zp;;vn@YKBeVja~Z7+!kY=AQm6g^y@-O-;?na$sQPK}67k&w8}8xw%1#JSzH~8n781 z2DYy|;t&0#LXko9A5n&UsZ`(f4~=v>9XxgNWWP87xd028wU*f!HvR5Ns+`Ggvym7p z*5__q{#>7lPWWVNY^x;TKWX z1TOCk33;RJ`wv#S>6_KZjE$l5HcRwiUuB*eWMfd|2H1sy8S$0*jGEbya1Og;2Qg#MBs1_ zK=c7w9NoUc_*|*n4;*O!GKUfQiu8Zu5V+7j*UM3pCr<+G0*4KG9@#1lntoyRH^%^! zrvO>-^G~3?+&+(m(7-I%KY$09px{2fIVAu4Fb@53=nj{R`Nn$i7%86s$Qe!>SZv?9 zg}<6yPQx@~&tLQiH}v0=;CpEQ$&7p@H@;C7uADTed;Y_}Pr((!4bGky9OF3L33ncD zV)b(98os!GX;AAi4%zX&H#hiSDI;#`a2?M5#hvB5Zozj1{-$`iWY0H?|67Q@XC^oG zxO#CP-zERYL_iq}#DMEtj%2=!IT6t0H{wgy`!3IaC#<+m=Ejc8_I&p_S95O8f9=9? z$iHzxw|)cCiAx-H{hj4snXG>@Pya!MeRs$AQ2moj`kF!9JpKPcPX3>$*E#kc0+>8f UVb!q-kjo$gy=#|CezlMOA9Hz_xBvhE literal 0 HcmV?d00001 diff --git a/python/gym_jiminy/unit_py/data/cassie_standing_panda3d_7.png b/python/gym_jiminy/unit_py/data/cassie_standing_panda3d_7.png new file mode 100644 index 0000000000000000000000000000000000000000..cfeef3d9a3bb95d29a82ae99ab5c2ea2e1fe1465 GIT binary patch literal 6679 zcmds+i9giq_rOQGNTQoIH){za5-nsfE}^X1(?VqEB9g7KjW)h1)NK$N``9IeEMrWe z#9(d-4P(eQ*=9o4F*CpCqkHe~_j~>RgP+%HUOu1CoX>O4bDnd~bDsA+Ja28bL-aRM z7!0=K+}SgBFqps(=p(WPJULT+b_fQOVw^kkyTk1lb3+kNJe|?|zXuT`yu!V_ohar< z_Jo%@O#Fh_a%QiQ;u)h3>&I4xst5CSp|9>!fM@JEd$3(-P*Ge$UBL6*!HR={s!IFs z__+vOj(PZsxASa_XMDWjxB9y#TlAktbN3F2eA{j!GGM*^^;0 zF~2?dEF&+Cl8TAJqF`Hm6nzy0n*R`)gUuJ!3vTt4lr%IPkbrIVtPwLb?9hS<)MtzC ze6lPE6KJOkY`OLO9{FrjcXdTW9W5}_XYh#7Eh8^KCk)$S7bGll)a3!3Vf(b105L^Ey2w6_3@$S(h(w1QfZX zOrTv2ZqKlXYy6dkOVxBYpKM?^~_wm5Tnhwzk2!&~SHY4fTkEjo{&?DDwO;KfKF&S6|HblGb@M^3t>( z^-=DH%a_&Uf}QrGb4>G|qG<0E4)DLbHQplG$O*OEogKY?;hS5{IoSj@DjSm#z$e5`L)t$O%SXYam!_U1tT03pf8-94wQ6MK#{Ww?Jp zVrQ%OOH#0(pP#$C`$Q^1?MUMC5g(FkR$7{-jL4yg6*(kHy3t=Ret{K1aX=iY!;((tBNQG#f?}3)v(g*T#E#Wf3Dg%~#*j_dc^C^6DRd{Lxcjh4N?$9DARu(ycpFRz)>H z;D02BHRfg1CnY8pw9J~%Iac%&lLqIO2ZwpfSi5p3;>g|Y9Tf)4U#<mLw%at4m#7 zJ>l`=>cP1O4<2aUkdu+QQFC!AoHXR0^!PEhVm4Tp*!*p>A>N#bNsdIOgm6bsWxOlOo*Jmy?qW|R;ji@OLIrR9` z;~01KXv_T~rKqCE18)3&XVSEzi7i+neUzwM>;j=1B#d16x191zwY+EiU}_6za+P!FPYY6|3KbOQ(!1tR_RfKQD-ALpjZccKlFYKslE zX&TOUDe8C4OiiQLd$J5xNAAJ#Yiny-sTw_NSBRkr2?-=tNClC@A_9@4^u-D9rXTFu zjqgFe+{Ko83S)`v*LC&FjmTB|m7%arGEXrs1(OsH!+4_kA=ca}FrYq=78ylNcgu~3z`sdG|U*8zC zGq<<5@9F6oLvmZ{v-nGCX=#j??nj8oNwlldq=_xIqH*J%o4Vb6?mkjcgCu{_VV842`QqU)hUhn%CwyIF5Lpc~pDZ-2;CoC0 zX{c20l!Wm5*jv?CyZ=-@Jy+e68MRESudm12)rS@LcXnFp&gmq+uCD$p!%vD_9%>p>~s}b($p0PNSqsN{0MXZ;%_TPfuW3x1%XL+&DcL&Pw8wM(vEQ zTKe}I)EI^);M{}>PSX)PorZ9<3r(J4Y&3-R+f99>x~AGSeDC+Sgp(#(+$`Wx>kSrm z=0k|@$r6mvF>Sl>=$0wTER37^6eEH?)DYs!{s>aLqr8MNj`kltHm>#{-`pB8SB?EN zJ3ITxZDTZfhmd&vW9|*@=sdBBF0U%5QuU)p4ffF@f+aWF+uQ49;dl_R$r9NY{XBBR z!M-F#i|CnNq$0^G@!KmlZkxwlpYPo<9Kc!acaC0aK7!Ywl#Ej-SDlerDn*^+|hTwQG1_oS^oDse?7c-f02dK`NjhTsihs0L3jM@5L zYkNO|5@B?n9U!D6ZfxC!i-+%fotp75Wsl|bQaFFCe&zXuP|LTy*@SZy7*-{3G#&}%b~MFrVwuv zz3_}3$wY9Zsidc*m5Ai1)`qea_f;2=o@#1pk3lKJ$wwTxquw(WEQH96AP?1&xpV!E zlPBSL1gkF3sT5i$3x(ns(3On5xdVb1WFu=}+2a9^Y|H)#dWRMXB%K>N`1*!#Eoe=M zgSoKSG=kWkzcR|1XagiN%Wj(SD6h0moe94Av=i*W z1hpB4NCYZUZuK^c^-NX!9G-=9wvvv`NFh5I)|0Cbv_@zbESoN)Zjje&LHv?Fnz4tF z;p`ECmUA2d)od}=M04wcs5g5~r$ILA$Hzqt-M90Rya_q<#xkaAwjFE{SR%d~Y+zX% zjsGO27bos_rT9du^kF6 zY`XTGC7k)3XvFoJM>BWVa4YL_Wj^9MjIjR!{7;jHL zQr5{N9$v~-X`skSNb6j^d*1fwj$h3{EBSSvo-j4^fx#4Tk8%+`cQ|S)7NY|S*~?sb z%lwxwUp{^Ml>L4YUijiqyL1pr^Z+uiLxS5IlPK!jrlh0_rx4z~d&f|V2n?)LiI!vDX9-Hzk~hBWIYO+pv9{)MS9r81(mVT7-@)!LJdogaJdxYk7fTS!3D%X_ z=cG`dZEg~B>Ftkn91fSBu3M=PRVV0Aulp#S6Ay|}Nr#LnIx{r^y{MP<;)P{YK5as& zmvM@9K-+(o8S^TU;6|R$n28dNk-1g4i7u%A4Ph z7VUcYO`Q6)-X2Zur@sr;ISX>6qHxmSs+Vx@glx%HkA0HTo^ZuvZ@6MvJ{J}kIX79` z#JiFuGa}F>UPAGaQmwcY1iJszU*|X04n!}Vw*jLk_i8!xx^bDMDf&UpVbeNlRrfl8 zH6>nNULC?i=^PLe+vMh~5IheUbE~m2q*5hbjnZK-D=0+;doJkc^78V41$Z^%i4f4_ zq(s1X6g<&FATCw(Un)-lbA?mRqf?BU%@dk^G)gKOYeT}n&Xsej>*}t9mDdU@@!9+< z;rvlWlRj`@W--QWb$5wL7tV)5P@^tt1%c(6#ptC@aG241jvK_@w6 zvocHTq2Bhd9fa;gZ8DjVDO{LiFX;4yK|}cX1L%AC^OyT*6v1>E2j^=f8`yeHb+yB5 zxo=8C$^~LG6A|wheUId%S8w1;OwG(F!k}G51$u#&g8P{H^yyRVC(yc2J4JMgt6GE` zIiiF^Qfu@UJ{;o8y}o?E2W%9>LfN_1a`K6KRAEFWX5nxm3>7ESP!=0={I)-T~d-s!r)jiK0XdA#jmdXG|Wm^QskS3p@TA)qkEVWE*IPe zB+k2|Gr?KPy3l^NiS2H5rW{&NZmkqF(r~<2RT|1A@1si6>5=2HH3x$Vn+N7XrJnlM z4AAM9v&<-qk-@>$PNm80y%S3CB9)V2s%0wip+r)3bug%yv%_R0busTTGcRFTj|$4Z zy*X&vfgAsJ-%{)feYw|WV*r@nF}ezhIpcfgVB)FFB!dBMzc1&N*f{I9+3bdDx$NeK zxnV+A}6Q4Xp9!VXJ8gxbmqQd67Y~3VUEW2dH=h%&lJu^|FH%Eb=o*3A#M7xR^ z7r1ZidT%Sd7?==hf6v@LMF60OSVJsoL_Q55fE1%$ajh~9ejW#Rr8;~)4NkNF`64dd zPJehNIF4CVFBzAP2(GtKG|YKM`eY8DEDI%xiOP%gl1U%a4$qul4u4txr|N(~%){Aw=3@%EszQsfol z7eL3-{1S9=Y7`|UCFm?R6}*nTnu6-`3gRr!X%9y(g4Ucbe1AzRe@=Kqx3lsKDPpCb znVDfXPPx?{V=#8TtorPZt*^e($wM zF1!t$#>!Q!eo;;guU5{ATxeI$lBUz%>Vl3|^Z@?=TleP35ffXz`BurPX5*ys+1TN3 z`zo9+I-C_hVA2vfcX%nL*EEx#IJTt0%T^yWuK3G_!4I)VZz6sqBQ9TGTHh`Gc zk7K0>5N7+Aw{0qhp17zBzPcQf-w)xezYWlN_^$l23K$>IGHWGet5d#k#hY3>QwMQY zmWH0nH)48zf;0L3QoiOFd0XxSIaSMB;W|6`Ckzi4>qRg#6n#e;GIId+?Lq=@hrKayRiF#11zvEEIqu2oV0HiE+m)y)yg% zYLJwd&3K+oQ1p_{B#1dAo}+vO2(S0*l>==i9070I*qk_mn85zlSD+zIMvXUr{i(Ll=&_TI)4xXhu*76=<~bO!R+|L0sFI=l=A88{ zfl?!v*rls~y;a?;aU6lZ`?f;97L(noT6I@R*P+<_d(n2DHy#z=nFNI_2pH(G^dT3R z!$a`@=|_RyO`J&()9_r|egCSYBvn&fe%DVwBh%K%aj*V$fF}zku!%--5r&KkfjQwV z^T=(|KVP>@Mqd*W&$GR-ecR5&2#_ZEldju%&tk@|{Wmu5JU?%}T`cye|J-aC&UYL~ ztu1F-H7wuw*lnhdm(^{-U;0x1vHR}{9NW+P^-fMMw1Pgs1Q#X%y)pm}(^`X1Ft{ None: # Parser for Jiminy's hardware description file. "toml", # Web-based mesh visualizer used as Viewer's backend. - # 0.19.0 introduces many new features, including loading generic + # 0.0.19 introduces many new features, including loading generic # geometries and jiminy_py viewer releases on it for rendering # collision bodies. + # 0.3.1 updates threejs from 122 to 132, breakin compatibility with the + # old, now deprecated, geometry class used to internally to display + # tile floor. "meshcat>=0.0.19", # Standalone mesh visualizer used as Viewer's backend. # Panda3d>1.10.9 adds support of Nvidia EGL rendering without X11 diff --git a/python/jiminy_py/src/jiminy_py/dynamics.py b/python/jiminy_py/src/jiminy_py/dynamics.py index 07b4c1dc5..967b67dbc 100644 --- a/python/jiminy_py/src/jiminy_py/dynamics.py +++ b/python/jiminy_py/src/jiminy_py/dynamics.py @@ -70,8 +70,8 @@ def velocityXYZQuatToXYZRPY(xyzquat: np.ndarray, However, it is not the case for the linear velocity. .. warning:: - Linear velocity in XYZRPY must be local-world-aligned frame, while - returned linear velocity in XYZQuat is in local frame. + Linear velocity in XYZQuat must be local frame, while returned linear + velocity in XYZRPY is in local-world-aligned frame. """ quat = pin.Quaternion(xyzquat[3:]) rpy = matrixToRpy(quat.matrix()) diff --git a/python/jiminy_py/src/jiminy_py/plot.py b/python/jiminy_py/src/jiminy_py/plot.py index 8c4cd0a9b..fbac743b6 100644 --- a/python/jiminy_py/src/jiminy_py/plot.py +++ b/python/jiminy_py/src/jiminy_py/plot.py @@ -298,6 +298,7 @@ def add_tab(self, plot_method(ax, time, data) if self.tabs_data: self.figure.delaxes(ax) + ax.grid() axes = [ax] # Get unique legend for every subplots diff --git a/python/jiminy_py/src/jiminy_py/viewer/meshcat/index.html b/python/jiminy_py/src/jiminy_py/viewer/meshcat/index.html index eaa05cefe..cabcbe77c 100644 --- a/python/jiminy_py/src/jiminy_py/viewer/meshcat/index.html +++ b/python/jiminy_py/src/jiminy_py/viewer/meshcat/index.html @@ -72,20 +72,25 @@ // Replace the mesh grid by a filled checkerboard, similar to // the one of Gepetto-gui. The paving size is 1m by 1m. var segments = 20; - var geometry = new MeshCat.THREE.PlaneGeometry(20, 20, segments, segments); - var materialEven = new MeshCat.THREE.MeshBasicMaterial( - {color: 0x222233, side: MeshCat.THREE.DoubleSide}); - var materialOdd = new MeshCat.THREE.MeshBasicMaterial( - {color: 0xf2f2fe, side: MeshCat.THREE.DoubleSide}); - var materials = [materialEven, materialOdd] - for (x of [...Array(segments).keys()]) { - for (y of [...Array(segments).keys()]) { - i = x * segments + y; - j = 2 * i; - geometry.faces[j].materialIndex = geometry.faces[j + 1].materialIndex = (x + y) % 2; + var cmap = [new MeshCat.THREE.Color(0x222233), new MeshCat.THREE.Color(0xf2f2fe)]; + var geometry = new MeshCat.THREE.PlaneBufferGeometry( + segments, segments, segments, segments).toNonIndexed(); + var material = new MeshCat.THREE.MeshBasicMaterial( + {vertexColors: true, side: MeshCat.THREE.DoubleSide}); + var colors = []; + for (var x of [...Array(segments).keys()]) { + for (var y of [...Array(segments).keys()]) { + var color = cmap[(x + y) % 2]; + colors.push(color.r, color.g, color.b); + colors.push(color.r, color.g, color.b); + colors.push(color.r, color.g, color.b); + colors.push(color.r, color.g, color.b); + colors.push(color.r, color.g, color.b); + colors.push(color.r, color.g, color.b); } } - var checkerboard = new MeshCat.THREE.Mesh(geometry, materials); + geometry.setAttribute('color', new MeshCat.THREE.Float32BufferAttribute(colors, 3)); + var checkerboard = new MeshCat.THREE.Mesh(geometry, material); viewer.scene_tree.find(["Grid"]).set_object(checkerboard) viewer.scene_tree.find(["Axes", ""]).object.material.linewidth = 2.5 diff --git a/python/jiminy_py/src/jiminy_py/viewer/meshcat/recorder.py b/python/jiminy_py/src/jiminy_py/viewer/meshcat/recorder.py index 5a948b851..4ea048842 100644 --- a/python/jiminy_py/src/jiminy_py/viewer/meshcat/recorder.py +++ b/python/jiminy_py/src/jiminy_py/viewer/meshcat/recorder.py @@ -331,7 +331,7 @@ def release(self) -> None: def _send_request(self, request: str, message: Optional[str] = None, - timeout: float = 15.0) -> None: + timeout: float = 20.0) -> None: if not self.is_open: raise RuntimeError( "Meshcat recorder is not open. Impossible to send requests.") diff --git a/python/jiminy_py/src/jiminy_py/viewer/panda3d/panda3d_visualizer.py b/python/jiminy_py/src/jiminy_py/viewer/panda3d/panda3d_visualizer.py index 35202392f..bdcd8559b 100644 --- a/python/jiminy_py/src/jiminy_py/viewer/panda3d/panda3d_visualizer.py +++ b/python/jiminy_py/src/jiminy_py/viewer/panda3d/panda3d_visualizer.py @@ -4,6 +4,7 @@ import sys import math import array +import pickle import warnings import xml.etree.ElementTree as ET from datetime import datetime @@ -170,7 +171,7 @@ def make_cone(num_sides: int = 16) -> Geom: """Create a close shaped cone, approximate by a pyramid with regular convex n-sided polygon base. - For reference about refular polygon: + For reference about regular polygon: https://en.wikipedia.org/wiki/Regular_polygon """ # Define vertex format @@ -206,8 +207,53 @@ def make_cone(num_sides: int = 16) -> Geom: prim.add_vertices(i, i + 1, num_sides + 1) prim.add_vertices(i + 1, i, num_sides + 2) + # Create geometry object geom = Geom(vdata) geom.add_primitive(prim) + + return geom + + +def make_height_map(height_map: Callable[ + [np.ndarray], Tuple[float, np.ndarray]], + grid_size: float, + grid_unit: float) -> Geom: + """Create height map. + """ + # Compute grid size and number of vertices + grid_dim = int(np.ceil(grid_size / grid_unit)) + 1 + num_vertices = grid_dim ** 2 + + # Define vertex format + vformat = GeomVertexFormat.get_v3n3t2() + vdata = GeomVertexData('vdata', vformat, Geom.UH_static) + vdata.uncleanSetNumRows(num_vertices) + vertex = GeomVertexWriter(vdata, 'vertex') + normal = GeomVertexWriter(vdata, 'normal') + tcoord = GeomVertexWriter(vdata, 'texcoord') + + # # Add grid points + for x in np.arange(grid_dim) * grid_unit - grid_size / 2.0: + for y in np.arange(grid_dim) * grid_unit - grid_size / 2.0: + height, normal_i = height_map(np.array([x, y, 0.0])) + vertex.addData3(x, y, height) + normal.addData3(*normal_i) + tcoord.addData2(x, y) + + # Make triangles + prim = GeomTriangles(Geom.UH_static) + for j in range(grid_dim): + for i in range(grid_dim - 1): + k = j * grid_dim + i + if j < grid_dim - 1: + prim.add_vertices(k + 1, k, k + grid_dim) + if j > 0: + prim.add_vertices(k, k + 1, k + 1 - grid_dim) + + # Create geometry object + geom = Geom(vdata) + geom.add_primitive(prim) + return geom @@ -687,22 +733,48 @@ def _make_axes(self) -> NodePath: node.set_scale(0.3) return node - def _make_floor(self) -> NodePath: + def _make_floor(self, + height_map: Optional[Callable[ + [np.ndarray], Tuple[float, np.ndarray]]] = None, + grid_unit: float = 0.2) -> NodePath: model = GeomNode('floor') node = self.render.attach_new_node(model) - for xi in range(-10, 11): - for yi in range(-10, 11): - tile = GeomNode(f"tile-{xi}.{yi}") - tile.add_geom(geometry.make_plane(size=(1.0, 1.0))) - tile_path = node.attach_new_node(tile) - tile_path.set_pos((xi, yi, 0.0)) - if (xi + yi) % 2: - tile_path.set_color((0.95, 0.95, 1.0, 1)) - else: - tile_path.set_color((0.13, 0.13, 0.2, 1)) + + if height_map is None: + for xi in range(-10, 11): + for yi in range(-10, 11): + tile = GeomNode(f"tile-{xi}.{yi}") + tile.add_geom(geometry.make_plane(size=(1.0, 1.0))) + tile_path = node.attach_new_node(tile) + tile_path.set_pos((xi, yi, 0.0)) + if (xi + yi) % 2: + tile_path.set_color((0.95, 0.95, 1.0, 1)) + else: + tile_path.set_color((0.13, 0.13, 0.2, 1)) + else: + model.add_geom(make_height_map(height_map, 20.0, grid_unit)) + render_attrib = node.get_state().get_attrib_def( + RenderModeAttrib.get_class_slot()) + node.set_attrib(RenderModeAttrib.make( + RenderModeAttrib.M_filled_wireframe, + 0.5, # thickness + render_attrib.perspective, + (0.7, 0.7, 0.7, 1.0) # wireframe_color + )) + node.set_two_sided(True) + return node + def update_floor(self, + height_map: Optional[Callable[ + [np.ndarray], Tuple[float, np.ndarray]]] = None, + grid_unit: float = 0.2) -> NodePath: + if height_map is not None and not callable(height_map): + height_map = pickle.loads(height_map) + self._floor.remove_node() + self._floor = self._make_floor(height_map, grid_unit) + def append_group(self, root_path: str, remove_if_exists: bool = True, diff --git a/python/jiminy_pywrap/src/Controllers.cc b/python/jiminy_pywrap/src/Controllers.cc index 19ba90a87..d70887d1d 100644 --- a/python/jiminy_pywrap/src/Controllers.cc +++ b/python/jiminy_pywrap/src/Controllers.cc @@ -271,8 +271,10 @@ namespace python boost::noncopyable>("BaseController") .def("reset", &AbstractController::reset, &AbstractControllerWrapper::default_reset, (bp::arg("self"), bp::arg("reset_dynamic_telemetry") = false)) - .def("compute_command", bp::pure_virtual(&AbstractController::computeCommand)) - .def("internal_dynamics", bp::pure_virtual(&AbstractController::internalDynamics)); + .def("compute_command", bp::pure_virtual(&AbstractController::computeCommand), + (bp::arg("self"), "t", "q", "v", "command")) + .def("internal_dynamics", bp::pure_virtual(&AbstractController::internalDynamics), + (bp::arg("self"), "t", "q", "v", "u_custom")); } }; From fa62e4091f2879bdd67b63e35dad00b7c84299ef Mon Sep 17 00:00:00 2001 From: Alexis DUBURCQ Date: Sun, 5 Sep 2021 02:04:21 +0200 Subject: [PATCH 5/8] [python/viewer] Fix meshcat notebook viewer. (#406) * [python/viewer] Fix meshcat interactive cell display. Co-authored-by: Alexis Duburcq --- examples/tutorial.ipynb | 1211 +++++++++-------- .../unit_py/test_pipeline_control.py | 9 +- .../src/jiminy_py/viewer/meshcat/recorder.py | 4 +- .../src/jiminy_py/viewer/meshcat/server.py | 36 +- .../src/jiminy_py/viewer/meshcat/wrapper.py | 43 +- .../jiminy_py/src/jiminy_py/viewer/viewer.py | 15 +- 6 files changed, 707 insertions(+), 611 deletions(-) diff --git a/examples/tutorial.ipynb b/examples/tutorial.ipynb index 4ee437e82..da13f48f1 100644 --- a/examples/tutorial.ipynb +++ b/examples/tutorial.ipynb @@ -31,7 +31,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 1, "metadata": { "tags": [] }, @@ -39,7 +39,7 @@ { "data": { "application/vnd.jupyter.widget-view+json": { - "model_id": "2cca83eadffa4a86904a50015cb21fff", + "model_id": "0b737ae3cb614de3bd3a56902ded6510", "version_major": 2, "version_minor": 0 }, @@ -109,45 +109,43 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 2, "metadata": {}, "outputs": [ { "data": { "application/javascript": [ "/* Put everything inside the global mpl namespace */\n", - "/* global mpl */\n", "window.mpl = {};\n", "\n", - "mpl.get_websocket_type = function () {\n", - " if (typeof WebSocket !== 'undefined') {\n", + "\n", + "mpl.get_websocket_type = function() {\n", + " if (typeof(WebSocket) !== 'undefined') {\n", " return WebSocket;\n", - " } else if (typeof MozWebSocket !== 'undefined') {\n", + " } else if (typeof(MozWebSocket) !== 'undefined') {\n", " return MozWebSocket;\n", " } else {\n", - " alert(\n", - " 'Your browser does not have WebSocket support. ' +\n", - " 'Please try Chrome, Safari or Firefox ≥ 6. ' +\n", - " 'Firefox 4 and 5 are also supported but you ' +\n", - " 'have to enable WebSockets in about:config.'\n", - " );\n", - " }\n", - "};\n", + " alert('Your browser does not have WebSocket support. ' +\n", + " 'Please try Chrome, Safari or Firefox ≥ 6. ' +\n", + " 'Firefox 4 and 5 are also supported but you ' +\n", + " 'have to enable WebSockets in about:config.');\n", + " };\n", + "}\n", "\n", - "mpl.figure = function (figure_id, websocket, ondownload, parent_element) {\n", + "mpl.figure = function(figure_id, websocket, ondownload, parent_element) {\n", " this.id = figure_id;\n", "\n", " this.ws = websocket;\n", "\n", - " this.supports_binary = this.ws.binaryType !== undefined;\n", + " this.supports_binary = (this.ws.binaryType != undefined);\n", "\n", " if (!this.supports_binary) {\n", - " var warnings = document.getElementById('mpl-warnings');\n", + " var warnings = document.getElementById(\"mpl-warnings\");\n", " if (warnings) {\n", " warnings.style.display = 'block';\n", - " warnings.textContent =\n", - " 'This browser does not support binary websocket messages. ' +\n", - " 'Performance may be slow.';\n", + " warnings.textContent = (\n", + " \"This browser does not support binary websocket messages. \" +\n", + " \"Performance may be slow.\");\n", " }\n", " }\n", "\n", @@ -162,11 +160,11 @@ "\n", " this.image_mode = 'full';\n", "\n", - " this.root = document.createElement('div');\n", - " this.root.setAttribute('style', 'display: inline-block');\n", - " this._root_extra_style(this.root);\n", + " this.root = $('
');\n", + " this._root_extra_style(this.root)\n", + " this.root.attr('style', 'display: inline-block');\n", "\n", - " parent_element.appendChild(this.root);\n", + " $(parent_element).append(this.root);\n", "\n", " this._init_header(this);\n", " this._init_canvas(this);\n", @@ -176,346 +174,281 @@ "\n", " this.waiting = false;\n", "\n", - " this.ws.onopen = function () {\n", - " fig.send_message('supports_binary', { value: fig.supports_binary });\n", - " fig.send_message('send_image_mode', {});\n", - " if (mpl.ratio !== 1) {\n", - " fig.send_message('set_dpi_ratio', { dpi_ratio: mpl.ratio });\n", + " this.ws.onopen = function () {\n", + " fig.send_message(\"supports_binary\", {value: fig.supports_binary});\n", + " fig.send_message(\"send_image_mode\", {});\n", + " if (mpl.ratio != 1) {\n", + " fig.send_message(\"set_dpi_ratio\", {'dpi_ratio': mpl.ratio});\n", + " }\n", + " fig.send_message(\"refresh\", {});\n", " }\n", - " fig.send_message('refresh', {});\n", - " };\n", "\n", - " this.imageObj.onload = function () {\n", - " if (fig.image_mode === 'full') {\n", - " // Full images could contain transparency (where diff images\n", - " // almost always do), so we need to clear the canvas so that\n", - " // there is no ghosting.\n", - " fig.context.clearRect(0, 0, fig.canvas.width, fig.canvas.height);\n", - " }\n", - " fig.context.drawImage(fig.imageObj, 0, 0);\n", - " };\n", + " this.imageObj.onload = function() {\n", + " if (fig.image_mode == 'full') {\n", + " // Full images could contain transparency (where diff images\n", + " // almost always do), so we need to clear the canvas so that\n", + " // there is no ghosting.\n", + " fig.context.clearRect(0, 0, fig.canvas.width, fig.canvas.height);\n", + " }\n", + " fig.context.drawImage(fig.imageObj, 0, 0);\n", + " };\n", "\n", - " this.imageObj.onunload = function () {\n", + " this.imageObj.onunload = function() {\n", " fig.ws.close();\n", - " };\n", + " }\n", "\n", " this.ws.onmessage = this._make_on_message_function(this);\n", "\n", " this.ondownload = ondownload;\n", - "};\n", + "}\n", "\n", - "mpl.figure.prototype._init_header = function () {\n", - " var titlebar = document.createElement('div');\n", - " titlebar.classList =\n", - " 'ui-dialog-titlebar ui-widget-header ui-corner-all ui-helper-clearfix';\n", - " var titletext = document.createElement('div');\n", - " titletext.classList = 'ui-dialog-title';\n", - " titletext.setAttribute(\n", - " 'style',\n", - " 'width: 100%; text-align: center; padding: 3px;'\n", - " );\n", - " titlebar.appendChild(titletext);\n", - " this.root.appendChild(titlebar);\n", - " this.header = titletext;\n", - "};\n", + "mpl.figure.prototype._init_header = function() {\n", + " var titlebar = $(\n", + " '
');\n", + " var titletext = $(\n", + " '
');\n", + " titlebar.append(titletext)\n", + " this.root.append(titlebar);\n", + " this.header = titletext[0];\n", + "}\n", "\n", - "mpl.figure.prototype._canvas_extra_style = function (_canvas_div) {};\n", "\n", - "mpl.figure.prototype._root_extra_style = function (_canvas_div) {};\n", "\n", - "mpl.figure.prototype._init_canvas = function () {\n", - " var fig = this;\n", + "mpl.figure.prototype._canvas_extra_style = function(canvas_div) {\n", "\n", - " var canvas_div = (this.canvas_div = document.createElement('div'));\n", - " canvas_div.setAttribute(\n", - " 'style',\n", - " 'border: 1px solid #ddd;' +\n", - " 'box-sizing: content-box;' +\n", - " 'clear: both;' +\n", - " 'min-height: 1px;' +\n", - " 'min-width: 1px;' +\n", - " 'outline: 0;' +\n", - " 'overflow: hidden;' +\n", - " 'position: relative;' +\n", - " 'resize: both;'\n", - " );\n", + "}\n", "\n", - " function on_keyboard_event_closure(name) {\n", - " return function (event) {\n", - " return fig.key_event(event, name);\n", - " };\n", - " }\n", "\n", - " canvas_div.addEventListener(\n", - " 'keydown',\n", - " on_keyboard_event_closure('key_press')\n", - " );\n", - " canvas_div.addEventListener(\n", - " 'keyup',\n", - " on_keyboard_event_closure('key_release')\n", - " );\n", + "mpl.figure.prototype._root_extra_style = function(canvas_div) {\n", "\n", - " this._canvas_extra_style(canvas_div);\n", - " this.root.appendChild(canvas_div);\n", + "}\n", "\n", - " var canvas = (this.canvas = document.createElement('canvas'));\n", - " canvas.classList.add('mpl-canvas');\n", - " canvas.setAttribute('style', 'box-sizing: content-box;');\n", + "mpl.figure.prototype._init_canvas = function() {\n", + " var fig = this;\n", "\n", - " this.context = canvas.getContext('2d');\n", + " var canvas_div = $('
');\n", "\n", - " var backingStore =\n", - " this.context.backingStorePixelRatio ||\n", - " this.context.webkitBackingStorePixelRatio ||\n", - " this.context.mozBackingStorePixelRatio ||\n", - " this.context.msBackingStorePixelRatio ||\n", - " this.context.oBackingStorePixelRatio ||\n", - " this.context.backingStorePixelRatio ||\n", - " 1;\n", + " canvas_div.attr('style', 'position: relative; clear: both; outline: 0');\n", "\n", - " mpl.ratio = (window.devicePixelRatio || 1) / backingStore;\n", + " function canvas_keyboard_event(event) {\n", + " return fig.key_event(event, event['data']);\n", + " }\n", "\n", - " var rubberband_canvas = (this.rubberband_canvas = document.createElement(\n", - " 'canvas'\n", - " ));\n", - " rubberband_canvas.setAttribute(\n", - " 'style',\n", - " 'box-sizing: content-box; position: absolute; left: 0; top: 0; z-index: 1;'\n", - " );\n", + " canvas_div.keydown('key_press', canvas_keyboard_event);\n", + " canvas_div.keyup('key_release', canvas_keyboard_event);\n", + " this.canvas_div = canvas_div\n", + " this._canvas_extra_style(canvas_div)\n", + " this.root.append(canvas_div);\n", "\n", - " var resizeObserver = new ResizeObserver(function (entries) {\n", - " var nentries = entries.length;\n", - " for (var i = 0; i < nentries; i++) {\n", - " var entry = entries[i];\n", - " var width, height;\n", - " if (entry.contentBoxSize) {\n", - " if (entry.contentBoxSize instanceof Array) {\n", - " // Chrome 84 implements new version of spec.\n", - " width = entry.contentBoxSize[0].inlineSize;\n", - " height = entry.contentBoxSize[0].blockSize;\n", - " } else {\n", - " // Firefox implements old version of spec.\n", - " width = entry.contentBoxSize.inlineSize;\n", - " height = entry.contentBoxSize.blockSize;\n", - " }\n", - " } else {\n", - " // Chrome <84 implements even older version of spec.\n", - " width = entry.contentRect.width;\n", - " height = entry.contentRect.height;\n", - " }\n", + " var canvas = $('');\n", + " canvas.addClass('mpl-canvas');\n", + " canvas.attr('style', \"left: 0; top: 0; z-index: 0; outline: 0\")\n", "\n", - " // Keep the size of the canvas and rubber band canvas in sync with\n", - " // the canvas container.\n", - " if (entry.devicePixelContentBoxSize) {\n", - " // Chrome 84 implements new version of spec.\n", - " canvas.setAttribute(\n", - " 'width',\n", - " entry.devicePixelContentBoxSize[0].inlineSize\n", - " );\n", - " canvas.setAttribute(\n", - " 'height',\n", - " entry.devicePixelContentBoxSize[0].blockSize\n", - " );\n", - " } else {\n", - " canvas.setAttribute('width', width * mpl.ratio);\n", - " canvas.setAttribute('height', height * mpl.ratio);\n", - " }\n", - " canvas.setAttribute(\n", - " 'style',\n", - " 'width: ' + width + 'px; height: ' + height + 'px;'\n", - " );\n", - "\n", - " rubberband_canvas.setAttribute('width', width);\n", - " rubberband_canvas.setAttribute('height', height);\n", - "\n", - " // And update the size in Python. We ignore the initial 0/0 size\n", - " // that occurs as the element is placed into the DOM, which should\n", - " // otherwise not happen due to the minimum size styling.\n", - " if (width != 0 && height != 0) {\n", - " fig.request_resize(width, height);\n", - " }\n", - " }\n", + " this.canvas = canvas[0];\n", + " this.context = canvas[0].getContext(\"2d\");\n", + "\n", + " var backingStore = this.context.backingStorePixelRatio ||\n", + "\tthis.context.webkitBackingStorePixelRatio ||\n", + "\tthis.context.mozBackingStorePixelRatio ||\n", + "\tthis.context.msBackingStorePixelRatio ||\n", + "\tthis.context.oBackingStorePixelRatio ||\n", + "\tthis.context.backingStorePixelRatio || 1;\n", + "\n", + " mpl.ratio = (window.devicePixelRatio || 1) / backingStore;\n", + "\n", + " var rubberband = $('');\n", + " rubberband.attr('style', \"position: absolute; left: 0; top: 0; z-index: 1;\")\n", + "\n", + " var pass_mouse_events = true;\n", + "\n", + " canvas_div.resizable({\n", + " start: function(event, ui) {\n", + " pass_mouse_events = false;\n", + " },\n", + " resize: function(event, ui) {\n", + " fig.request_resize(ui.size.width, ui.size.height);\n", + " },\n", + " stop: function(event, ui) {\n", + " pass_mouse_events = true;\n", + " fig.request_resize(ui.size.width, ui.size.height);\n", + " },\n", " });\n", - " resizeObserver.observe(canvas_div);\n", "\n", - " function on_mouse_event_closure(name) {\n", - " return function (event) {\n", - " return fig.mouse_event(event, name);\n", - " };\n", + " function mouse_event_fn(event) {\n", + " if (pass_mouse_events)\n", + " return fig.mouse_event(event, event['data']);\n", " }\n", "\n", - " rubberband_canvas.addEventListener(\n", - " 'mousedown',\n", - " on_mouse_event_closure('button_press')\n", - " );\n", - " rubberband_canvas.addEventListener(\n", - " 'mouseup',\n", - " on_mouse_event_closure('button_release')\n", - " );\n", + " rubberband.mousedown('button_press', mouse_event_fn);\n", + " rubberband.mouseup('button_release', mouse_event_fn);\n", " // Throttle sequential mouse events to 1 every 20ms.\n", - " rubberband_canvas.addEventListener(\n", - " 'mousemove',\n", - " on_mouse_event_closure('motion_notify')\n", - " );\n", + " rubberband.mousemove('motion_notify', mouse_event_fn);\n", "\n", - " rubberband_canvas.addEventListener(\n", - " 'mouseenter',\n", - " on_mouse_event_closure('figure_enter')\n", - " );\n", - " rubberband_canvas.addEventListener(\n", - " 'mouseleave',\n", - " on_mouse_event_closure('figure_leave')\n", - " );\n", + " rubberband.mouseenter('figure_enter', mouse_event_fn);\n", + " rubberband.mouseleave('figure_leave', mouse_event_fn);\n", "\n", - " canvas_div.addEventListener('wheel', function (event) {\n", + " canvas_div.on(\"wheel\", function (event) {\n", + " event = event.originalEvent;\n", + " event['data'] = 'scroll'\n", " if (event.deltaY < 0) {\n", " event.step = 1;\n", " } else {\n", " event.step = -1;\n", " }\n", - " on_mouse_event_closure('scroll')(event);\n", + " mouse_event_fn(event);\n", " });\n", "\n", - " canvas_div.appendChild(canvas);\n", - " canvas_div.appendChild(rubberband_canvas);\n", + " canvas_div.append(canvas);\n", + " canvas_div.append(rubberband);\n", "\n", - " this.rubberband_context = rubberband_canvas.getContext('2d');\n", - " this.rubberband_context.strokeStyle = '#000000';\n", + " this.rubberband = rubberband;\n", + " this.rubberband_canvas = rubberband[0];\n", + " this.rubberband_context = rubberband[0].getContext(\"2d\");\n", + " this.rubberband_context.strokeStyle = \"#000000\";\n", "\n", - " this._resize_canvas = function (width, height, forward) {\n", - " if (forward) {\n", - " canvas_div.style.width = width + 'px';\n", - " canvas_div.style.height = height + 'px';\n", - " }\n", - " };\n", + " this._resize_canvas = function(width, height) {\n", + " // Keep the size of the canvas, canvas container, and rubber band\n", + " // canvas in synch.\n", + " canvas_div.css('width', width)\n", + " canvas_div.css('height', height)\n", + "\n", + " canvas.attr('width', width * mpl.ratio);\n", + " canvas.attr('height', height * mpl.ratio);\n", + " canvas.attr('style', 'width: ' + width + 'px; height: ' + height + 'px;');\n", + "\n", + " rubberband.attr('width', width);\n", + " rubberband.attr('height', height);\n", + " }\n", + "\n", + " // Set the figure to an initial 600x600px, this will subsequently be updated\n", + " // upon first draw.\n", + " this._resize_canvas(600, 600);\n", "\n", " // Disable right mouse context menu.\n", - " this.rubberband_canvas.addEventListener('contextmenu', function (_e) {\n", - " event.preventDefault();\n", + " $(this.rubberband_canvas).bind(\"contextmenu\",function(e){\n", " return false;\n", " });\n", "\n", - " function set_focus() {\n", + " function set_focus () {\n", " canvas.focus();\n", " canvas_div.focus();\n", " }\n", "\n", " window.setTimeout(set_focus, 100);\n", - "};\n", + "}\n", "\n", - "mpl.figure.prototype._init_toolbar = function () {\n", + "mpl.figure.prototype._init_toolbar = function() {\n", " var fig = this;\n", "\n", - " var toolbar = document.createElement('div');\n", - " toolbar.classList = 'mpl-toolbar';\n", - " this.root.appendChild(toolbar);\n", + " var nav_element = $('
');\n", + " nav_element.attr('style', 'width: 100%');\n", + " this.root.append(nav_element);\n", "\n", - " function on_click_closure(name) {\n", - " return function (_event) {\n", - " return fig.toolbar_button_onclick(name);\n", - " };\n", + " // Define a callback function for later on.\n", + " function toolbar_event(event) {\n", + " return fig.toolbar_button_onclick(event['data']);\n", " }\n", - "\n", - " function on_mouseover_closure(tooltip) {\n", - " return function (event) {\n", - " if (!event.currentTarget.disabled) {\n", - " return fig.toolbar_button_onmouseover(tooltip);\n", - " }\n", - " };\n", + " function toolbar_mouse_event(event) {\n", + " return fig.toolbar_button_onmouseover(event['data']);\n", " }\n", "\n", - " fig.buttons = {};\n", - " var buttonGroup = document.createElement('div');\n", - " buttonGroup.classList = 'mpl-button-group';\n", - " for (var toolbar_ind in mpl.toolbar_items) {\n", + " for(var toolbar_ind in mpl.toolbar_items) {\n", " var name = mpl.toolbar_items[toolbar_ind][0];\n", " var tooltip = mpl.toolbar_items[toolbar_ind][1];\n", " var image = mpl.toolbar_items[toolbar_ind][2];\n", " var method_name = mpl.toolbar_items[toolbar_ind][3];\n", "\n", " if (!name) {\n", - " /* Instead of a spacer, we start a new button group. */\n", - " if (buttonGroup.hasChildNodes()) {\n", - " toolbar.appendChild(buttonGroup);\n", - " }\n", - " buttonGroup = document.createElement('div');\n", - " buttonGroup.classList = 'mpl-button-group';\n", + " // put a spacer in here.\n", " continue;\n", " }\n", - "\n", - " var button = (fig.buttons[name] = document.createElement('button'));\n", - " button.classList = 'mpl-widget';\n", - " button.setAttribute('role', 'button');\n", - " button.setAttribute('aria-disabled', 'false');\n", - " button.addEventListener('click', on_click_closure(method_name));\n", - " button.addEventListener('mouseover', on_mouseover_closure(tooltip));\n", - "\n", - " var icon_img = document.createElement('img');\n", - " icon_img.src = '_images/' + image + '.png';\n", - " icon_img.srcset = '_images/' + image + '_large.png 2x';\n", - " icon_img.alt = tooltip;\n", - " button.appendChild(icon_img);\n", - "\n", - " buttonGroup.appendChild(button);\n", + " var button = $('');\n", - " button.click(method_name, toolbar_event);\n", - " button.mouseover(tooltip, toolbar_mouse_event);\n", - " nav_element.append(button);\n", - " }\n", - "\n", - " // Add the status bar.\n", - " var status_bar = $('');\n", - " nav_element.append(status_bar);\n", - " this.message = status_bar[0];\n", - "\n", - " // Add the close button to the window.\n", - " var buttongrp = $('
');\n", - " var button = $('');\n", - " button.click(function (evt) { fig.handle_close(fig, {}); } );\n", - " button.mouseover('Stop Interaction', toolbar_mouse_event);\n", - " buttongrp.append(button);\n", - " var titlebar = this.root.find($('.ui-dialog-titlebar'));\n", - " titlebar.prepend(buttongrp);\n", - "}\n", - "\n", - "mpl.figure.prototype._root_extra_style = function(el){\n", - " var fig = this\n", - " el.on(\"remove\", function(){\n", - "\tfig.close_ws(fig, {});\n", - " });\n", - "}\n", - "\n", - "mpl.figure.prototype._canvas_extra_style = function(el){\n", - " // this is important to make the div 'focusable\n", - " el.attr('tabindex', 0)\n", - " // reach out to IPython and tell the keyboard manager to turn it's self\n", - " // off when our div gets focus\n", - "\n", - " // location in version 3\n", - " if (IPython.notebook.keyboard_manager) {\n", - " IPython.notebook.keyboard_manager.register_events(el);\n", - " }\n", - " else {\n", - " // location in version 2\n", - " IPython.keyboard_manager.register_events(el);\n", - " }\n", - "\n", - "}\n", - "\n", - "mpl.figure.prototype._key_event_extra = function(event, name) {\n", - " var manager = IPython.notebook.keyboard_manager;\n", - " if (!manager)\n", - " manager = IPython.keyboard_manager;\n", - "\n", - " // Check for shift+enter\n", - " if (event.shiftKey && event.which == 13) {\n", - " this.canvas_div.blur();\n", - " // select the cell after this one\n", - " var index = IPython.notebook.find_cell_index(this.cell_info[0]);\n", - " IPython.notebook.select(index + 1);\n", - " }\n", - "}\n", - "\n", - "mpl.figure.prototype.handle_save = function(fig, msg) {\n", - " fig.ondownload(fig, null);\n", - "}\n", - "\n", - "\n", - "mpl.find_output_cell = function(html_output) {\n", - " // Return the cell and output element which can be found *uniquely* in the notebook.\n", - " // Note - this is a bit hacky, but it is done because the \"notebook_saving.Notebook\"\n", - " // IPython event is triggered only after the cells have been serialised, which for\n", - " // our purposes (turning an active figure into a static one), is too late.\n", - " var cells = IPython.notebook.get_cells();\n", - " var ncells = cells.length;\n", - " for (var i=0; i= 3 moved mimebundle to data attribute of output\n", - " data = data.data;\n", - " }\n", - " if (data['text/html'] == html_output) {\n", - " return [cell, data, j];\n", - " }\n", - " }\n", - " }\n", - " }\n", - "}\n", - "\n", - "// Register the function which deals with the matplotlib target/channel.\n", - "// The kernel may be null if the page has been refreshed.\n", - "if (IPython.notebook.kernel != null) {\n", - " IPython.notebook.kernel.comm_manager.register_target('matplotlib', mpl.mpl_figure_comm);\n", - "}\n" - ], "text/plain": [ - "" - ] + "HBox(children=(FloatProgress(value=0.0, max=10.0), HTML(value='')))" + ], + "application/vnd.jupyter.widget-view+json": { + "version_major": 2, + "version_minor": 0, + "model_id": "50963f48cbd64d77b0b7ceee27f27adc" + } }, - "metadata": {}, - "output_type": "display_data" + "metadata": {} }, { - "data": { - "text/html": [ - "" - ], - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" + "output_type": "stream", + "name": "stdout", + "text": [ + "\n" + ] } ], + "metadata": { + "tags": [] + } + }, + { + "cell_type": "markdown", + "source": [ + "The simulation generates a log of its comuptation: this log can be retrieved by using ```simulator.get_log``` - and written to a file for latter processing by the engine with ```simulator.engine.write_log```." + ], + "metadata": {} + }, + { + "cell_type": "code", + "execution_count": 2, "source": [ "# Get dictionary of logged scalar variables\n", "log_data = simulator.log_data\n", "\n", "# Let's plot the joint position to see the pendulum fall.\n", - "%matplotlib notebook\n", + "%matplotlib inline\n", "import matplotlib.pyplot as plt\n", "\n", "plt.plot(log_data['Global.Time'], log_data['HighLevelController.currentPositionPendulum'])\n", "plt.title('Pendulum angle (rad)')\n", "plt.grid()\n", "plt.show()" - ] + ], + "outputs": [ + { + "output_type": "display_data", + "data": { + "text/plain": [ + "
" + ], + "image/png": "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" + }, + "metadata": { + "needs_background": "light" + } + } + ], + "metadata": {} }, { "cell_type": "markdown", - "metadata": {}, "source": [ "The results of a simulation can also be visualized in a 3D viewer: either `gepetto-gui` or `meshcat`. We use the latter here as it can be integrated in jupyter." - ] + ], + "metadata": {} }, { "cell_type": "code", "execution_count": 3, - "metadata": { - "scrolled": false - }, + "source": [ + "camera_xyzrpy = ([5.0, 0.0, 2.0e-5], [np.pi/2, 0.0, np.pi/2])\n", + "simulator.replay(camera_xyzrpy=camera_xyzrpy)" + ], "outputs": [ { - "name": "stdout", - "output_type": "stream", - "text": [ - "You can open the visualizer by visiting the following URL:\n", - "http://127.0.0.1:7000/static/\n" - ] - }, - { + "output_type": "display_data", "data": { + "text/plain": [ + "" + ], "text/html": [ "\n", "
\n", - " !function(e,t){"object"==typeof exports&&"object"==typeof module?module.exports=t():"function"==typeof define&&define.amd?define([],t):"object"==typeof exports?exports.MeshCat=t():e.MeshCat=t()}(window,(function(){return function(e){var t={};function n(r){if(t[r])return t[r].exports;var i=t[r]={i:r,l:!1,exports:{}};return e[r].call(i.exports,i,i.exports,n),i.l=!0,i.exports}return n.m=e,n.c=t,n.d=function(e,t,r){n.o(e,t)||Object.defineProperty(e,t,{enumerable:!0,get:r})},n.r=function(e){"undefined"!=typeof Symbol&&Symbol.toStringTag&&Object.defineProperty(e,Symbol.toStringTag,{value:"Module"}),Object.defineProperty(e,"__esModule",{value:!0})},n.t=function(e,t){if(1&t&&(e=n(e)),8&t)return e;if(4&t&&"object"==typeof e&&e&&e.__esModule)return e;var r=Object.create(null);if(n.r(r),Object.defineProperty(r,"default",{enumerable:!0,value:e}),2&t&&"string"!=typeof e)for(var i in e)n.d(r,i,function(t){return e[t]}.bind(null,i));return r},n.n=function(e){var t=e&&e.__esModule?function(){return e.default}:function(){return e};return n.d(t,"a",t),t},n.o=function(e,t){return Object.prototype.hasOwnProperty.call(e,t)},n.p="",n(n.s=27)}([function(e,t,n){"use strict";n.r(t),n.d(t,"ACESFilmicToneMapping",(function(){return ce})),n.d(t,"AddEquation",(function(){return R})),n.d(t,"AddOperation",(function(){return ne})),n.d(t,"AdditiveBlending",(function(){return S})),n.d(t,"AlphaFormat",(function(){return He})),n.d(t,"AlwaysDepth",(function(){return Y})),n.d(t,"AlwaysStencilFunc",(function(){return an})),n.d(t,"AmbientLight",(function(){return Xu})),n.d(t,"AmbientLightProbe",(function(){return vh})),n.d(t,"AnimationClip",(function(){return tu})),n.d(t,"AnimationLoader",(function(){return lu})),n.d(t,"AnimationMixer",(function(){return Yh})),n.d(t,"AnimationObjectGroup",(function(){return Wh})),n.d(t,"AnimationUtils",(function(){return Hl})),n.d(t,"ArcCurve",(function(){return vu})),n.d(t,"ArrayCamera",(function(){return fs})),n.d(t,"ArrowHelper",(function(){return Yd})),n.d(t,"Audio",(function(){return Ah})),n.d(t,"AudioAnalyser",(function(){return Nh})),n.d(t,"AudioContext",(function(){return dh})),n.d(t,"AudioListener",(function(){return Sh})),n.d(t,"AudioLoader",(function(){return ph})),n.d(t,"AxesHelper",(function(){return Xd})),n.d(t,"AxisHelper",(function(){return _p})),n.d(t,"BackSide",(function(){return v})),n.d(t,"BasicDepthPacking",(function(){return zt})),n.d(t,"BasicShadowMap",(function(){return d})),n.d(t,"BinaryTextureLoader",(function(){return Tp})),n.d(t,"Bone",(function(){return Xs})),n.d(t,"BooleanKeyframeTrack",(function(){return Xl})),n.d(t,"BoundingBoxHelper",(function(){return xp})),n.d(t,"Box2",(function(){return nd})),n.d(t,"Box3",(function(){return br})),n.d(t,"Box3Helper",(function(){return Hd})),n.d(t,"BoxBufferGeometry",(function(){return Ji})),n.d(t,"BoxGeometry",(function(){return Xi})),n.d(t,"BoxHelper",(function(){return Gd})),n.d(t,"BufferAttribute",(function(){return ri})),n.d(t,"BufferGeometry",(function(){return wi})),n.d(t,"BufferGeometryLoader",(function(){return eh})),n.d(t,"ByteType",(function(){return Pe})),n.d(t,"Cache",(function(){return ru})),n.d(t,"Camera",(function(){return no})),n.d(t,"CameraHelper",(function(){return Ud})),n.d(t,"CanvasRenderer",(function(){return Ap})),n.d(t,"CanvasTexture",(function(){return gc})),n.d(t,"CatmullRomCurve3",(function(){return Mu})),n.d(t,"CineonToneMapping",(function(){return se})),n.d(t,"CircleBufferGeometry",(function(){return Cl})),n.d(t,"CircleGeometry",(function(){return Ll})),n.d(t,"ClampToEdgeWrapping",(function(){return ye})),n.d(t,"Clock",(function(){return xh})),n.d(t,"ClosedSplineCurve3",(function(){return vp})),n.d(t,"Color",(function(){return Jr})),n.d(t,"ColorKeyframeTrack",(function(){return Jl})),n.d(t,"CompressedTexture",(function(){return mc})),n.d(t,"CompressedTextureLoader",(function(){return uu})),n.d(t,"ConeBufferGeometry",(function(){return Al})),n.d(t,"ConeGeometry",(function(){return Sl})),n.d(t,"CubeCamera",(function(){return ao})),n.d(t,"CubeGeometry",(function(){return Xi})),n.d(t,"CubeReflectionMapping",(function(){return ue})),n.d(t,"CubeRefractionMapping",(function(){return he})),n.d(t,"CubeTexture",(function(){return Po})),n.d(t,"CubeTextureLoader",(function(){return pu})),n.d(t,"CubeUVReflectionMapping",(function(){return me})),n.d(t,"CubeUVRefractionMapping",(function(){return ge})),n.d(t,"CubicBezierCurve",(function(){return Au})),n.d(t,"CubicBezierCurve3",(function(){return Lu})),n.d(t,"CubicInterpolant",(function(){return Vl})),n.d(t,"CullFaceBack",(function(){return s})),n.d(t,"CullFaceFront",(function(){return c})),n.d(t,"CullFaceFrontBack",(function(){return l})),n.d(t,"CullFaceNone",(function(){return a})),n.d(t,"Curve",(function(){return mu})),n.d(t,"CurvePath",(function(){return Du})),n.d(t,"CustomBlending",(function(){return C})),n.d(t,"CylinderBufferGeometry",(function(){return Tl})),n.d(t,"CylinderGeometry",(function(){return El})),n.d(t,"Cylindrical",(function(){return ed})),n.d(t,"DataTexture",(function(){return co})),n.d(t,"DataTexture2DArray",(function(){return Oo})),n.d(t,"DataTexture3D",(function(){return No})),n.d(t,"DataTextureLoader",(function(){return hu})),n.d(t,"DecrementStencilOp",(function(){return Xt})),n.d(t,"DecrementWrapStencilOp",(function(){return Zt})),n.d(t,"DefaultLoadingManager",(function(){return ou})),n.d(t,"DepthFormat",(function(){return Xe})),n.d(t,"DepthStencilFormat",(function(){return Je})),n.d(t,"DepthTexture",(function(){return vc})),n.d(t,"DirectionalLight",(function(){return Yu})),n.d(t,"DirectionalLightHelper",(function(){return Dd})),n.d(t,"DirectionalLightShadow",(function(){return qu})),n.d(t,"DiscreteInterpolant",(function(){return ql})),n.d(t,"DodecahedronBufferGeometry",(function(){return Rc})),n.d(t,"DodecahedronGeometry",(function(){return Cc})),n.d(t,"DoubleSide",(function(){return y})),n.d(t,"DstAlphaFactor",(function(){return G})),n.d(t,"DstColorFactor",(function(){return j})),n.d(t,"DynamicBufferAttribute",(function(){return sp})),n.d(t,"DynamicCopyUsage",(function(){return fn})),n.d(t,"DynamicDrawUsage",(function(){return cn})),n.d(t,"DynamicReadUsage",(function(){return hn})),n.d(t,"EdgesGeometry",(function(){return Ml})),n.d(t,"EdgesHelper",(function(){return wp})),n.d(t,"EllipseCurve",(function(){return gu})),n.d(t,"EqualDepth",(function(){return Z})),n.d(t,"EqualStencilFunc",(function(){return en})),n.d(t,"EquirectangularReflectionMapping",(function(){return de})),n.d(t,"EquirectangularRefractionMapping",(function(){return pe})),n.d(t,"Euler",(function(){return Vn})),n.d(t,"EventDispatcher",(function(){return gn})),n.d(t,"ExtrudeBufferGeometry",(function(){return ll})),n.d(t,"ExtrudeGeometry",(function(){return cl})),n.d(t,"Face3",(function(){return $r})),n.d(t,"Face4",(function(){return Jd})),n.d(t,"FaceColors",(function(){return w})),n.d(t,"FaceNormalsHelper",(function(){return Pd})),n.d(t,"FileLoader",(function(){return cu})),n.d(t,"FlatShading",(function(){return b})),n.d(t,"Float32Attribute",(function(){return mp})),n.d(t,"Float32BufferAttribute",(function(){return hi})),n.d(t,"Float64Attribute",(function(){return gp})),n.d(t,"Float64BufferAttribute",(function(){return di})),n.d(t,"FloatType",(function(){return Be})),n.d(t,"Fog",(function(){return Ms})),n.d(t,"FogExp2",(function(){return ws})),n.d(t,"Font",(function(){return lh})),n.d(t,"FontLoader",(function(){return hh})),n.d(t,"FrontFaceDirectionCCW",(function(){return h})),n.d(t,"FrontFaceDirectionCW",(function(){return u})),n.d(t,"FrontSide",(function(){return g})),n.d(t,"Frustum",(function(){return ho})),n.d(t,"GammaEncoding",(function(){return It})),n.d(t,"Geometry",(function(){return Yi})),n.d(t,"GeometryUtils",(function(){return Sp})),n.d(t,"GreaterDepth",(function(){return Q})),n.d(t,"GreaterEqualDepth",(function(){return K})),n.d(t,"GreaterEqualStencilFunc",(function(){return on})),n.d(t,"GreaterStencilFunc",(function(){return nn})),n.d(t,"GridHelper",(function(){return Td})),n.d(t,"Group",(function(){return ps})),n.d(t,"HalfFloatType",(function(){return ke})),n.d(t,"HemisphereLight",(function(){return Fu})),n.d(t,"HemisphereLightHelper",(function(){return Md})),n.d(t,"HemisphereLightProbe",(function(){return gh})),n.d(t,"IcosahedronBufferGeometry",(function(){return Lc})),n.d(t,"IcosahedronGeometry",(function(){return Ac})),n.d(t,"ImageBitmapLoader",(function(){return sh})),n.d(t,"ImageLoader",(function(){return du})),n.d(t,"ImageUtils",(function(){return Ln})),n.d(t,"ImmediateRenderObject",(function(){return ad})),n.d(t,"IncrementStencilOp",(function(){return Yt})),n.d(t,"IncrementWrapStencilOp",(function(){return Jt})),n.d(t,"InstancedBufferAttribute",(function(){return $u})),n.d(t,"InstancedBufferGeometry",(function(){return Qu})),n.d(t,"InstancedInterleavedBuffer",(function(){return Jh})),n.d(t,"InstancedMesh",(function(){return Js})),n.d(t,"Int16Attribute",(function(){return hp})),n.d(t,"Int16BufferAttribute",(function(){return si})),n.d(t,"Int32Attribute",(function(){return pp})),n.d(t,"Int32BufferAttribute",(function(){return li})),n.d(t,"Int8Attribute",(function(){return cp})),n.d(t,"Int8BufferAttribute",(function(){return ii})),n.d(t,"IntType",(function(){return Ie})),n.d(t,"InterleavedBuffer",(function(){return Es})),n.d(t,"InterleavedBufferAttribute",(function(){return Ts})),n.d(t,"Interpolant",(function(){return jl})),n.d(t,"InterpolateDiscrete",(function(){return Mt})),n.d(t,"InterpolateLinear",(function(){return Et})),n.d(t,"InterpolateSmooth",(function(){return Tt})),n.d(t,"InvertStencilOp",(function(){return Kt})),n.d(t,"JSONLoader",(function(){return Lp})),n.d(t,"KeepStencilOp",(function(){return Wt})),n.d(t,"KeyframeTrack",(function(){return Yl})),n.d(t,"LOD",(function(){return js})),n.d(t,"LatheBufferGeometry",(function(){return bl})),n.d(t,"LatheGeometry",(function(){return yl})),n.d(t,"Layers",(function(){return Wn})),n.d(t,"LensFlare",(function(){return Rp})),n.d(t,"LessDepth",(function(){return X})),n.d(t,"LessEqualDepth",(function(){return J})),n.d(t,"LessEqualStencilFunc",(function(){return tn})),n.d(t,"LessStencilFunc",(function(){return $t})),n.d(t,"Light",(function(){return Uu})),n.d(t,"LightProbe",(function(){return mh})),n.d(t,"LightProbeHelper",(function(){return Ed})),n.d(t,"LightShadow",(function(){return zu})),n.d(t,"Line",(function(){return nc})),n.d(t,"Line3",(function(){return od})),n.d(t,"LineBasicMaterial",(function(){return Zs})),n.d(t,"LineCurve",(function(){return Cu})),n.d(t,"LineCurve3",(function(){return Ru})),n.d(t,"LineDashedMaterial",(function(){return zl})),n.d(t,"LineLoop",(function(){return ac})),n.d(t,"LinePieces",(function(){return Kd})),n.d(t,"LineSegments",(function(){return oc})),n.d(t,"LineStrip",(function(){return Zd})),n.d(t,"LinearEncoding",(function(){return Ot})),n.d(t,"LinearFilter",(function(){return Te})),n.d(t,"LinearInterpolant",(function(){return Wl})),n.d(t,"LinearMipMapLinearFilter",(function(){return Ce})),n.d(t,"LinearMipMapNearestFilter",(function(){return Ae})),n.d(t,"LinearMipmapLinearFilter",(function(){return Le})),n.d(t,"LinearMipmapNearestFilter",(function(){return Se})),n.d(t,"LinearToneMapping",(function(){return ie})),n.d(t,"Loader",(function(){return au})),n.d(t,"LoaderUtils",(function(){return Ku})),n.d(t,"LoadingManager",(function(){return iu})),n.d(t,"LogLuvEncoding",(function(){return Bt})),n.d(t,"LoopOnce",(function(){return _t})),n.d(t,"LoopPingPong",(function(){return wt})),n.d(t,"LoopRepeat",(function(){return xt})),n.d(t,"LuminanceAlphaFormat",(function(){return qe})),n.d(t,"LuminanceFormat",(function(){return We})),n.d(t,"MOUSE",(function(){return i})),n.d(t,"Material",(function(){return ti})),n.d(t,"MaterialLoader",(function(){return Zu})),n.d(t,"Math",(function(){return bn})),n.d(t,"Matrix3",(function(){return An})),n.d(t,"Matrix4",(function(){return Gn})),n.d(t,"MaxEquation",(function(){return I})),n.d(t,"Mesh",(function(){return zi})),n.d(t,"MeshBasicMaterial",(function(){return ni})),n.d(t,"MeshDepthMaterial",(function(){return rs})),n.d(t,"MeshDistanceMaterial",(function(){return is})),n.d(t,"MeshFaceMaterial",(function(){return Qd})),n.d(t,"MeshLambertMaterial",(function(){return Ul})),n.d(t,"MeshMatcapMaterial",(function(){return Fl})),n.d(t,"MeshNormalMaterial",(function(){return kl})),n.d(t,"MeshPhongMaterial",(function(){return Dl})),n.d(t,"MeshPhysicalMaterial",(function(){return Il})),n.d(t,"MeshStandardMaterial",(function(){return Nl})),n.d(t,"MeshToonMaterial",(function(){return Bl})),n.d(t,"MinEquation",(function(){return N})),n.d(t,"MirroredRepeatWrapping",(function(){return be})),n.d(t,"MixOperation",(function(){return te})),n.d(t,"MultiMaterial",(function(){return $d})),n.d(t,"MultiplyBlending",(function(){return L})),n.d(t,"MultiplyOperation",(function(){return ee})),n.d(t,"NearestFilter",(function(){return _e})),n.d(t,"NearestMipMapLinearFilter",(function(){return Ee})),n.d(t,"NearestMipMapNearestFilter",(function(){return we})),n.d(t,"NearestMipmapLinearFilter",(function(){return Me})),n.d(t,"NearestMipmapNearestFilter",(function(){return xe})),n.d(t,"NeverDepth",(function(){return q})),n.d(t,"NeverStencilFunc",(function(){return Qt})),n.d(t,"NoBlending",(function(){return E})),n.d(t,"NoColors",(function(){return x})),n.d(t,"NoToneMapping",(function(){return re})),n.d(t,"NormalBlending",(function(){return T})),n.d(t,"NotEqualDepth",(function(){return $})),n.d(t,"NotEqualStencilFunc",(function(){return rn})),n.d(t,"NumberKeyframeTrack",(function(){return Zl})),n.d(t,"Object3D",(function(){return or})),n.d(t,"ObjectLoader",(function(){return nh})),n.d(t,"ObjectSpaceNormalMap",(function(){return jt})),n.d(t,"OctahedronBufferGeometry",(function(){return Sc})),n.d(t,"OctahedronGeometry",(function(){return Tc})),n.d(t,"OneFactor",(function(){return B})),n.d(t,"OneMinusDstAlphaFactor",(function(){return H})),n.d(t,"OneMinusDstColorFactor",(function(){return V})),n.d(t,"OneMinusSrcAlphaFactor",(function(){return z})),n.d(t,"OneMinusSrcColorFactor",(function(){return U})),n.d(t,"OrthographicCamera",(function(){return Wu})),n.d(t,"PCFShadowMap",(function(){return p})),n.d(t,"PCFSoftShadowMap",(function(){return f})),n.d(t,"ParametricBufferGeometry",(function(){return _c})),n.d(t,"ParametricGeometry",(function(){return bc})),n.d(t,"Particle",(function(){return tp})),n.d(t,"ParticleBasicMaterial",(function(){return ip})),n.d(t,"ParticleSystem",(function(){return np})),n.d(t,"ParticleSystemMaterial",(function(){return op})),n.d(t,"Path",(function(){return Bu})),n.d(t,"PerspectiveCamera",(function(){return ro})),n.d(t,"Plane",(function(){return Ir})),n.d(t,"PlaneBufferGeometry",(function(){return bo})),n.d(t,"PlaneGeometry",(function(){return yo})),n.d(t,"PlaneHelper",(function(){return jd})),n.d(t,"PointCloud",(function(){return ep})),n.d(t,"PointCloudMaterial",(function(){return rp})),n.d(t,"PointLight",(function(){return Vu})),n.d(t,"PointLightHelper",(function(){return yd})),n.d(t,"Points",(function(){return dc})),n.d(t,"PointsMaterial",(function(){return sc})),n.d(t,"PolarGridHelper",(function(){return Sd})),n.d(t,"PolyhedronBufferGeometry",(function(){return wc})),n.d(t,"PolyhedronGeometry",(function(){return xc})),n.d(t,"PositionalAudio",(function(){return Oh})),n.d(t,"PositionalAudioHelper",(function(){return Ad})),n.d(t,"PropertyBinding",(function(){return Vh})),n.d(t,"PropertyMixer",(function(){return Ih})),n.d(t,"QuadraticBezierCurve",(function(){return Pu})),n.d(t,"QuadraticBezierCurve3",(function(){return Ou})),n.d(t,"Quaternion",(function(){return xn})),n.d(t,"QuaternionKeyframeTrack",(function(){return Ql})),n.d(t,"QuaternionLinearInterpolant",(function(){return Kl})),n.d(t,"REVISION",(function(){return r})),n.d(t,"RGBADepthPacking",(function(){return Gt})),n.d(t,"RGBAFormat",(function(){return Ve})),n.d(t,"RGBA_ASTC_10x10_Format",(function(){return vt})),n.d(t,"RGBA_ASTC_10x5_Format",(function(){return ft})),n.d(t,"RGBA_ASTC_10x6_Format",(function(){return mt})),n.d(t,"RGBA_ASTC_10x8_Format",(function(){return gt})),n.d(t,"RGBA_ASTC_12x10_Format",(function(){return yt})),n.d(t,"RGBA_ASTC_12x12_Format",(function(){return bt})),n.d(t,"RGBA_ASTC_4x4_Format",(function(){return at})),n.d(t,"RGBA_ASTC_5x4_Format",(function(){return st})),n.d(t,"RGBA_ASTC_5x5_Format",(function(){return ct})),n.d(t,"RGBA_ASTC_6x5_Format",(function(){return lt})),n.d(t,"RGBA_ASTC_6x6_Format",(function(){return ut})),n.d(t,"RGBA_ASTC_8x5_Format",(function(){return ht})),n.d(t,"RGBA_ASTC_8x6_Format",(function(){return dt})),n.d(t,"RGBA_ASTC_8x8_Format",(function(){return pt})),n.d(t,"RGBA_PVRTC_2BPPV1_Format",(function(){return it})),n.d(t,"RGBA_PVRTC_4BPPV1_Format",(function(){return rt})),n.d(t,"RGBA_S3TC_DXT1_Format",(function(){return Qe})),n.d(t,"RGBA_S3TC_DXT3_Format",(function(){return $e})),n.d(t,"RGBA_S3TC_DXT5_Format",(function(){return et})),n.d(t,"RGBDEncoding",(function(){return Ft})),n.d(t,"RGBEEncoding",(function(){return Dt})),n.d(t,"RGBEFormat",(function(){return Ye})),n.d(t,"RGBFormat",(function(){return je})),n.d(t,"RGBM16Encoding",(function(){return Ut})),n.d(t,"RGBM7Encoding",(function(){return kt})),n.d(t,"RGB_ETC1_Format",(function(){return ot})),n.d(t,"RGB_PVRTC_2BPPV1_Format",(function(){return nt})),n.d(t,"RGB_PVRTC_4BPPV1_Format",(function(){return tt})),n.d(t,"RGB_S3TC_DXT1_Format",(function(){return Ke})),n.d(t,"RawShaderMaterial",(function(){return Ol})),n.d(t,"Ray",(function(){return Rr})),n.d(t,"Raycaster",(function(){return Zh})),n.d(t,"RectAreaLight",(function(){return Ju})),n.d(t,"RectAreaLightHelper",(function(){return bd})),n.d(t,"RedFormat",(function(){return Ze})),n.d(t,"ReinhardToneMapping",(function(){return oe})),n.d(t,"RepeatWrapping",(function(){return ve})),n.d(t,"ReplaceStencilOp",(function(){return qt})),n.d(t,"ReverseSubtractEquation",(function(){return O})),n.d(t,"RingBufferGeometry",(function(){return vl})),n.d(t,"RingGeometry",(function(){return gl})),n.d(t,"Scene",(function(){return ar})),n.d(t,"SceneUtils",(function(){return Cp})),n.d(t,"ShaderChunk",(function(){return po})),n.d(t,"ShaderLib",(function(){return mo})),n.d(t,"ShaderMaterial",(function(){return to})),n.d(t,"ShadowMaterial",(function(){return Pl})),n.d(t,"Shape",(function(){return ku})),n.d(t,"ShapeBufferGeometry",(function(){return xl})),n.d(t,"ShapeGeometry",(function(){return _l})),n.d(t,"ShapePath",(function(){return ch})),n.d(t,"ShapeUtils",(function(){return ol})),n.d(t,"ShortType",(function(){return Oe})),n.d(t,"Skeleton",(function(){return Ys})),n.d(t,"SkeletonHelper",(function(){return vd})),n.d(t,"SkinnedMesh",(function(){return Vs})),n.d(t,"SmoothShading",(function(){return _})),n.d(t,"Sphere",(function(){return wr})),n.d(t,"SphereBufferGeometry",(function(){return ml})),n.d(t,"SphereGeometry",(function(){return fl})),n.d(t,"Spherical",(function(){return $h})),n.d(t,"SphericalHarmonics3",(function(){return fh})),n.d(t,"SphericalReflectionMapping",(function(){return fe})),n.d(t,"Spline",(function(){return bp})),n.d(t,"SplineCurve",(function(){return Nu})),n.d(t,"SplineCurve3",(function(){return yp})),n.d(t,"SpotLight",(function(){return Hu})),n.d(t,"SpotLightHelper",(function(){return pd})),n.d(t,"SpotLightShadow",(function(){return Gu})),n.d(t,"Sprite",(function(){return Fs})),n.d(t,"SpriteMaterial",(function(){return Ss})),n.d(t,"SrcAlphaFactor",(function(){return F})),n.d(t,"SrcAlphaSaturateFactor",(function(){return W})),n.d(t,"SrcColorFactor",(function(){return k})),n.d(t,"StaticCopyUsage",(function(){return pn})),n.d(t,"StaticDrawUsage",(function(){return sn})),n.d(t,"StaticReadUsage",(function(){return un})),n.d(t,"StereoCamera",(function(){return _h})),n.d(t,"StreamCopyUsage",(function(){return mn})),n.d(t,"StreamDrawUsage",(function(){return ln})),n.d(t,"StreamReadUsage",(function(){return dn})),n.d(t,"StringKeyframeTrack",(function(){return $l})),n.d(t,"SubtractEquation",(function(){return P})),n.d(t,"SubtractiveBlending",(function(){return A})),n.d(t,"TOUCH",(function(){return o})),n.d(t,"TangentSpaceNormalMap",(function(){return Ht})),n.d(t,"TetrahedronBufferGeometry",(function(){return Ec})),n.d(t,"TetrahedronGeometry",(function(){return Mc})),n.d(t,"TextBufferGeometry",(function(){return pl})),n.d(t,"TextGeometry",(function(){return dl})),n.d(t,"Texture",(function(){return Rn})),n.d(t,"TextureLoader",(function(){return fu})),n.d(t,"TorusBufferGeometry",(function(){return Bc})),n.d(t,"TorusGeometry",(function(){return Dc})),n.d(t,"TorusKnotBufferGeometry",(function(){return Ic})),n.d(t,"TorusKnotGeometry",(function(){return Nc})),n.d(t,"Triangle",(function(){return Wr})),n.d(t,"TriangleFanDrawMode",(function(){return Pt})),n.d(t,"TriangleStripDrawMode",(function(){return Rt})),n.d(t,"TrianglesDrawMode",(function(){return Ct})),n.d(t,"TubeBufferGeometry",(function(){return Oc})),n.d(t,"TubeGeometry",(function(){return Pc})),n.d(t,"UVMapping",(function(){return le})),n.d(t,"Uint16Attribute",(function(){return dp})),n.d(t,"Uint16BufferAttribute",(function(){return ci})),n.d(t,"Uint32Attribute",(function(){return fp})),n.d(t,"Uint32BufferAttribute",(function(){return ui})),n.d(t,"Uint8Attribute",(function(){return lp})),n.d(t,"Uint8BufferAttribute",(function(){return oi})),n.d(t,"Uint8ClampedAttribute",(function(){return up})),n.d(t,"Uint8ClampedBufferAttribute",(function(){return ai})),n.d(t,"Uncharted2ToneMapping",(function(){return ae})),n.d(t,"Uniform",(function(){return Xh})),n.d(t,"UniformsLib",(function(){return fo})),n.d(t,"UniformsUtils",(function(){return Qi})),n.d(t,"UnsignedByteType",(function(){return Re})),n.d(t,"UnsignedInt248Type",(function(){return Ge})),n.d(t,"UnsignedIntType",(function(){return De})),n.d(t,"UnsignedShort4444Type",(function(){return Ue})),n.d(t,"UnsignedShort5551Type",(function(){return Fe})),n.d(t,"UnsignedShort565Type",(function(){return ze})),n.d(t,"UnsignedShortType",(function(){return Ne})),n.d(t,"VSMShadowMap",(function(){return m})),n.d(t,"Vector2",(function(){return _n})),n.d(t,"Vector3",(function(){return En})),n.d(t,"Vector4",(function(){return Pn})),n.d(t,"VectorKeyframeTrack",(function(){return eu})),n.d(t,"Vertex",(function(){return ap})),n.d(t,"VertexColors",(function(){return M})),n.d(t,"VertexNormalsHelper",(function(){return hd})),n.d(t,"VideoTexture",(function(){return fc})),n.d(t,"WebGLMultisampleRenderTarget",(function(){return Nn})),n.d(t,"WebGLRenderTarget",(function(){return On})),n.d(t,"WebGLRenderTargetCube",(function(){return so})),n.d(t,"WebGLRenderer",(function(){return xs})),n.d(t,"WebGLUtils",(function(){return us})),n.d(t,"WireframeGeometry",(function(){return yc})),n.d(t,"WireframeHelper",(function(){return Mp})),n.d(t,"WrapAroundEnding",(function(){return Lt})),n.d(t,"XHRLoader",(function(){return Ep})),n.d(t,"ZeroCurvatureEnding",(function(){return St})),n.d(t,"ZeroFactor",(function(){return D})),n.d(t,"ZeroSlopeEnding",(function(){return At})),n.d(t,"ZeroStencilOp",(function(){return Vt})),n.d(t,"sRGBEncoding",(function(){return Nt})),void 0===Number.EPSILON&&(Number.EPSILON=Math.pow(2,-52)),void 0===Number.isInteger&&(Number.isInteger=function(e){return"number"==typeof e&&isFinite(e)&&Math.floor(e)===e}),void 0===Math.sign&&(Math.sign=function(e){return e<0?-1:e>0?1:+e}),"name"in Function.prototype==!1&&Object.defineProperty(Function.prototype,"name",{get:function(){return this.toString().match(/^\\s*function\\s*([^\\(\\s]*)/)[1]}}),void 0===Object.assign&&(Object.assign=function(e){if(null==e)throw new TypeError("Cannot convert undefined or null to object");for(var t=Object(e),n=1;n>8&255]+vn[e>>16&255]+vn[e>>24&255]+"-"+vn[255&t]+vn[t>>8&255]+"-"+vn[t>>16&15|64]+vn[t>>24&255]+"-"+vn[63&n|128]+vn[n>>8&255]+"-"+vn[n>>16&255]+vn[n>>24&255]+vn[255&r]+vn[r>>8&255]+vn[r>>16&255]+vn[r>>24&255]).toUpperCase()},clamp:function(e,t,n){return Math.max(t,Math.min(n,e))},euclideanModulo:function(e,t){return(e%t+t)%t},mapLinear:function(e,t,n,r,i){return r+(e-t)*(i-r)/(n-t)},lerp:function(e,t,n){return(1-n)*e+n*t},smoothstep:function(e,t,n){return e<=t?0:e>=n?1:(e=(e-t)/(n-t))*e*(3-2*e)},smootherstep:function(e,t,n){return e<=t?0:e>=n?1:(e=(e-t)/(n-t))*e*e*(e*(6*e-15)+10)},randInt:function(e,t){return e+Math.floor(Math.random()*(t-e+1))},randFloat:function(e,t){return e+Math.random()*(t-e)},randFloatSpread:function(e){return e*(.5-Math.random())},degToRad:function(e){return e*bn.DEG2RAD},radToDeg:function(e){return e*bn.RAD2DEG},isPowerOfTwo:function(e){return 0==(e&e-1)&&0!==e},ceilPowerOfTwo:function(e){return Math.pow(2,Math.ceil(Math.log(e)/Math.LN2))},floorPowerOfTwo:function(e){return Math.pow(2,Math.floor(Math.log(e)/Math.LN2))}};function _n(e,t){this.x=e||0,this.y=t||0}function xn(e,t,n,r){this._x=e||0,this._y=t||0,this._z=n||0,this._w=void 0!==r?r:1}Object.defineProperties(_n.prototype,{width:{get:function(){return this.x},set:function(e){this.x=e}},height:{get:function(){return this.y},set:function(e){this.y=e}}}),Object.assign(_n.prototype,{isVector2:!0,set:function(e,t){return this.x=e,this.y=t,this},setScalar:function(e){return this.x=e,this.y=e,this},setX:function(e){return this.x=e,this},setY:function(e){return this.y=e,this},setComponent:function(e,t){switch(e){case 0:this.x=t;break;case 1:this.y=t;break;default:throw new Error("index is out of range: "+e)}return this},getComponent:function(e){switch(e){case 0:return this.x;case 1:return this.y;default:throw new Error("index is out of range: "+e)}},clone:function(){return new this.constructor(this.x,this.y)},copy:function(e){return this.x=e.x,this.y=e.y,this},add:function(e,t){return void 0!==t?(console.warn("THREE.Vector2: .add() now only accepts one argument. Use .addVectors( a, b ) instead."),this.addVectors(e,t)):(this.x+=e.x,this.y+=e.y,this)},addScalar:function(e){return this.x+=e,this.y+=e,this},addVectors:function(e,t){return this.x=e.x+t.x,this.y=e.y+t.y,this},addScaledVector:function(e,t){return this.x+=e.x*t,this.y+=e.y*t,this},sub:function(e,t){return void 0!==t?(console.warn("THREE.Vector2: .sub() now only accepts one argument. Use .subVectors( a, b ) instead."),this.subVectors(e,t)):(this.x-=e.x,this.y-=e.y,this)},subScalar:function(e){return this.x-=e,this.y-=e,this},subVectors:function(e,t){return this.x=e.x-t.x,this.y=e.y-t.y,this},multiply:function(e){return this.x*=e.x,this.y*=e.y,this},multiplyScalar:function(e){return this.x*=e,this.y*=e,this},divide:function(e){return this.x/=e.x,this.y/=e.y,this},divideScalar:function(e){return this.multiplyScalar(1/e)},applyMatrix3:function(e){var t=this.x,n=this.y,r=e.elements;return this.x=r[0]*t+r[3]*n+r[6],this.y=r[1]*t+r[4]*n+r[7],this},min:function(e){return this.x=Math.min(this.x,e.x),this.y=Math.min(this.y,e.y),this},max:function(e){return this.x=Math.max(this.x,e.x),this.y=Math.max(this.y,e.y),this},clamp:function(e,t){return this.x=Math.max(e.x,Math.min(t.x,this.x)),this.y=Math.max(e.y,Math.min(t.y,this.y)),this},clampScalar:function(e,t){return this.x=Math.max(e,Math.min(t,this.x)),this.y=Math.max(e,Math.min(t,this.y)),this},clampLength:function(e,t){var n=this.length();return this.divideScalar(n||1).multiplyScalar(Math.max(e,Math.min(t,n)))},floor:function(){return this.x=Math.floor(this.x),this.y=Math.floor(this.y),this},ceil:function(){return this.x=Math.ceil(this.x),this.y=Math.ceil(this.y),this},round:function(){return this.x=Math.round(this.x),this.y=Math.round(this.y),this},roundToZero:function(){return this.x=this.x<0?Math.ceil(this.x):Math.floor(this.x),this.y=this.y<0?Math.ceil(this.y):Math.floor(this.y),this},negate:function(){return this.x=-this.x,this.y=-this.y,this},dot:function(e){return this.x*e.x+this.y*e.y},cross:function(e){return this.x*e.y-this.y*e.x},lengthSq:function(){return this.x*this.x+this.y*this.y},length:function(){return Math.sqrt(this.x*this.x+this.y*this.y)},manhattanLength:function(){return Math.abs(this.x)+Math.abs(this.y)},normalize:function(){return this.divideScalar(this.length()||1)},angle:function(){var e=Math.atan2(this.y,this.x);return e<0&&(e+=2*Math.PI),e},distanceTo:function(e){return Math.sqrt(this.distanceToSquared(e))},distanceToSquared:function(e){var t=this.x-e.x,n=this.y-e.y;return t*t+n*n},manhattanDistanceTo:function(e){return Math.abs(this.x-e.x)+Math.abs(this.y-e.y)},setLength:function(e){return this.normalize().multiplyScalar(e)},lerp:function(e,t){return this.x+=(e.x-this.x)*t,this.y+=(e.y-this.y)*t,this},lerpVectors:function(e,t,n){return this.subVectors(t,e).multiplyScalar(n).add(e)},equals:function(e){return e.x===this.x&&e.y===this.y},fromArray:function(e,t){return void 0===t&&(t=0),this.x=e[t],this.y=e[t+1],this},toArray:function(e,t){return void 0===e&&(e=[]),void 0===t&&(t=0),e[t]=this.x,e[t+1]=this.y,e},fromBufferAttribute:function(e,t,n){return void 0!==n&&console.warn("THREE.Vector2: offset has been removed from .fromBufferAttribute()."),this.x=e.getX(t),this.y=e.getY(t),this},rotateAround:function(e,t){var n=Math.cos(t),r=Math.sin(t),i=this.x-e.x,o=this.y-e.y;return this.x=i*n-o*r+e.x,this.y=i*r+o*n+e.y,this}}),Object.assign(xn,{slerp:function(e,t,n,r){return n.copy(e).slerp(t,r)},slerpFlat:function(e,t,n,r,i,o,a){var s=n[r+0],c=n[r+1],l=n[r+2],u=n[r+3],h=i[o+0],d=i[o+1],p=i[o+2],f=i[o+3];if(u!==f||s!==h||c!==d||l!==p){var m=1-a,g=s*h+c*d+l*p+u*f,v=g>=0?1:-1,y=1-g*g;if(y>Number.EPSILON){var b=Math.sqrt(y),_=Math.atan2(b,g*v);m=Math.sin(m*_)/b,a=Math.sin(a*_)/b}var x=a*v;if(s=s*m+h*x,c=c*m+d*x,l=l*m+p*x,u=u*m+f*x,m===1-a){var w=1/Math.sqrt(s*s+c*c+l*l+u*u);s*=w,c*=w,l*=w,u*=w}}e[t]=s,e[t+1]=c,e[t+2]=l,e[t+3]=u}}),Object.defineProperties(xn.prototype,{x:{get:function(){return this._x},set:function(e){this._x=e,this._onChangeCallback()}},y:{get:function(){return this._y},set:function(e){this._y=e,this._onChangeCallback()}},z:{get:function(){return this._z},set:function(e){this._z=e,this._onChangeCallback()}},w:{get:function(){return this._w},set:function(e){this._w=e,this._onChangeCallback()}}}),Object.assign(xn.prototype,{isQuaternion:!0,set:function(e,t,n,r){return this._x=e,this._y=t,this._z=n,this._w=r,this._onChangeCallback(),this},clone:function(){return new this.constructor(this._x,this._y,this._z,this._w)},copy:function(e){return this._x=e.x,this._y=e.y,this._z=e.z,this._w=e.w,this._onChangeCallback(),this},setFromEuler:function(e,t){if(!e||!e.isEuler)throw new Error("THREE.Quaternion: .setFromEuler() now expects an Euler rotation rather than a Vector3 and order.");var n=e._x,r=e._y,i=e._z,o=e.order,a=Math.cos,s=Math.sin,c=a(n/2),l=a(r/2),u=a(i/2),h=s(n/2),d=s(r/2),p=s(i/2);return"XYZ"===o?(this._x=h*l*u+c*d*p,this._y=c*d*u-h*l*p,this._z=c*l*p+h*d*u,this._w=c*l*u-h*d*p):"YXZ"===o?(this._x=h*l*u+c*d*p,this._y=c*d*u-h*l*p,this._z=c*l*p-h*d*u,this._w=c*l*u+h*d*p):"ZXY"===o?(this._x=h*l*u-c*d*p,this._y=c*d*u+h*l*p,this._z=c*l*p+h*d*u,this._w=c*l*u-h*d*p):"ZYX"===o?(this._x=h*l*u-c*d*p,this._y=c*d*u+h*l*p,this._z=c*l*p-h*d*u,this._w=c*l*u+h*d*p):"YZX"===o?(this._x=h*l*u+c*d*p,this._y=c*d*u+h*l*p,this._z=c*l*p-h*d*u,this._w=c*l*u-h*d*p):"XZY"===o&&(this._x=h*l*u-c*d*p,this._y=c*d*u-h*l*p,this._z=c*l*p+h*d*u,this._w=c*l*u+h*d*p),!1!==t&&this._onChangeCallback(),this},setFromAxisAngle:function(e,t){var n=t/2,r=Math.sin(n);return this._x=e.x*r,this._y=e.y*r,this._z=e.z*r,this._w=Math.cos(n),this._onChangeCallback(),this},setFromRotationMatrix:function(e){var t,n=e.elements,r=n[0],i=n[4],o=n[8],a=n[1],s=n[5],c=n[9],l=n[2],u=n[6],h=n[10],d=r+s+h;return d>0?(t=.5/Math.sqrt(d+1),this._w=.25/t,this._x=(u-c)*t,this._y=(o-l)*t,this._z=(a-i)*t):r>s&&r>h?(t=2*Math.sqrt(1+r-s-h),this._w=(u-c)/t,this._x=.25*t,this._y=(i+a)/t,this._z=(o+l)/t):s>h?(t=2*Math.sqrt(1+s-r-h),this._w=(o-l)/t,this._x=(i+a)/t,this._y=.25*t,this._z=(c+u)/t):(t=2*Math.sqrt(1+h-r-s),this._w=(a-i)/t,this._x=(o+l)/t,this._y=(c+u)/t,this._z=.25*t),this._onChangeCallback(),this},setFromUnitVectors:function(e,t){var n=e.dot(t)+1;return n<1e-6?(n=0,Math.abs(e.x)>Math.abs(e.z)?(this._x=-e.y,this._y=e.x,this._z=0,this._w=n):(this._x=0,this._y=-e.z,this._z=e.y,this._w=n)):(this._x=e.y*t.z-e.z*t.y,this._y=e.z*t.x-e.x*t.z,this._z=e.x*t.y-e.y*t.x,this._w=n),this.normalize()},angleTo:function(e){return 2*Math.acos(Math.abs(bn.clamp(this.dot(e),-1,1)))},rotateTowards:function(e,t){var n=this.angleTo(e);if(0===n)return this;var r=Math.min(1,t/n);return this.slerp(e,r),this},inverse:function(){return this.conjugate()},conjugate:function(){return this._x*=-1,this._y*=-1,this._z*=-1,this._onChangeCallback(),this},dot:function(e){return this._x*e._x+this._y*e._y+this._z*e._z+this._w*e._w},lengthSq:function(){return this._x*this._x+this._y*this._y+this._z*this._z+this._w*this._w},length:function(){return Math.sqrt(this._x*this._x+this._y*this._y+this._z*this._z+this._w*this._w)},normalize:function(){var e=this.length();return 0===e?(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:function(e,t){return void 0!==t?(console.warn("THREE.Quaternion: .multiply() now only accepts one argument. Use .multiplyQuaternions( a, b ) instead."),this.multiplyQuaternions(e,t)):this.multiplyQuaternions(this,e)},premultiply:function(e){return this.multiplyQuaternions(e,this)},multiplyQuaternions:function(e,t){var n=e._x,r=e._y,i=e._z,o=e._w,a=t._x,s=t._y,c=t._z,l=t._w;return this._x=n*l+o*a+r*c-i*s,this._y=r*l+o*s+i*a-n*c,this._z=i*l+o*c+n*s-r*a,this._w=o*l-n*a-r*s-i*c,this._onChangeCallback(),this},slerp:function(e,t){if(0===t)return this;if(1===t)return this.copy(e);var n=this._x,r=this._y,i=this._z,o=this._w,a=o*e._w+n*e._x+r*e._y+i*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=n,this._y=r,this._z=i,this;var s=1-a*a;if(s<=Number.EPSILON){var c=1-t;return this._w=c*o+t*this._w,this._x=c*n+t*this._x,this._y=c*r+t*this._y,this._z=c*i+t*this._z,this.normalize(),this._onChangeCallback(),this}var l=Math.sqrt(s),u=Math.atan2(l,a),h=Math.sin((1-t)*u)/l,d=Math.sin(t*u)/l;return this._w=o*h+this._w*d,this._x=n*h+this._x*d,this._y=r*h+this._y*d,this._z=i*h+this._z*d,this._onChangeCallback(),this},equals:function(e){return e._x===this._x&&e._y===this._y&&e._z===this._z&&e._w===this._w},fromArray:function(e,t){return void 0===t&&(t=0),this._x=e[t],this._y=e[t+1],this._z=e[t+2],this._w=e[t+3],this._onChangeCallback(),this},toArray:function(e,t){return void 0===e&&(e=[]),void 0===t&&(t=0),e[t]=this._x,e[t+1]=this._y,e[t+2]=this._z,e[t+3]=this._w,e},_onChange:function(e){return this._onChangeCallback=e,this},_onChangeCallback:function(){}});var wn=new En,Mn=new xn;function En(e,t,n){this.x=e||0,this.y=t||0,this.z=n||0}Object.assign(En.prototype,{isVector3:!0,set:function(e,t,n){return this.x=e,this.y=t,this.z=n,this},setScalar:function(e){return this.x=e,this.y=e,this.z=e,this},setX:function(e){return this.x=e,this},setY:function(e){return this.y=e,this},setZ:function(e){return this.z=e,this},setComponent:function(e,t){switch(e){case 0:this.x=t;break;case 1:this.y=t;break;case 2:this.z=t;break;default:throw new Error("index is out of range: "+e)}return this},getComponent:function(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:function(){return new this.constructor(this.x,this.y,this.z)},copy:function(e){return this.x=e.x,this.y=e.y,this.z=e.z,this},add:function(e,t){return void 0!==t?(console.warn("THREE.Vector3: .add() now only accepts one argument. Use .addVectors( a, b ) instead."),this.addVectors(e,t)):(this.x+=e.x,this.y+=e.y,this.z+=e.z,this)},addScalar:function(e){return this.x+=e,this.y+=e,this.z+=e,this},addVectors:function(e,t){return this.x=e.x+t.x,this.y=e.y+t.y,this.z=e.z+t.z,this},addScaledVector:function(e,t){return this.x+=e.x*t,this.y+=e.y*t,this.z+=e.z*t,this},sub:function(e,t){return void 0!==t?(console.warn("THREE.Vector3: .sub() now only accepts one argument. Use .subVectors( a, b ) instead."),this.subVectors(e,t)):(this.x-=e.x,this.y-=e.y,this.z-=e.z,this)},subScalar:function(e){return this.x-=e,this.y-=e,this.z-=e,this},subVectors:function(e,t){return this.x=e.x-t.x,this.y=e.y-t.y,this.z=e.z-t.z,this},multiply:function(e,t){return void 0!==t?(console.warn("THREE.Vector3: .multiply() now only accepts one argument. Use .multiplyVectors( a, b ) instead."),this.multiplyVectors(e,t)):(this.x*=e.x,this.y*=e.y,this.z*=e.z,this)},multiplyScalar:function(e){return this.x*=e,this.y*=e,this.z*=e,this},multiplyVectors:function(e,t){return this.x=e.x*t.x,this.y=e.y*t.y,this.z=e.z*t.z,this},applyEuler:function(e){return e&&e.isEuler||console.error("THREE.Vector3: .applyEuler() now expects an Euler rotation rather than a Vector3 and order."),this.applyQuaternion(Mn.setFromEuler(e))},applyAxisAngle:function(e,t){return this.applyQuaternion(Mn.setFromAxisAngle(e,t))},applyMatrix3:function(e){var t=this.x,n=this.y,r=this.z,i=e.elements;return this.x=i[0]*t+i[3]*n+i[6]*r,this.y=i[1]*t+i[4]*n+i[7]*r,this.z=i[2]*t+i[5]*n+i[8]*r,this},applyMatrix4:function(e){var t=this.x,n=this.y,r=this.z,i=e.elements,o=1/(i[3]*t+i[7]*n+i[11]*r+i[15]);return this.x=(i[0]*t+i[4]*n+i[8]*r+i[12])*o,this.y=(i[1]*t+i[5]*n+i[9]*r+i[13])*o,this.z=(i[2]*t+i[6]*n+i[10]*r+i[14])*o,this},applyQuaternion:function(e){var t=this.x,n=this.y,r=this.z,i=e.x,o=e.y,a=e.z,s=e.w,c=s*t+o*r-a*n,l=s*n+a*t-i*r,u=s*r+i*n-o*t,h=-i*t-o*n-a*r;return this.x=c*s+h*-i+l*-a-u*-o,this.y=l*s+h*-o+u*-i-c*-a,this.z=u*s+h*-a+c*-o-l*-i,this},project:function(e){return this.applyMatrix4(e.matrixWorldInverse).applyMatrix4(e.projectionMatrix)},unproject:function(e){return this.applyMatrix4(e.projectionMatrixInverse).applyMatrix4(e.matrixWorld)},transformDirection:function(e){var t=this.x,n=this.y,r=this.z,i=e.elements;return this.x=i[0]*t+i[4]*n+i[8]*r,this.y=i[1]*t+i[5]*n+i[9]*r,this.z=i[2]*t+i[6]*n+i[10]*r,this.normalize()},divide:function(e){return this.x/=e.x,this.y/=e.y,this.z/=e.z,this},divideScalar:function(e){return this.multiplyScalar(1/e)},min:function(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:function(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:function(e,t){return this.x=Math.max(e.x,Math.min(t.x,this.x)),this.y=Math.max(e.y,Math.min(t.y,this.y)),this.z=Math.max(e.z,Math.min(t.z,this.z)),this},clampScalar:function(e,t){return this.x=Math.max(e,Math.min(t,this.x)),this.y=Math.max(e,Math.min(t,this.y)),this.z=Math.max(e,Math.min(t,this.z)),this},clampLength:function(e,t){var n=this.length();return this.divideScalar(n||1).multiplyScalar(Math.max(e,Math.min(t,n)))},floor:function(){return this.x=Math.floor(this.x),this.y=Math.floor(this.y),this.z=Math.floor(this.z),this},ceil:function(){return this.x=Math.ceil(this.x),this.y=Math.ceil(this.y),this.z=Math.ceil(this.z),this},round:function(){return this.x=Math.round(this.x),this.y=Math.round(this.y),this.z=Math.round(this.z),this},roundToZero:function(){return this.x=this.x<0?Math.ceil(this.x):Math.floor(this.x),this.y=this.y<0?Math.ceil(this.y):Math.floor(this.y),this.z=this.z<0?Math.ceil(this.z):Math.floor(this.z),this},negate:function(){return this.x=-this.x,this.y=-this.y,this.z=-this.z,this},dot:function(e){return this.x*e.x+this.y*e.y+this.z*e.z},lengthSq:function(){return this.x*this.x+this.y*this.y+this.z*this.z},length:function(){return Math.sqrt(this.x*this.x+this.y*this.y+this.z*this.z)},manhattanLength:function(){return Math.abs(this.x)+Math.abs(this.y)+Math.abs(this.z)},normalize:function(){return this.divideScalar(this.length()||1)},setLength:function(e){return this.normalize().multiplyScalar(e)},lerp:function(e,t){return this.x+=(e.x-this.x)*t,this.y+=(e.y-this.y)*t,this.z+=(e.z-this.z)*t,this},lerpVectors:function(e,t,n){return this.subVectors(t,e).multiplyScalar(n).add(e)},cross:function(e,t){return void 0!==t?(console.warn("THREE.Vector3: .cross() now only accepts one argument. Use .crossVectors( a, b ) instead."),this.crossVectors(e,t)):this.crossVectors(this,e)},crossVectors:function(e,t){var n=e.x,r=e.y,i=e.z,o=t.x,a=t.y,s=t.z;return this.x=r*s-i*a,this.y=i*o-n*s,this.z=n*a-r*o,this},projectOnVector:function(e){var t=e.dot(this)/e.lengthSq();return this.copy(e).multiplyScalar(t)},projectOnPlane:function(e){return wn.copy(this).projectOnVector(e),this.sub(wn)},reflect:function(e){return this.sub(wn.copy(e).multiplyScalar(2*this.dot(e)))},angleTo:function(e){var t=Math.sqrt(this.lengthSq()*e.lengthSq());0===t&&console.error("THREE.Vector3: angleTo() can't handle zero length vectors.");var n=this.dot(e)/t;return Math.acos(bn.clamp(n,-1,1))},distanceTo:function(e){return Math.sqrt(this.distanceToSquared(e))},distanceToSquared:function(e){var t=this.x-e.x,n=this.y-e.y,r=this.z-e.z;return t*t+n*n+r*r},manhattanDistanceTo:function(e){return Math.abs(this.x-e.x)+Math.abs(this.y-e.y)+Math.abs(this.z-e.z)},setFromSpherical:function(e){return this.setFromSphericalCoords(e.radius,e.phi,e.theta)},setFromSphericalCoords:function(e,t,n){var r=Math.sin(t)*e;return this.x=r*Math.sin(n),this.y=Math.cos(t)*e,this.z=r*Math.cos(n),this},setFromCylindrical:function(e){return this.setFromCylindricalCoords(e.radius,e.theta,e.y)},setFromCylindricalCoords:function(e,t,n){return this.x=e*Math.sin(t),this.y=n,this.z=e*Math.cos(t),this},setFromMatrixPosition:function(e){var t=e.elements;return this.x=t[12],this.y=t[13],this.z=t[14],this},setFromMatrixScale:function(e){var t=this.setFromMatrixColumn(e,0).length(),n=this.setFromMatrixColumn(e,1).length(),r=this.setFromMatrixColumn(e,2).length();return this.x=t,this.y=n,this.z=r,this},setFromMatrixColumn:function(e,t){return this.fromArray(e.elements,4*t)},equals:function(e){return e.x===this.x&&e.y===this.y&&e.z===this.z},fromArray:function(e,t){return void 0===t&&(t=0),this.x=e[t],this.y=e[t+1],this.z=e[t+2],this},toArray:function(e,t){return void 0===e&&(e=[]),void 0===t&&(t=0),e[t]=this.x,e[t+1]=this.y,e[t+2]=this.z,e},fromBufferAttribute:function(e,t,n){return void 0!==n&&console.warn("THREE.Vector3: offset has been removed from .fromBufferAttribute()."),this.x=e.getX(t),this.y=e.getY(t),this.z=e.getZ(t),this}});var Tn,Sn=new En;function An(){this.elements=[1,0,0,0,1,0,0,0,1],arguments.length>0&&console.error("THREE.Matrix3: the constructor no longer reads arguments. use .set() instead.")}Object.assign(An.prototype,{isMatrix3:!0,set:function(e,t,n,r,i,o,a,s,c){var l=this.elements;return l[0]=e,l[1]=r,l[2]=a,l[3]=t,l[4]=i,l[5]=s,l[6]=n,l[7]=o,l[8]=c,this},identity:function(){return this.set(1,0,0,0,1,0,0,0,1),this},clone:function(){return(new this.constructor).fromArray(this.elements)},copy:function(e){var t=this.elements,n=e.elements;return t[0]=n[0],t[1]=n[1],t[2]=n[2],t[3]=n[3],t[4]=n[4],t[5]=n[5],t[6]=n[6],t[7]=n[7],t[8]=n[8],this},setFromMatrix4:function(e){var t=e.elements;return this.set(t[0],t[4],t[8],t[1],t[5],t[9],t[2],t[6],t[10]),this},applyToBufferAttribute:function(e){for(var t=0,n=e.count;t2048||t.height>2048?t.toDataURL("image/jpeg",.6):t.toDataURL("image/png")}},Cn=0;function Rn(e,t,n,r,i,o,a,s,c,l){Object.defineProperty(this,"id",{value:Cn++}),this.uuid=bn.generateUUID(),this.name="",this.image=void 0!==e?e:Rn.DEFAULT_IMAGE,this.mipmaps=[],this.mapping=void 0!==t?t:Rn.DEFAULT_MAPPING,this.wrapS=void 0!==n?n:ye,this.wrapT=void 0!==r?r:ye,this.magFilter=void 0!==i?i:Te,this.minFilter=void 0!==o?o:Le,this.anisotropy=void 0!==c?c:1,this.format=void 0!==a?a:Ve,this.type=void 0!==s?s:Re,this.offset=new _n(0,0),this.repeat=new _n(1,1),this.center=new _n(0,0),this.rotation=0,this.matrixAutoUpdate=!0,this.matrix=new An,this.generateMipmaps=!0,this.premultiplyAlpha=!1,this.flipY=!0,this.unpackAlignment=4,this.encoding=void 0!==l?l:Ot,this.version=0,this.onUpdate=null}function Pn(e,t,n,r){this.x=e||0,this.y=t||0,this.z=n||0,this.w=void 0!==r?r:1}function On(e,t,n){this.width=e,this.height=t,this.scissor=new Pn(0,0,e,t),this.scissorTest=!1,this.viewport=new Pn(0,0,e,t),n=n||{},this.texture=new Rn(void 0,void 0,n.wrapS,n.wrapT,n.magFilter,n.minFilter,n.format,n.type,n.anisotropy,n.encoding),this.texture.image={},this.texture.image.width=e,this.texture.image.height=t,this.texture.generateMipmaps=void 0!==n.generateMipmaps&&n.generateMipmaps,this.texture.minFilter=void 0!==n.minFilter?n.minFilter:Te,this.depthBuffer=void 0===n.depthBuffer||n.depthBuffer,this.stencilBuffer=void 0===n.stencilBuffer||n.stencilBuffer,this.depthTexture=void 0!==n.depthTexture?n.depthTexture:null}function Nn(e,t,n){On.call(this,e,t,n),this.samples=4}Rn.DEFAULT_IMAGE=void 0,Rn.DEFAULT_MAPPING=le,Rn.prototype=Object.assign(Object.create(gn.prototype),{constructor:Rn,isTexture:!0,updateMatrix:function(){this.matrix.setUvTransform(this.offset.x,this.offset.y,this.repeat.x,this.repeat.y,this.rotation,this.center.x,this.center.y)},clone:function(){return(new this.constructor).copy(this)},copy:function(e){return this.name=e.name,this.image=e.image,this.mipmaps=e.mipmaps.slice(0),this.mapping=e.mapping,this.wrapS=e.wrapS,this.wrapT=e.wrapT,this.magFilter=e.magFilter,this.minFilter=e.minFilter,this.anisotropy=e.anisotropy,this.format=e.format,this.type=e.type,this.offset.copy(e.offset),this.repeat.copy(e.repeat),this.center.copy(e.center),this.rotation=e.rotation,this.matrixAutoUpdate=e.matrixAutoUpdate,this.matrix.copy(e.matrix),this.generateMipmaps=e.generateMipmaps,this.premultiplyAlpha=e.premultiplyAlpha,this.flipY=e.flipY,this.unpackAlignment=e.unpackAlignment,this.encoding=e.encoding,this},toJSON:function(e){var t=void 0===e||"string"==typeof e;if(!t&&void 0!==e.textures[this.uuid])return e.textures[this.uuid];var n={metadata:{version:4.5,type:"Texture",generator:"Texture.toJSON"},uuid:this.uuid,name:this.name,mapping:this.mapping,repeat:[this.repeat.x,this.repeat.y],offset:[this.offset.x,this.offset.y],center:[this.center.x,this.center.y],rotation:this.rotation,wrap:[this.wrapS,this.wrapT],format:this.format,type:this.type,encoding:this.encoding,minFilter:this.minFilter,magFilter:this.magFilter,anisotropy:this.anisotropy,flipY:this.flipY,premultiplyAlpha:this.premultiplyAlpha,unpackAlignment:this.unpackAlignment};if(void 0!==this.image){var r=this.image;if(void 0===r.uuid&&(r.uuid=bn.generateUUID()),!t&&void 0===e.images[r.uuid]){var i;if(Array.isArray(r)){i=[];for(var o=0,a=r.length;o1)switch(this.wrapS){case ve:e.x=e.x-Math.floor(e.x);break;case ye:e.x=e.x<0?0:1;break;case be:1===Math.abs(Math.floor(e.x)%2)?e.x=Math.ceil(e.x)-e.x:e.x=e.x-Math.floor(e.x)}if(e.y<0||e.y>1)switch(this.wrapT){case ve:e.y=e.y-Math.floor(e.y);break;case ye:e.y=e.y<0?0:1;break;case be:1===Math.abs(Math.floor(e.y)%2)?e.y=Math.ceil(e.y)-e.y:e.y=e.y-Math.floor(e.y)}return this.flipY&&(e.y=1-e.y),e}}),Object.defineProperty(Rn.prototype,"needsUpdate",{set:function(e){!0===e&&this.version++}}),Object.defineProperties(Pn.prototype,{width:{get:function(){return this.z},set:function(e){this.z=e}},height:{get:function(){return this.w},set:function(e){this.w=e}}}),Object.assign(Pn.prototype,{isVector4:!0,set:function(e,t,n,r){return this.x=e,this.y=t,this.z=n,this.w=r,this},setScalar:function(e){return this.x=e,this.y=e,this.z=e,this.w=e,this},setX:function(e){return this.x=e,this},setY:function(e){return this.y=e,this},setZ:function(e){return this.z=e,this},setW:function(e){return this.w=e,this},setComponent:function(e,t){switch(e){case 0:this.x=t;break;case 1:this.y=t;break;case 2:this.z=t;break;case 3:this.w=t;break;default:throw new Error("index is out of range: "+e)}return this},getComponent:function(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:function(){return new this.constructor(this.x,this.y,this.z,this.w)},copy:function(e){return this.x=e.x,this.y=e.y,this.z=e.z,this.w=void 0!==e.w?e.w:1,this},add:function(e,t){return void 0!==t?(console.warn("THREE.Vector4: .add() now only accepts one argument. Use .addVectors( a, b ) instead."),this.addVectors(e,t)):(this.x+=e.x,this.y+=e.y,this.z+=e.z,this.w+=e.w,this)},addScalar:function(e){return this.x+=e,this.y+=e,this.z+=e,this.w+=e,this},addVectors:function(e,t){return this.x=e.x+t.x,this.y=e.y+t.y,this.z=e.z+t.z,this.w=e.w+t.w,this},addScaledVector:function(e,t){return this.x+=e.x*t,this.y+=e.y*t,this.z+=e.z*t,this.w+=e.w*t,this},sub:function(e,t){return void 0!==t?(console.warn("THREE.Vector4: .sub() now only accepts one argument. Use .subVectors( a, b ) instead."),this.subVectors(e,t)):(this.x-=e.x,this.y-=e.y,this.z-=e.z,this.w-=e.w,this)},subScalar:function(e){return this.x-=e,this.y-=e,this.z-=e,this.w-=e,this},subVectors:function(e,t){return this.x=e.x-t.x,this.y=e.y-t.y,this.z=e.z-t.z,this.w=e.w-t.w,this},multiplyScalar:function(e){return this.x*=e,this.y*=e,this.z*=e,this.w*=e,this},applyMatrix4:function(e){var t=this.x,n=this.y,r=this.z,i=this.w,o=e.elements;return this.x=o[0]*t+o[4]*n+o[8]*r+o[12]*i,this.y=o[1]*t+o[5]*n+o[9]*r+o[13]*i,this.z=o[2]*t+o[6]*n+o[10]*r+o[14]*i,this.w=o[3]*t+o[7]*n+o[11]*r+o[15]*i,this},divideScalar:function(e){return this.multiplyScalar(1/e)},setAxisAngleFromQuaternion:function(e){this.w=2*Math.acos(e.w);var t=Math.sqrt(1-e.w*e.w);return t<1e-4?(this.x=1,this.y=0,this.z=0):(this.x=e.x/t,this.y=e.y/t,this.z=e.z/t),this},setAxisAngleFromRotationMatrix:function(e){var t,n,r,i,o=e.elements,a=o[0],s=o[4],c=o[8],l=o[1],u=o[5],h=o[9],d=o[2],p=o[6],f=o[10];if(Math.abs(s-l)<.01&&Math.abs(c-d)<.01&&Math.abs(h-p)<.01){if(Math.abs(s+l)<.1&&Math.abs(c+d)<.1&&Math.abs(h+p)<.1&&Math.abs(a+u+f-3)<.1)return this.set(1,0,0,0),this;t=Math.PI;var m=(a+1)/2,g=(u+1)/2,v=(f+1)/2,y=(s+l)/4,b=(c+d)/4,_=(h+p)/4;return m>g&&m>v?m<.01?(n=0,r=.707106781,i=.707106781):(r=y/(n=Math.sqrt(m)),i=b/n):g>v?g<.01?(n=.707106781,r=0,i=.707106781):(n=y/(r=Math.sqrt(g)),i=_/r):v<.01?(n=.707106781,r=.707106781,i=0):(n=b/(i=Math.sqrt(v)),r=_/i),this.set(n,r,i,t),this}var x=Math.sqrt((p-h)*(p-h)+(c-d)*(c-d)+(l-s)*(l-s));return Math.abs(x)<.001&&(x=1),this.x=(p-h)/x,this.y=(c-d)/x,this.z=(l-s)/x,this.w=Math.acos((a+u+f-1)/2),this},min:function(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:function(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:function(e,t){return this.x=Math.max(e.x,Math.min(t.x,this.x)),this.y=Math.max(e.y,Math.min(t.y,this.y)),this.z=Math.max(e.z,Math.min(t.z,this.z)),this.w=Math.max(e.w,Math.min(t.w,this.w)),this},clampScalar:function(e,t){return this.x=Math.max(e,Math.min(t,this.x)),this.y=Math.max(e,Math.min(t,this.y)),this.z=Math.max(e,Math.min(t,this.z)),this.w=Math.max(e,Math.min(t,this.w)),this},clampLength:function(e,t){var n=this.length();return this.divideScalar(n||1).multiplyScalar(Math.max(e,Math.min(t,n)))},floor:function(){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:function(){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:function(){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:function(){return this.x=this.x<0?Math.ceil(this.x):Math.floor(this.x),this.y=this.y<0?Math.ceil(this.y):Math.floor(this.y),this.z=this.z<0?Math.ceil(this.z):Math.floor(this.z),this.w=this.w<0?Math.ceil(this.w):Math.floor(this.w),this},negate:function(){return this.x=-this.x,this.y=-this.y,this.z=-this.z,this.w=-this.w,this},dot:function(e){return this.x*e.x+this.y*e.y+this.z*e.z+this.w*e.w},lengthSq:function(){return this.x*this.x+this.y*this.y+this.z*this.z+this.w*this.w},length:function(){return Math.sqrt(this.x*this.x+this.y*this.y+this.z*this.z+this.w*this.w)},manhattanLength:function(){return Math.abs(this.x)+Math.abs(this.y)+Math.abs(this.z)+Math.abs(this.w)},normalize:function(){return this.divideScalar(this.length()||1)},setLength:function(e){return this.normalize().multiplyScalar(e)},lerp:function(e,t){return this.x+=(e.x-this.x)*t,this.y+=(e.y-this.y)*t,this.z+=(e.z-this.z)*t,this.w+=(e.w-this.w)*t,this},lerpVectors:function(e,t,n){return this.subVectors(t,e).multiplyScalar(n).add(e)},equals:function(e){return e.x===this.x&&e.y===this.y&&e.z===this.z&&e.w===this.w},fromArray:function(e,t){return void 0===t&&(t=0),this.x=e[t],this.y=e[t+1],this.z=e[t+2],this.w=e[t+3],this},toArray:function(e,t){return void 0===e&&(e=[]),void 0===t&&(t=0),e[t]=this.x,e[t+1]=this.y,e[t+2]=this.z,e[t+3]=this.w,e},fromBufferAttribute:function(e,t,n){return void 0!==n&&console.warn("THREE.Vector4: offset has been removed from .fromBufferAttribute()."),this.x=e.getX(t),this.y=e.getY(t),this.z=e.getZ(t),this.w=e.getW(t),this}}),On.prototype=Object.assign(Object.create(gn.prototype),{constructor:On,isWebGLRenderTarget:!0,setSize:function(e,t){this.width===e&&this.height===t||(this.width=e,this.height=t,this.texture.image.width=e,this.texture.image.height=t,this.dispose()),this.viewport.set(0,0,e,t),this.scissor.set(0,0,e,t)},clone:function(){return(new this.constructor).copy(this)},copy:function(e){return this.width=e.width,this.height=e.height,this.viewport.copy(e.viewport),this.texture=e.texture.clone(),this.depthBuffer=e.depthBuffer,this.stencilBuffer=e.stencilBuffer,this.depthTexture=e.depthTexture,this},dispose:function(){this.dispatchEvent({type:"dispose"})}}),Nn.prototype=Object.assign(Object.create(On.prototype),{constructor:Nn,isWebGLMultisampleRenderTarget:!0,copy:function(e){return On.prototype.copy.call(this,e),this.samples=e.samples,this}});var In=new En,Dn=new Gn,Bn=new En(0,0,0),kn=new En(1,1,1),Un=new En,Fn=new En,zn=new En;function Gn(){this.elements=[1,0,0,0,0,1,0,0,0,0,1,0,0,0,0,1],arguments.length>0&&console.error("THREE.Matrix4: the constructor no longer reads arguments. use .set() instead.")}Object.assign(Gn.prototype,{isMatrix4:!0,set:function(e,t,n,r,i,o,a,s,c,l,u,h,d,p,f,m){var g=this.elements;return g[0]=e,g[4]=t,g[8]=n,g[12]=r,g[1]=i,g[5]=o,g[9]=a,g[13]=s,g[2]=c,g[6]=l,g[10]=u,g[14]=h,g[3]=d,g[7]=p,g[11]=f,g[15]=m,this},identity:function(){return this.set(1,0,0,0,0,1,0,0,0,0,1,0,0,0,0,1),this},clone:function(){return(new Gn).fromArray(this.elements)},copy:function(e){var t=this.elements,n=e.elements;return t[0]=n[0],t[1]=n[1],t[2]=n[2],t[3]=n[3],t[4]=n[4],t[5]=n[5],t[6]=n[6],t[7]=n[7],t[8]=n[8],t[9]=n[9],t[10]=n[10],t[11]=n[11],t[12]=n[12],t[13]=n[13],t[14]=n[14],t[15]=n[15],this},copyPosition:function(e){var t=this.elements,n=e.elements;return t[12]=n[12],t[13]=n[13],t[14]=n[14],this},extractBasis:function(e,t,n){return e.setFromMatrixColumn(this,0),t.setFromMatrixColumn(this,1),n.setFromMatrixColumn(this,2),this},makeBasis:function(e,t,n){return this.set(e.x,t.x,n.x,0,e.y,t.y,n.y,0,e.z,t.z,n.z,0,0,0,0,1),this},extractRotation:function(e){var t=this.elements,n=e.elements,r=1/In.setFromMatrixColumn(e,0).length(),i=1/In.setFromMatrixColumn(e,1).length(),o=1/In.setFromMatrixColumn(e,2).length();return t[0]=n[0]*r,t[1]=n[1]*r,t[2]=n[2]*r,t[3]=0,t[4]=n[4]*i,t[5]=n[5]*i,t[6]=n[6]*i,t[7]=0,t[8]=n[8]*o,t[9]=n[9]*o,t[10]=n[10]*o,t[11]=0,t[12]=0,t[13]=0,t[14]=0,t[15]=1,this},makeRotationFromEuler:function(e){e&&e.isEuler||console.error("THREE.Matrix4: .makeRotationFromEuler() now expects a Euler rotation rather than a Vector3 and order.");var t=this.elements,n=e.x,r=e.y,i=e.z,o=Math.cos(n),a=Math.sin(n),s=Math.cos(r),c=Math.sin(r),l=Math.cos(i),u=Math.sin(i);if("XYZ"===e.order){var h=o*l,d=o*u,p=a*l,f=a*u;t[0]=s*l,t[4]=-s*u,t[8]=c,t[1]=d+p*c,t[5]=h-f*c,t[9]=-a*s,t[2]=f-h*c,t[6]=p+d*c,t[10]=o*s}else if("YXZ"===e.order){var m=s*l,g=s*u,v=c*l,y=c*u;t[0]=m+y*a,t[4]=v*a-g,t[8]=o*c,t[1]=o*u,t[5]=o*l,t[9]=-a,t[2]=g*a-v,t[6]=y+m*a,t[10]=o*s}else if("ZXY"===e.order){m=s*l,g=s*u,v=c*l,y=c*u;t[0]=m-y*a,t[4]=-o*u,t[8]=v+g*a,t[1]=g+v*a,t[5]=o*l,t[9]=y-m*a,t[2]=-o*c,t[6]=a,t[10]=o*s}else if("ZYX"===e.order){h=o*l,d=o*u,p=a*l,f=a*u;t[0]=s*l,t[4]=p*c-d,t[8]=h*c+f,t[1]=s*u,t[5]=f*c+h,t[9]=d*c-p,t[2]=-c,t[6]=a*s,t[10]=o*s}else if("YZX"===e.order){var b=o*s,_=o*c,x=a*s,w=a*c;t[0]=s*l,t[4]=w-b*u,t[8]=x*u+_,t[1]=u,t[5]=o*l,t[9]=-a*l,t[2]=-c*l,t[6]=_*u+x,t[10]=b-w*u}else if("XZY"===e.order){b=o*s,_=o*c,x=a*s,w=a*c;t[0]=s*l,t[4]=-u,t[8]=c*l,t[1]=b*u+w,t[5]=o*l,t[9]=_*u-x,t[2]=x*u-_,t[6]=a*l,t[10]=w*u+b}return t[3]=0,t[7]=0,t[11]=0,t[12]=0,t[13]=0,t[14]=0,t[15]=1,this},makeRotationFromQuaternion:function(e){return this.compose(Bn,e,kn)},lookAt:function(e,t,n){var r=this.elements;return zn.subVectors(e,t),0===zn.lengthSq()&&(zn.z=1),zn.normalize(),Un.crossVectors(n,zn),0===Un.lengthSq()&&(1===Math.abs(n.z)?zn.x+=1e-4:zn.z+=1e-4,zn.normalize(),Un.crossVectors(n,zn)),Un.normalize(),Fn.crossVectors(zn,Un),r[0]=Un.x,r[4]=Fn.x,r[8]=zn.x,r[1]=Un.y,r[5]=Fn.y,r[9]=zn.y,r[2]=Un.z,r[6]=Fn.z,r[10]=zn.z,this},multiply:function(e,t){return void 0!==t?(console.warn("THREE.Matrix4: .multiply() now only accepts one argument. Use .multiplyMatrices( a, b ) instead."),this.multiplyMatrices(e,t)):this.multiplyMatrices(this,e)},premultiply:function(e){return this.multiplyMatrices(e,this)},multiplyMatrices:function(e,t){var n=e.elements,r=t.elements,i=this.elements,o=n[0],a=n[4],s=n[8],c=n[12],l=n[1],u=n[5],h=n[9],d=n[13],p=n[2],f=n[6],m=n[10],g=n[14],v=n[3],y=n[7],b=n[11],_=n[15],x=r[0],w=r[4],M=r[8],E=r[12],T=r[1],S=r[5],A=r[9],L=r[13],C=r[2],R=r[6],P=r[10],O=r[14],N=r[3],I=r[7],D=r[11],B=r[15];return i[0]=o*x+a*T+s*C+c*N,i[4]=o*w+a*S+s*R+c*I,i[8]=o*M+a*A+s*P+c*D,i[12]=o*E+a*L+s*O+c*B,i[1]=l*x+u*T+h*C+d*N,i[5]=l*w+u*S+h*R+d*I,i[9]=l*M+u*A+h*P+d*D,i[13]=l*E+u*L+h*O+d*B,i[2]=p*x+f*T+m*C+g*N,i[6]=p*w+f*S+m*R+g*I,i[10]=p*M+f*A+m*P+g*D,i[14]=p*E+f*L+m*O+g*B,i[3]=v*x+y*T+b*C+_*N,i[7]=v*w+y*S+b*R+_*I,i[11]=v*M+y*A+b*P+_*D,i[15]=v*E+y*L+b*O+_*B,this},multiplyScalar:function(e){var t=this.elements;return t[0]*=e,t[4]*=e,t[8]*=e,t[12]*=e,t[1]*=e,t[5]*=e,t[9]*=e,t[13]*=e,t[2]*=e,t[6]*=e,t[10]*=e,t[14]*=e,t[3]*=e,t[7]*=e,t[11]*=e,t[15]*=e,this},applyToBufferAttribute:function(e){for(var t=0,n=e.count;t1){for(var t=0;t1){for(var t=0;t0){r.children=[];for(s=0;s0&&(n.geometries=h),d.length>0&&(n.materials=d),p.length>0&&(n.textures=p),f.length>0&&(n.images=f),a.length>0&&(n.shapes=a)}return n.object=r,n;function m(e){var t=[];for(var n in e){var r=e[n];delete r.metadata,t.push(r)}return t}},clone:function(e){return(new this.constructor).copy(this,e)},copy:function(e,t){if(void 0===t&&(t=!0),this.name=e.name,this.up.copy(e.up),this.position.copy(e.position),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.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.userData=JSON.parse(JSON.stringify(e.userData)),!0===t)for(var n=0;ns)return!1}return!0}Object.assign(br.prototype,{isBox3:!0,set:function(e,t){return this.min.copy(e),this.max.copy(t),this},setFromArray:function(e){for(var t=1/0,n=1/0,r=1/0,i=-1/0,o=-1/0,a=-1/0,s=0,c=e.length;si&&(i=l),u>o&&(o=u),h>a&&(a=h)}return this.min.set(t,n,r),this.max.set(i,o,a),this},setFromBufferAttribute:function(e){for(var t=1/0,n=1/0,r=1/0,i=-1/0,o=-1/0,a=-1/0,s=0,c=e.count;si&&(i=l),u>o&&(o=u),h>a&&(a=h)}return this.min.set(t,n,r),this.max.set(i,o,a),this},setFromPoints:function(e){this.makeEmpty();for(var t=0,n=e.length;tthis.max.x||e.ythis.max.y||e.zthis.max.z)},containsBox:function(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:function(e,t){return void 0===t&&(console.warn("THREE.Box3: .getParameter() target is now required"),t=new En),t.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:function(e){return!(e.max.xthis.max.x||e.max.ythis.max.y||e.max.zthis.max.z)},intersectsSphere:function(e){return this.clampPoint(e.center,cr),cr.distanceToSquared(e.center)<=e.radius*e.radius},intersectsPlane:function(e){var t,n;return e.normal.x>0?(t=e.normal.x*this.min.x,n=e.normal.x*this.max.x):(t=e.normal.x*this.max.x,n=e.normal.x*this.min.x),e.normal.y>0?(t+=e.normal.y*this.min.y,n+=e.normal.y*this.max.y):(t+=e.normal.y*this.max.y,n+=e.normal.y*this.min.y),e.normal.z>0?(t+=e.normal.z*this.min.z,n+=e.normal.z*this.max.z):(t+=e.normal.z*this.max.z,n+=e.normal.z*this.min.z),t<=-e.constant&&n>=-e.constant},intersectsTriangle:function(e){if(this.isEmpty())return!1;this.getCenter(mr),gr.subVectors(this.max,mr),lr.subVectors(e.a,mr),ur.subVectors(e.b,mr),hr.subVectors(e.c,mr),dr.subVectors(ur,lr),pr.subVectors(hr,ur),fr.subVectors(lr,hr);var t=[0,-dr.z,dr.y,0,-pr.z,pr.y,0,-fr.z,fr.y,dr.z,0,-dr.x,pr.z,0,-pr.x,fr.z,0,-fr.x,-dr.y,dr.x,0,-pr.y,pr.x,0,-fr.y,fr.x,0];return!!_r(t,lr,ur,hr,gr)&&(!!_r(t=[1,0,0,0,1,0,0,0,1],lr,ur,hr,gr)&&(vr.crossVectors(dr,pr),_r(t=[vr.x,vr.y,vr.z],lr,ur,hr,gr)))},clampPoint:function(e,t){return void 0===t&&(console.warn("THREE.Box3: .clampPoint() target is now required"),t=new En),t.copy(e).clamp(this.min,this.max)},distanceToPoint:function(e){return cr.copy(e).clamp(this.min,this.max).sub(e).length()},getBoundingSphere:function(e){return void 0===e&&console.error("THREE.Box3: .getBoundingSphere() target is now required"),this.getCenter(e.center),e.radius=.5*this.getSize(cr).length(),e},intersect:function(e){return this.min.max(e.min),this.max.min(e.max),this.isEmpty()&&this.makeEmpty(),this},union:function(e){return this.min.min(e.min),this.max.max(e.max),this},applyMatrix4:function(e){return this.isEmpty()?this:(sr[0].set(this.min.x,this.min.y,this.min.z).applyMatrix4(e),sr[1].set(this.min.x,this.min.y,this.max.z).applyMatrix4(e),sr[2].set(this.min.x,this.max.y,this.min.z).applyMatrix4(e),sr[3].set(this.min.x,this.max.y,this.max.z).applyMatrix4(e),sr[4].set(this.max.x,this.min.y,this.min.z).applyMatrix4(e),sr[5].set(this.max.x,this.min.y,this.max.z).applyMatrix4(e),sr[6].set(this.max.x,this.max.y,this.min.z).applyMatrix4(e),sr[7].set(this.max.x,this.max.y,this.max.z).applyMatrix4(e),this.setFromPoints(sr),this)},translate:function(e){return this.min.add(e),this.max.add(e),this},equals:function(e){return e.min.equals(this.min)&&e.max.equals(this.max)}});var xr=new br;function wr(e,t){this.center=void 0!==e?e:new En,this.radius=void 0!==t?t:0}Object.assign(wr.prototype,{set:function(e,t){return this.center.copy(e),this.radius=t,this},setFromPoints:function(e,t){var n=this.center;void 0!==t?n.copy(t):xr.setFromPoints(e).getCenter(n);for(var r=0,i=0,o=e.length;ithis.radius*this.radius&&(t.sub(this.center).normalize(),t.multiplyScalar(this.radius).add(this.center)),t},getBoundingBox:function(e){return void 0===e&&(console.warn("THREE.Sphere: .getBoundingBox() target is now required"),e=new br),e.set(this.center,this.center),e.expandByScalar(this.radius),e},applyMatrix4:function(e){return this.center.applyMatrix4(e),this.radius=this.radius*e.getMaxScaleOnAxis(),this},translate:function(e){return this.center.add(e),this},equals:function(e){return e.center.equals(this.center)&&e.radius===this.radius}});var Mr=new En,Er=new En,Tr=new En,Sr=new En,Ar=new En,Lr=new En,Cr=new En;function Rr(e,t){this.origin=void 0!==e?e:new En,this.direction=void 0!==t?t:new En}Object.assign(Rr.prototype,{set:function(e,t){return this.origin.copy(e),this.direction.copy(t),this},clone:function(){return(new this.constructor).copy(this)},copy:function(e){return this.origin.copy(e.origin),this.direction.copy(e.direction),this},at:function(e,t){return void 0===t&&(console.warn("THREE.Ray: .at() target is now required"),t=new En),t.copy(this.direction).multiplyScalar(e).add(this.origin)},lookAt:function(e){return this.direction.copy(e).sub(this.origin).normalize(),this},recast:function(e){return this.origin.copy(this.at(e,Mr)),this},closestPointToPoint:function(e,t){void 0===t&&(console.warn("THREE.Ray: .closestPointToPoint() target is now required"),t=new En),t.subVectors(e,this.origin);var n=t.dot(this.direction);return n<0?t.copy(this.origin):t.copy(this.direction).multiplyScalar(n).add(this.origin)},distanceToPoint:function(e){return Math.sqrt(this.distanceSqToPoint(e))},distanceSqToPoint:function(e){var t=Mr.subVectors(e,this.origin).dot(this.direction);return t<0?this.origin.distanceToSquared(e):(Mr.copy(this.direction).multiplyScalar(t).add(this.origin),Mr.distanceToSquared(e))},distanceSqToSegment:function(e,t,n,r){Er.copy(e).add(t).multiplyScalar(.5),Tr.copy(t).sub(e).normalize(),Sr.copy(this.origin).sub(Er);var i,o,a,s,c=.5*e.distanceTo(t),l=-this.direction.dot(Tr),u=Sr.dot(this.direction),h=-Sr.dot(Tr),d=Sr.lengthSq(),p=Math.abs(1-l*l);if(p>0)if(o=l*u-h,s=c*p,(i=l*h-u)>=0)if(o>=-s)if(o<=s){var f=1/p;a=(i*=f)*(i+l*(o*=f)+2*u)+o*(l*i+o+2*h)+d}else o=c,a=-(i=Math.max(0,-(l*o+u)))*i+o*(o+2*h)+d;else o=-c,a=-(i=Math.max(0,-(l*o+u)))*i+o*(o+2*h)+d;else o<=-s?a=-(i=Math.max(0,-(-l*c+u)))*i+(o=i>0?-c:Math.min(Math.max(-c,-h),c))*(o+2*h)+d:o<=s?(i=0,a=(o=Math.min(Math.max(-c,-h),c))*(o+2*h)+d):a=-(i=Math.max(0,-(l*c+u)))*i+(o=i>0?c:Math.min(Math.max(-c,-h),c))*(o+2*h)+d;else o=l>0?-c:c,a=-(i=Math.max(0,-(l*o+u)))*i+o*(o+2*h)+d;return n&&n.copy(this.direction).multiplyScalar(i).add(this.origin),r&&r.copy(Tr).multiplyScalar(o).add(Er),a},intersectSphere:function(e,t){Mr.subVectors(e.center,this.origin);var n=Mr.dot(this.direction),r=Mr.dot(Mr)-n*n,i=e.radius*e.radius;if(r>i)return null;var o=Math.sqrt(i-r),a=n-o,s=n+o;return a<0&&s<0?null:a<0?this.at(s,t):this.at(a,t)},intersectsSphere:function(e){return this.distanceSqToPoint(e.center)<=e.radius*e.radius},distanceToPlane:function(e){var t=e.normal.dot(this.direction);if(0===t)return 0===e.distanceToPoint(this.origin)?0:null;var n=-(this.origin.dot(e.normal)+e.constant)/t;return n>=0?n:null},intersectPlane:function(e,t){var n=this.distanceToPlane(e);return null===n?null:this.at(n,t)},intersectsPlane:function(e){var t=e.distanceToPoint(this.origin);return 0===t||e.normal.dot(this.direction)*t<0},intersectBox:function(e,t){var n,r,i,o,a,s,c=1/this.direction.x,l=1/this.direction.y,u=1/this.direction.z,h=this.origin;return c>=0?(n=(e.min.x-h.x)*c,r=(e.max.x-h.x)*c):(n=(e.max.x-h.x)*c,r=(e.min.x-h.x)*c),l>=0?(i=(e.min.y-h.y)*l,o=(e.max.y-h.y)*l):(i=(e.max.y-h.y)*l,o=(e.min.y-h.y)*l),n>o||i>r?null:((i>n||n!=n)&&(n=i),(o=0?(a=(e.min.z-h.z)*u,s=(e.max.z-h.z)*u):(a=(e.max.z-h.z)*u,s=(e.min.z-h.z)*u),n>s||a>r?null:((a>n||n!=n)&&(n=a),(s=0?n:r,t)))},intersectsBox:function(e){return null!==this.intersectBox(e,Mr)},intersectTriangle:function(e,t,n,r,i){Ar.subVectors(t,e),Lr.subVectors(n,e),Cr.crossVectors(Ar,Lr);var o,a=this.direction.dot(Cr);if(a>0){if(r)return null;o=1}else{if(!(a<0))return null;o=-1,a=-a}Sr.subVectors(this.origin,e);var s=o*this.direction.dot(Lr.crossVectors(Sr,Lr));if(s<0)return null;var c=o*this.direction.dot(Ar.cross(Sr));if(c<0)return null;if(s+c>a)return null;var l=-o*Sr.dot(Cr);return l<0?null:this.at(l/a,i)},applyMatrix4:function(e){return this.origin.applyMatrix4(e),this.direction.transformDirection(e),this},equals:function(e){return e.origin.equals(this.origin)&&e.direction.equals(this.direction)}});var Pr=new En,Or=new En,Nr=new An;function Ir(e,t){this.normal=void 0!==e?e:new En(1,0,0),this.constant=void 0!==t?t:0}Object.assign(Ir.prototype,{isPlane:!0,set:function(e,t){return this.normal.copy(e),this.constant=t,this},setComponents:function(e,t,n,r){return this.normal.set(e,t,n),this.constant=r,this},setFromNormalAndCoplanarPoint:function(e,t){return this.normal.copy(e),this.constant=-t.dot(this.normal),this},setFromCoplanarPoints:function(e,t,n){var r=Pr.subVectors(n,t).cross(Or.subVectors(e,t)).normalize();return this.setFromNormalAndCoplanarPoint(r,e),this},clone:function(){return(new this.constructor).copy(this)},copy:function(e){return this.normal.copy(e.normal),this.constant=e.constant,this},normalize:function(){var e=1/this.normal.length();return this.normal.multiplyScalar(e),this.constant*=e,this},negate:function(){return this.constant*=-1,this.normal.negate(),this},distanceToPoint:function(e){return this.normal.dot(e)+this.constant},distanceToSphere:function(e){return this.distanceToPoint(e.center)-e.radius},projectPoint:function(e,t){return void 0===t&&(console.warn("THREE.Plane: .projectPoint() target is now required"),t=new En),t.copy(this.normal).multiplyScalar(-this.distanceToPoint(e)).add(e)},intersectLine:function(e,t){void 0===t&&(console.warn("THREE.Plane: .intersectLine() target is now required"),t=new En);var n=e.delta(Pr),r=this.normal.dot(n);if(0===r)return 0===this.distanceToPoint(e.start)?t.copy(e.start):void 0;var i=-(e.start.dot(this.normal)+this.constant)/r;return i<0||i>1?void 0:t.copy(n).multiplyScalar(i).add(e.start)},intersectsLine:function(e){var t=this.distanceToPoint(e.start),n=this.distanceToPoint(e.end);return t<0&&n>0||n<0&&t>0},intersectsBox:function(e){return e.intersectsPlane(this)},intersectsSphere:function(e){return e.intersectsPlane(this)},coplanarPoint:function(e){return void 0===e&&(console.warn("THREE.Plane: .coplanarPoint() target is now required"),e=new En),e.copy(this.normal).multiplyScalar(-this.constant)},applyMatrix4:function(e,t){var n=t||Nr.getNormalMatrix(e),r=this.coplanarPoint(Pr).applyMatrix4(e),i=this.normal.applyMatrix3(n).normalize();return this.constant=-r.dot(i),this},translate:function(e){return this.constant-=e.dot(this.normal),this},equals:function(e){return e.normal.equals(this.normal)&&e.constant===this.constant}});var Dr=new En,Br=new En,kr=new En,Ur=new En,Fr=new En,zr=new En,Gr=new En,Hr=new En,jr=new En,Vr=new En;function Wr(e,t,n){this.a=void 0!==e?e:new En,this.b=void 0!==t?t:new En,this.c=void 0!==n?n:new En}Object.assign(Wr,{getNormal:function(e,t,n,r){void 0===r&&(console.warn("THREE.Triangle: .getNormal() target is now required"),r=new En),r.subVectors(n,t),Dr.subVectors(e,t),r.cross(Dr);var i=r.lengthSq();return i>0?r.multiplyScalar(1/Math.sqrt(i)):r.set(0,0,0)},getBarycoord:function(e,t,n,r,i){Dr.subVectors(r,t),Br.subVectors(n,t),kr.subVectors(e,t);var o=Dr.dot(Dr),a=Dr.dot(Br),s=Dr.dot(kr),c=Br.dot(Br),l=Br.dot(kr),u=o*c-a*a;if(void 0===i&&(console.warn("THREE.Triangle: .getBarycoord() target is now required"),i=new En),0===u)return i.set(-2,-1,-1);var h=1/u,d=(c*s-a*l)*h,p=(o*l-a*s)*h;return i.set(1-d-p,p,d)},containsPoint:function(e,t,n,r){return Wr.getBarycoord(e,t,n,r,Ur),Ur.x>=0&&Ur.y>=0&&Ur.x+Ur.y<=1},getUV:function(e,t,n,r,i,o,a,s){return this.getBarycoord(e,t,n,r,Ur),s.set(0,0),s.addScaledVector(i,Ur.x),s.addScaledVector(o,Ur.y),s.addScaledVector(a,Ur.z),s},isFrontFacing:function(e,t,n,r){return Dr.subVectors(n,t),Br.subVectors(e,t),Dr.cross(Br).dot(r)<0}}),Object.assign(Wr.prototype,{set:function(e,t,n){return this.a.copy(e),this.b.copy(t),this.c.copy(n),this},setFromPointsAndIndices:function(e,t,n,r){return this.a.copy(e[t]),this.b.copy(e[n]),this.c.copy(e[r]),this},clone:function(){return(new this.constructor).copy(this)},copy:function(e){return this.a.copy(e.a),this.b.copy(e.b),this.c.copy(e.c),this},getArea:function(){return Dr.subVectors(this.c,this.b),Br.subVectors(this.a,this.b),.5*Dr.cross(Br).length()},getMidpoint:function(e){return void 0===e&&(console.warn("THREE.Triangle: .getMidpoint() target is now required"),e=new En),e.addVectors(this.a,this.b).add(this.c).multiplyScalar(1/3)},getNormal:function(e){return Wr.getNormal(this.a,this.b,this.c,e)},getPlane:function(e){return void 0===e&&(console.warn("THREE.Triangle: .getPlane() target is now required"),e=new Ir),e.setFromCoplanarPoints(this.a,this.b,this.c)},getBarycoord:function(e,t){return Wr.getBarycoord(e,this.a,this.b,this.c,t)},getUV:function(e,t,n,r,i){return Wr.getUV(e,this.a,this.b,this.c,t,n,r,i)},containsPoint:function(e){return Wr.containsPoint(e,this.a,this.b,this.c)},isFrontFacing:function(e){return Wr.isFrontFacing(this.a,this.b,this.c,e)},intersectsBox:function(e){return e.intersectsTriangle(this)},closestPointToPoint:function(e,t){void 0===t&&(console.warn("THREE.Triangle: .closestPointToPoint() target is now required"),t=new En);var n,r,i=this.a,o=this.b,a=this.c;Fr.subVectors(o,i),zr.subVectors(a,i),Hr.subVectors(e,i);var s=Fr.dot(Hr),c=zr.dot(Hr);if(s<=0&&c<=0)return t.copy(i);jr.subVectors(e,o);var l=Fr.dot(jr),u=zr.dot(jr);if(l>=0&&u<=l)return t.copy(o);var h=s*u-l*c;if(h<=0&&s>=0&&l<=0)return n=s/(s-l),t.copy(i).addScaledVector(Fr,n);Vr.subVectors(e,a);var d=Fr.dot(Vr),p=zr.dot(Vr);if(p>=0&&d<=p)return t.copy(a);var f=d*c-s*p;if(f<=0&&c>=0&&p<=0)return r=c/(c-p),t.copy(i).addScaledVector(zr,r);var m=l*p-d*u;if(m<=0&&u-l>=0&&d-p>=0)return Gr.subVectors(a,o),r=(u-l)/(u-l+(d-p)),t.copy(o).addScaledVector(Gr,r);var g=1/(m+f+h);return n=f*g,r=h*g,t.copy(i).addScaledVector(Fr,n).addScaledVector(zr,r)},equals:function(e){return e.a.equals(this.a)&&e.b.equals(this.b)&&e.c.equals(this.c)}});var qr={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},Yr={h:0,s:0,l:0},Xr={h:0,s:0,l:0};function Jr(e,t,n){return void 0===t&&void 0===n?this.set(e):this.setRGB(e,t,n)}function Zr(e,t,n){return n<0&&(n+=1),n>1&&(n-=1),n<1/6?e+6*(t-e)*n:n<.5?t:n<2/3?e+6*(t-e)*(2/3-n):e}function Kr(e){return e<.04045?.0773993808*e:Math.pow(.9478672986*e+.0521327014,2.4)}function Qr(e){return e<.0031308?12.92*e:1.055*Math.pow(e,.41666)-.055}function $r(e,t,n,r,i,o){this.a=e,this.b=t,this.c=n,this.normal=r&&r.isVector3?r:new En,this.vertexNormals=Array.isArray(r)?r:[],this.color=i&&i.isColor?i:new Jr,this.vertexColors=Array.isArray(i)?i:[],this.materialIndex=void 0!==o?o:0}Object.assign(Jr.prototype,{isColor:!0,r:1,g:1,b:1,set:function(e){return e&&e.isColor?this.copy(e):"number"==typeof e?this.setHex(e):"string"==typeof e&&this.setStyle(e),this},setScalar:function(e){return this.r=e,this.g=e,this.b=e,this},setHex:function(e){return e=Math.floor(e),this.r=(e>>16&255)/255,this.g=(e>>8&255)/255,this.b=(255&e)/255,this},setRGB:function(e,t,n){return this.r=e,this.g=t,this.b=n,this},setHSL:function(e,t,n){if(e=bn.euclideanModulo(e,1),t=bn.clamp(t,0,1),n=bn.clamp(n,0,1),0===t)this.r=this.g=this.b=n;else{var r=n<=.5?n*(1+t):n+t-n*t,i=2*n-r;this.r=Zr(i,r,e+1/3),this.g=Zr(i,r,e),this.b=Zr(i,r,e-1/3)}return this},setStyle:function(e){function t(t){void 0!==t&&parseFloat(t)<1&&console.warn("THREE.Color: Alpha component of "+e+" will be ignored.")}var n;if(n=/^((?:rgb|hsl)a?)\\(\\s*([^\\)]*)\\)/.exec(e)){var r,i=n[1],o=n[2];switch(i){case"rgb":case"rgba":if(r=/^(\\d+)\\s*,\\s*(\\d+)\\s*,\\s*(\\d+)\\s*(,\\s*([0-9]*\\.?[0-9]+)\\s*)?$/.exec(o))return this.r=Math.min(255,parseInt(r[1],10))/255,this.g=Math.min(255,parseInt(r[2],10))/255,this.b=Math.min(255,parseInt(r[3],10))/255,t(r[5]),this;if(r=/^(\\d+)\\%\\s*,\\s*(\\d+)\\%\\s*,\\s*(\\d+)\\%\\s*(,\\s*([0-9]*\\.?[0-9]+)\\s*)?$/.exec(o))return this.r=Math.min(100,parseInt(r[1],10))/100,this.g=Math.min(100,parseInt(r[2],10))/100,this.b=Math.min(100,parseInt(r[3],10))/100,t(r[5]),this;break;case"hsl":case"hsla":if(r=/^([0-9]*\\.?[0-9]+)\\s*,\\s*(\\d+)\\%\\s*,\\s*(\\d+)\\%\\s*(,\\s*([0-9]*\\.?[0-9]+)\\s*)?$/.exec(o)){var a=parseFloat(r[1])/360,s=parseInt(r[2],10)/100,c=parseInt(r[3],10)/100;return t(r[5]),this.setHSL(a,s,c)}}}else if(n=/^\\#([A-Fa-f0-9]+)$/.exec(e)){var l=n[1],u=l.length;if(3===u)return this.r=parseInt(l.charAt(0)+l.charAt(0),16)/255,this.g=parseInt(l.charAt(1)+l.charAt(1),16)/255,this.b=parseInt(l.charAt(2)+l.charAt(2),16)/255,this;if(6===u)return this.r=parseInt(l.charAt(0)+l.charAt(1),16)/255,this.g=parseInt(l.charAt(2)+l.charAt(3),16)/255,this.b=parseInt(l.charAt(4)+l.charAt(5),16)/255,this}return e&&e.length>0?this.setColorName(e):this},setColorName:function(e){var t=qr[e];return void 0!==t?this.setHex(t):console.warn("THREE.Color: Unknown color "+e),this},clone:function(){return new this.constructor(this.r,this.g,this.b)},copy:function(e){return this.r=e.r,this.g=e.g,this.b=e.b,this},copyGammaToLinear:function(e,t){return void 0===t&&(t=2),this.r=Math.pow(e.r,t),this.g=Math.pow(e.g,t),this.b=Math.pow(e.b,t),this},copyLinearToGamma:function(e,t){void 0===t&&(t=2);var n=t>0?1/t:1;return this.r=Math.pow(e.r,n),this.g=Math.pow(e.g,n),this.b=Math.pow(e.b,n),this},convertGammaToLinear:function(e){return this.copyGammaToLinear(this,e),this},convertLinearToGamma:function(e){return this.copyLinearToGamma(this,e),this},copySRGBToLinear:function(e){return this.r=Kr(e.r),this.g=Kr(e.g),this.b=Kr(e.b),this},copyLinearToSRGB:function(e){return this.r=Qr(e.r),this.g=Qr(e.g),this.b=Qr(e.b),this},convertSRGBToLinear:function(){return this.copySRGBToLinear(this),this},convertLinearToSRGB:function(){return this.copyLinearToSRGB(this),this},getHex:function(){return 255*this.r<<16^255*this.g<<8^255*this.b<<0},getHexString:function(){return("000000"+this.getHex().toString(16)).slice(-6)},getHSL:function(e){void 0===e&&(console.warn("THREE.Color: .getHSL() target is now required"),e={h:0,s:0,l:0});var t,n,r=this.r,i=this.g,o=this.b,a=Math.max(r,i,o),s=Math.min(r,i,o),c=(s+a)/2;if(s===a)t=0,n=0;else{var l=a-s;switch(n=c<=.5?l/(a+s):l/(2-a-s),a){case r:t=(i-o)/l+(it&&(t=e[n]);return t}ti.prototype=Object.assign(Object.create(gn.prototype),{constructor:ti,isMaterial:!0,onBeforeCompile:function(){},setValues:function(e){if(void 0!==e)for(var t in e){var n=e[t];if(void 0!==n)if("shading"!==t){var r=this[t];void 0!==r?r&&r.isColor?r.set(n):r&&r.isVector3&&n&&n.isVector3?r.copy(n):this[t]=n:console.warn("THREE."+this.type+": '"+t+"' is not a property of this material.")}else console.warn("THREE."+this.type+": .shading has been removed. Use the boolean .flatShading instead."),this.flatShading=n===b;else console.warn("THREE.Material: '"+t+"' parameter is undefined.")}},toJSON:function(e){var t=void 0===e||"string"==typeof e;t&&(e={textures:{},images:{}});var n={metadata:{version:4.5,type:"Material",generator:"Material.toJSON"}};function r(e){var t=[];for(var n in e){var r=e[n];delete r.metadata,t.push(r)}return t}if(n.uuid=this.uuid,n.type=this.type,""!==this.name&&(n.name=this.name),this.color&&this.color.isColor&&(n.color=this.color.getHex()),void 0!==this.roughness&&(n.roughness=this.roughness),void 0!==this.metalness&&(n.metalness=this.metalness),this.sheen&&this.sheen.isColor&&(n.sheen=this.sheen.getHex()),this.emissive&&this.emissive.isColor&&(n.emissive=this.emissive.getHex()),this.emissiveIntensity&&1!==this.emissiveIntensity&&(n.emissiveIntensity=this.emissiveIntensity),this.specular&&this.specular.isColor&&(n.specular=this.specular.getHex()),void 0!==this.shininess&&(n.shininess=this.shininess),void 0!==this.clearcoat&&(n.clearcoat=this.clearcoat),void 0!==this.clearcoatRoughness&&(n.clearcoatRoughness=this.clearcoatRoughness),this.clearcoatNormalMap&&this.clearcoatNormalMap.isTexture&&(n.clearcoatNormalMap=this.clearcoatNormalMap.toJSON(e).uuid,n.clearcoatNormalScale=this.clearcoatNormalScale.toArray()),this.map&&this.map.isTexture&&(n.map=this.map.toJSON(e).uuid),this.matcap&&this.matcap.isTexture&&(n.matcap=this.matcap.toJSON(e).uuid),this.alphaMap&&this.alphaMap.isTexture&&(n.alphaMap=this.alphaMap.toJSON(e).uuid),this.lightMap&&this.lightMap.isTexture&&(n.lightMap=this.lightMap.toJSON(e).uuid),this.aoMap&&this.aoMap.isTexture&&(n.aoMap=this.aoMap.toJSON(e).uuid,n.aoMapIntensity=this.aoMapIntensity),this.bumpMap&&this.bumpMap.isTexture&&(n.bumpMap=this.bumpMap.toJSON(e).uuid,n.bumpScale=this.bumpScale),this.normalMap&&this.normalMap.isTexture&&(n.normalMap=this.normalMap.toJSON(e).uuid,n.normalMapType=this.normalMapType,n.normalScale=this.normalScale.toArray()),this.displacementMap&&this.displacementMap.isTexture&&(n.displacementMap=this.displacementMap.toJSON(e).uuid,n.displacementScale=this.displacementScale,n.displacementBias=this.displacementBias),this.roughnessMap&&this.roughnessMap.isTexture&&(n.roughnessMap=this.roughnessMap.toJSON(e).uuid),this.metalnessMap&&this.metalnessMap.isTexture&&(n.metalnessMap=this.metalnessMap.toJSON(e).uuid),this.emissiveMap&&this.emissiveMap.isTexture&&(n.emissiveMap=this.emissiveMap.toJSON(e).uuid),this.specularMap&&this.specularMap.isTexture&&(n.specularMap=this.specularMap.toJSON(e).uuid),this.envMap&&this.envMap.isTexture&&(n.envMap=this.envMap.toJSON(e).uuid,n.reflectivity=this.reflectivity,n.refractionRatio=this.refractionRatio,void 0!==this.combine&&(n.combine=this.combine),void 0!==this.envMapIntensity&&(n.envMapIntensity=this.envMapIntensity)),this.gradientMap&&this.gradientMap.isTexture&&(n.gradientMap=this.gradientMap.toJSON(e).uuid),void 0!==this.size&&(n.size=this.size),void 0!==this.sizeAttenuation&&(n.sizeAttenuation=this.sizeAttenuation),this.blending!==T&&(n.blending=this.blending),!0===this.flatShading&&(n.flatShading=this.flatShading),this.side!==g&&(n.side=this.side),this.vertexColors!==x&&(n.vertexColors=this.vertexColors),this.opacity<1&&(n.opacity=this.opacity),!0===this.transparent&&(n.transparent=this.transparent),n.depthFunc=this.depthFunc,n.depthTest=this.depthTest,n.depthWrite=this.depthWrite,n.stencilWrite=this.stencilWrite,n.stencilWriteMask=this.stencilWriteMask,n.stencilFunc=this.stencilFunc,n.stencilRef=this.stencilRef,n.stencilFuncMask=this.stencilFuncMask,n.stencilFail=this.stencilFail,n.stencilZFail=this.stencilZFail,n.stencilZPass=this.stencilZPass,this.rotation&&0!==this.rotation&&(n.rotation=this.rotation),!0===this.polygonOffset&&(n.polygonOffset=!0),0!==this.polygonOffsetFactor&&(n.polygonOffsetFactor=this.polygonOffsetFactor),0!==this.polygonOffsetUnits&&(n.polygonOffsetUnits=this.polygonOffsetUnits),this.linewidth&&1!==this.linewidth&&(n.linewidth=this.linewidth),void 0!==this.dashSize&&(n.dashSize=this.dashSize),void 0!==this.gapSize&&(n.gapSize=this.gapSize),void 0!==this.scale&&(n.scale=this.scale),!0===this.dithering&&(n.dithering=!0),this.alphaTest>0&&(n.alphaTest=this.alphaTest),!0===this.premultipliedAlpha&&(n.premultipliedAlpha=this.premultipliedAlpha),!0===this.wireframe&&(n.wireframe=this.wireframe),this.wireframeLinewidth>1&&(n.wireframeLinewidth=this.wireframeLinewidth),"round"!==this.wireframeLinecap&&(n.wireframeLinecap=this.wireframeLinecap),"round"!==this.wireframeLinejoin&&(n.wireframeLinejoin=this.wireframeLinejoin),!0===this.morphTargets&&(n.morphTargets=!0),!0===this.morphNormals&&(n.morphNormals=!0),!0===this.skinning&&(n.skinning=!0),!1===this.visible&&(n.visible=!1),!1===this.toneMapped&&(n.toneMapped=!1),"{}"!==JSON.stringify(this.userData)&&(n.userData=this.userData),t){var i=r(e.textures),o=r(e.images);i.length>0&&(n.textures=i),o.length>0&&(n.images=o)}return n},clone:function(){return(new this.constructor).copy(this)},copy:function(e){this.name=e.name,this.fog=e.fog,this.blending=e.blending,this.side=e.side,this.flatShading=e.flatShading,this.vertexTangents=e.vertexTangents,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.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;var t=e.clippingPlanes,n=null;if(null!==t){var r=t.length;n=new Array(r);for(var i=0;i!==r;++i)n[i]=t[i].clone()}return this.clippingPlanes=n,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.premultipliedAlpha=e.premultipliedAlpha,this.visible=e.visible,this.toneMapped=e.toneMapped,this.userData=JSON.parse(JSON.stringify(e.userData)),this},dispose:function(){this.dispatchEvent({type:"dispose"})}}),ni.prototype=Object.create(ti.prototype),ni.prototype.constructor=ni,ni.prototype.isMeshBasicMaterial=!0,ni.prototype.copy=function(e){return ti.prototype.copy.call(this,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.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.skinning=e.skinning,this.morphTargets=e.morphTargets,this},Object.defineProperty(ri.prototype,"needsUpdate",{set:function(e){!0===e&&this.version++}}),Object.assign(ri.prototype,{isBufferAttribute:!0,onUploadCallback:function(){},setUsage:function(e){return this.usage=e,this},copy:function(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},copyAt:function(e,t,n){e*=this.itemSize,n*=t.itemSize;for(var r=0,i=this.itemSize;r0,a=i[1]&&i[1].length>0,s=e.morphTargets,c=s.length;if(c>0){t=[];for(var l=0;l0){u=[];for(l=0;l0&&0===n.length&&console.error("THREE.DirectGeometry: Faceless geometries are not supported.");for(l=0;l65535?ui:ci)(e,1):this.index=e},getAttribute:function(e){return this.attributes[e]},setAttribute:function(e,t){return this.attributes[e]=t,this},deleteAttribute:function(e){return delete this.attributes[e],this},addGroup:function(e,t,n){this.groups.push({start:e,count:t,materialIndex:void 0!==n?n:0})},clearGroups:function(){this.groups=[]},setDrawRange:function(e,t){this.drawRange.start=e,this.drawRange.count=t},applyMatrix:function(e){var t=this.attributes.position;void 0!==t&&(e.applyToBufferAttribute(t),t.needsUpdate=!0);var n=this.attributes.normal;void 0!==n&&((new An).getNormalMatrix(e).applyToBufferAttribute(n),n.needsUpdate=!0);var r=this.attributes.tangent;void 0!==r&&((new An).getNormalMatrix(e).applyToBufferAttribute(r),r.needsUpdate=!0);return null!==this.boundingBox&&this.computeBoundingBox(),null!==this.boundingSphere&&this.computeBoundingSphere(),this},rotateX:function(e){return gi.makeRotationX(e),this.applyMatrix(gi),this},rotateY:function(e){return gi.makeRotationY(e),this.applyMatrix(gi),this},rotateZ:function(e){return gi.makeRotationZ(e),this.applyMatrix(gi),this},translate:function(e,t,n){return gi.makeTranslation(e,t,n),this.applyMatrix(gi),this},scale:function(e,t,n){return gi.makeScale(e,t,n),this.applyMatrix(gi),this},lookAt:function(e){return vi.lookAt(e),vi.updateMatrix(),this.applyMatrix(vi.matrix),this},center:function(){return this.computeBoundingBox(),this.boundingBox.getCenter(yi).negate(),this.translate(yi.x,yi.y,yi.z),this},setFromObject:function(e){var t=e.geometry;if(e.isPoints||e.isLine){var n=new hi(3*t.vertices.length,3),r=new hi(3*t.colors.length,3);if(this.setAttribute("position",n.copyVector3sArray(t.vertices)),this.setAttribute("color",r.copyColorsArray(t.colors)),t.lineDistances&&t.lineDistances.length===t.vertices.length){var i=new hi(t.lineDistances.length,1);this.setAttribute("lineDistance",i.copyArray(t.lineDistances))}null!==t.boundingSphere&&(this.boundingSphere=t.boundingSphere.clone()),null!==t.boundingBox&&(this.boundingBox=t.boundingBox.clone())}else e.isMesh&&t&&t.isGeometry&&this.fromGeometry(t);return this},setFromPoints:function(e){for(var t=[],n=0,r=e.length;n0){var n=new Float32Array(3*e.normals.length);this.setAttribute("normal",new ri(n,3).copyVector3sArray(e.normals))}if(e.colors.length>0){var r=new Float32Array(3*e.colors.length);this.setAttribute("color",new ri(r,3).copyColorsArray(e.colors))}if(e.uvs.length>0){var i=new Float32Array(2*e.uvs.length);this.setAttribute("uv",new ri(i,2).copyVector2sArray(e.uvs))}if(e.uvs2.length>0){var o=new Float32Array(2*e.uvs2.length);this.setAttribute("uv2",new ri(o,2).copyVector2sArray(e.uvs2))}for(var a in this.groups=e.groups,e.morphTargets){for(var s=[],c=e.morphTargets[a],l=0,u=c.length;l0){var p=new hi(4*e.skinIndices.length,4);this.setAttribute("skinIndex",p.copyVector4sArray(e.skinIndices))}if(e.skinWeights.length>0){var f=new hi(4*e.skinWeights.length,4);this.setAttribute("skinWeight",f.copyVector4sArray(e.skinWeights))}return null!==e.boundingSphere&&(this.boundingSphere=e.boundingSphere.clone()),null!==e.boundingBox&&(this.boundingBox=e.boundingBox.clone()),this},computeBoundingBox:function(){null===this.boundingBox&&(this.boundingBox=new br);var e=this.attributes.position,t=this.morphAttributes.position;if(void 0!==e){if(this.boundingBox.setFromBufferAttribute(e),t)for(var n=0,r=t.length;n0&&(e.userData=this.userData),void 0!==this.parameters){var t=this.parameters;for(var n in t)void 0!==t[n]&&(e[n]=t[n]);return e}e.data={attributes:{}};var r=this.index;null!==r&&(e.data.index={type:r.array.constructor.name,array:Array.prototype.slice.call(r.array)});var i=this.attributes;for(var n in i){var o=(d=i[n]).toJSON();""!==d.name&&(o.name=d.name),e.data.attributes[n]=o}var a={},s=!1;for(var n in this.morphAttributes){for(var c=this.morphAttributes[n],l=[],u=0,h=c.length;u0&&(a[n]=l,s=!0)}s&&(e.data.morphAttributes=a);var p=this.groups;p.length>0&&(e.data.groups=JSON.parse(JSON.stringify(p)));var f=this.boundingSphere;return null!==f&&(e.data.boundingSphere={center:f.center.toArray(),radius:f.radius}),e},clone:function(){return(new wi).copy(this)},copy:function(e){var t,n,r;this.index=null,this.attributes={},this.morphAttributes={},this.groups=[],this.boundingBox=null,this.boundingSphere=null,this.name=e.name;var i=e.index;null!==i&&this.setIndex(i.clone());var o=e.attributes;for(t in o){var a=o[t];this.setAttribute(t,a.clone())}var s=e.morphAttributes;for(t in s){var c=[],l=s[t];for(n=0,r=l.length;nn.far?null:{distance:c,point:Fi.clone(),object:e}}function Hi(e,t,n,r,i,o,a,s,c,l,u){Si.fromBufferAttribute(i,c),Ai.fromBufferAttribute(i,l),Li.fromBufferAttribute(i,u);var h=e.morphTargetInfluences;if(t.morphTargets&&o&&h){Oi.set(0,0,0),Ni.set(0,0,0),Ii.set(0,0,0);for(var d=0,p=o.length;d0){var a=i[o[0]];if(void 0!==a)for(this.morphTargetInfluences=[],this.morphTargetDictionary={},e=0,t=a.length;e0&&console.error("THREE.Mesh.updateMorphTargets() no longer supports THREE.Geometry. Use THREE.BufferGeometry instead.")}},raycast:function(e,t){var n,r=this.geometry,i=this.material,o=this.matrixWorld;if(void 0!==i&&(null===r.boundingSphere&&r.computeBoundingSphere(),Ti.copy(r.boundingSphere),Ti.applyMatrix4(o),!1!==e.ray.intersectsSphere(Ti)&&(Mi.getInverse(o),Ei.copy(e.ray).applyMatrix4(Mi),null===r.boundingBox||!1!==Ei.intersectsBox(r.boundingBox))))if(this.drawMode===Ct){if(r.isBufferGeometry){var a,s,c,l,u,h,d,p,f,m=r.index,g=r.attributes.position,v=r.morphAttributes.position,y=r.attributes.uv,b=r.attributes.uv2,_=r.groups,x=r.drawRange;if(null!==m)if(Array.isArray(i))for(l=0,h=_.length;l0&&(T=C);for(var R=0,P=L.length;R0)for(l=0;l0&&(this.normalsNeedUpdate=!0)},computeFlatVertexNormals:function(){var e,t,n;for(this.computeFaceNormals(),e=0,t=this.faces.length;e0&&(this.normalsNeedUpdate=!0)},computeMorphNormals:function(){var e,t,n,r,i;for(n=0,r=this.faces.length;n=0;n--){var f=d[n];for(this.faces.splice(f,1),a=0,s=this.faceVertexUvs.length;a0,g=p.vertexNormals.length>0,v=1!==p.color.r||1!==p.color.g||1!==p.color.b,y=p.vertexColors.length>0,b=0;if(b=M(b,0,0),b=M(b,1,!0),b=M(b,2,!1),b=M(b,3,f),b=M(b,4,m),b=M(b,5,g),b=M(b,6,v),b=M(b,7,y),a.push(b),a.push(p.a,p.b,p.c),a.push(p.materialIndex),f){var _=this.faceVertexUvs[0][i];a.push(S(_[0]),S(_[1]),S(_[2]))}if(m&&a.push(E(p.normal)),g){var x=p.vertexNormals;a.push(E(x[0]),E(x[1]),E(x[2]))}if(v&&a.push(T(p.color)),y){var w=p.vertexColors;a.push(T(w[0]),T(w[1]),T(w[2]))}}function M(e,t,n){return n?e|1<0&&(e.data.colors=l),h.length>0&&(e.data.uvs=[h]),e.data.faces=a,e},clone:function(){return(new Yi).copy(this)},copy:function(e){var t,n,r,i,o,a;this.vertices=[],this.colors=[],this.faces=[],this.faceVertexUvs=[[]],this.morphTargets=[],this.morphNormals=[],this.skinWeights=[],this.skinIndices=[],this.lineDistances=[],this.boundingBox=null,this.boundingSphere=null,this.name=e.name;var s=e.vertices;for(t=0,n=s.length;t0?1:-1,l.push(C.x,C.y,C.z),u.push(y/m),u.push(1-b/g),A+=1}}for(b=0;b0&&(t.defines=this.defines),t.vertexShader=this.vertexShader,t.fragmentShader=this.fragmentShader;var i={};for(var o in this.extensions)!0===this.extensions[o]&&(i[o]=!0);return Object.keys(i).length>0&&(t.extensions=i),t},no.prototype=Object.assign(Object.create(or.prototype),{constructor:no,isCamera:!0,copy:function(e,t){return or.prototype.copy.call(this,e,t),this.matrixWorldInverse.copy(e.matrixWorldInverse),this.projectionMatrix.copy(e.projectionMatrix),this.projectionMatrixInverse.copy(e.projectionMatrixInverse),this},getWorldDirection:function(e){void 0===e&&(console.warn("THREE.Camera: .getWorldDirection() target is now required"),e=new En),this.updateMatrixWorld(!0);var t=this.matrixWorld.elements;return e.set(-t[8],-t[9],-t[10]).normalize()},updateMatrixWorld:function(e){or.prototype.updateMatrixWorld.call(this,e),this.matrixWorldInverse.getInverse(this.matrixWorld)},clone:function(){return(new this.constructor).copy(this)}}),ro.prototype=Object.assign(Object.create(no.prototype),{constructor:ro,isPerspectiveCamera:!0,copy:function(e,t){return no.prototype.copy.call(this,e,t),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=null===e.view?null:Object.assign({},e.view),this.filmGauge=e.filmGauge,this.filmOffset=e.filmOffset,this},setFocalLength:function(e){var t=.5*this.getFilmHeight()/e;this.fov=2*bn.RAD2DEG*Math.atan(t),this.updateProjectionMatrix()},getFocalLength:function(){var e=Math.tan(.5*bn.DEG2RAD*this.fov);return.5*this.getFilmHeight()/e},getEffectiveFOV:function(){return 2*bn.RAD2DEG*Math.atan(Math.tan(.5*bn.DEG2RAD*this.fov)/this.zoom)},getFilmWidth:function(){return this.filmGauge*Math.min(this.aspect,1)},getFilmHeight:function(){return this.filmGauge/Math.max(this.aspect,1)},setViewOffset:function(e,t,n,r,i,o){this.aspect=e/t,null===this.view&&(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=t,this.view.offsetX=n,this.view.offsetY=r,this.view.width=i,this.view.height=o,this.updateProjectionMatrix()},clearViewOffset:function(){null!==this.view&&(this.view.enabled=!1),this.updateProjectionMatrix()},updateProjectionMatrix:function(){var e=this.near,t=e*Math.tan(.5*bn.DEG2RAD*this.fov)/this.zoom,n=2*t,r=this.aspect*n,i=-.5*r,o=this.view;if(null!==this.view&&this.view.enabled){var a=o.fullWidth,s=o.fullHeight;i+=o.offsetX*r/a,t-=o.offsetY*n/s,r*=o.width/a,n*=o.height/s}var c=this.filmOffset;0!==c&&(i+=e*c/this.getFilmWidth()),this.projectionMatrix.makePerspective(i,i+r,t,t-n,e,this.far),this.projectionMatrixInverse.getInverse(this.projectionMatrix)},toJSON:function(e){var t=or.prototype.toJSON.call(this,e);return t.object.fov=this.fov,t.object.zoom=this.zoom,t.object.near=this.near,t.object.far=this.far,t.object.focus=this.focus,t.object.aspect=this.aspect,null!==this.view&&(t.object.view=Object.assign({},this.view)),t.object.filmGauge=this.filmGauge,t.object.filmOffset=this.filmOffset,t}});var io=90,oo=1;function ao(e,t,n,r){or.call(this),this.type="CubeCamera";var i=new ro(io,oo,e,t);i.up.set(0,-1,0),i.lookAt(new En(1,0,0)),this.add(i);var o=new ro(io,oo,e,t);o.up.set(0,-1,0),o.lookAt(new En(-1,0,0)),this.add(o);var a=new ro(io,oo,e,t);a.up.set(0,0,1),a.lookAt(new En(0,1,0)),this.add(a);var s=new ro(io,oo,e,t);s.up.set(0,0,-1),s.lookAt(new En(0,-1,0)),this.add(s);var c=new ro(io,oo,e,t);c.up.set(0,-1,0),c.lookAt(new En(0,0,1)),this.add(c);var l=new ro(io,oo,e,t);l.up.set(0,-1,0),l.lookAt(new En(0,0,-1)),this.add(l),r=r||{format:je,magFilter:Te,minFilter:Te},this.renderTarget=new so(n,n,r),this.renderTarget.texture.name="CubeCamera",this.update=function(e,t){null===this.parent&&this.updateMatrixWorld();var n=e.getRenderTarget(),r=this.renderTarget,u=r.texture.generateMipmaps;r.texture.generateMipmaps=!1,e.setRenderTarget(r,0),e.render(t,i),e.setRenderTarget(r,1),e.render(t,o),e.setRenderTarget(r,2),e.render(t,a),e.setRenderTarget(r,3),e.render(t,s),e.setRenderTarget(r,4),e.render(t,c),r.texture.generateMipmaps=u,e.setRenderTarget(r,5),e.render(t,l),e.setRenderTarget(n)},this.clear=function(e,t,n,r){for(var i=e.getRenderTarget(),o=this.renderTarget,a=0;a<6;a++)e.setRenderTarget(o,a),e.clear(t,n,r);e.setRenderTarget(i)}}function so(e,t,n){On.call(this,e,t,n)}function co(e,t,n,r,i,o,a,s,c,l,u,h){Rn.call(this,null,o,a,s,c,l,r,i,u,h),this.image={data:e||null,width:t||1,height:n||1},this.magFilter=void 0!==c?c:_e,this.minFilter=void 0!==l?l:_e,this.generateMipmaps=!1,this.flipY=!1,this.unpackAlignment=1,this.needsUpdate=!0}ao.prototype=Object.create(or.prototype),ao.prototype.constructor=ao,so.prototype=Object.create(On.prototype),so.prototype.constructor=so,so.prototype.isWebGLRenderTargetCube=!0,so.prototype.fromEquirectangularTexture=function(e,t){this.texture.type=t.type,this.texture.format=t.format,this.texture.encoding=t.encoding;var n=new ar,r={uniforms:{tEquirect:{value:null}},vertexShader:["varying vec3 vWorldDirection;","vec3 transformDirection( in vec3 dir, in mat4 matrix ) {","\\treturn normalize( ( matrix * vec4( dir, 0.0 ) ).xyz );","}","void main() {","\\tvWorldDirection = transformDirection( position, modelMatrix );","\\t#include ","\\t#include ","}"].join("\\n"),fragmentShader:["uniform sampler2D tEquirect;","varying vec3 vWorldDirection;","#define RECIPROCAL_PI 0.31830988618","#define RECIPROCAL_PI2 0.15915494","void main() {","\\tvec3 direction = normalize( vWorldDirection );","\\tvec2 sampleUV;","\\tsampleUV.y = asin( clamp( direction.y, - 1.0, 1.0 ) ) * RECIPROCAL_PI + 0.5;","\\tsampleUV.x = atan( direction.z, direction.x ) * RECIPROCAL_PI2 + 0.5;","\\tgl_FragColor = texture2D( tEquirect, sampleUV );","}"].join("\\n")},i=new to({type:"CubemapFromEquirect",uniforms:Zi(r.uniforms),vertexShader:r.vertexShader,fragmentShader:r.fragmentShader,side:v,blending:E});i.uniforms.tEquirect.value=t;var o=new zi(new Ji(5,5,5),i);n.add(o);var a=new ao(1,10,1);return a.renderTarget=this,a.renderTarget.texture.name="CubeCameraTexture",a.update(e,n),o.geometry.dispose(),o.material.dispose(),this},co.prototype=Object.create(Rn.prototype),co.prototype.constructor=co,co.prototype.isDataTexture=!0;var lo=new wr,uo=new En;function ho(e,t,n,r,i,o){this.planes=[void 0!==e?e:new Ir,void 0!==t?t:new Ir,void 0!==n?n:new Ir,void 0!==r?r:new Ir,void 0!==i?i:new Ir,void 0!==o?o:new Ir]}Object.assign(ho.prototype,{set:function(e,t,n,r,i,o){var a=this.planes;return a[0].copy(e),a[1].copy(t),a[2].copy(n),a[3].copy(r),a[4].copy(i),a[5].copy(o),this},clone:function(){return(new this.constructor).copy(this)},copy:function(e){for(var t=this.planes,n=0;n<6;n++)t[n].copy(e.planes[n]);return this},setFromMatrix:function(e){var t=this.planes,n=e.elements,r=n[0],i=n[1],o=n[2],a=n[3],s=n[4],c=n[5],l=n[6],u=n[7],h=n[8],d=n[9],p=n[10],f=n[11],m=n[12],g=n[13],v=n[14],y=n[15];return t[0].setComponents(a-r,u-s,f-h,y-m).normalize(),t[1].setComponents(a+r,u+s,f+h,y+m).normalize(),t[2].setComponents(a+i,u+c,f+d,y+g).normalize(),t[3].setComponents(a-i,u-c,f-d,y-g).normalize(),t[4].setComponents(a-o,u-l,f-p,y-v).normalize(),t[5].setComponents(a+o,u+l,f+p,y+v).normalize(),this},intersectsObject:function(e){var t=e.geometry;return null===t.boundingSphere&&t.computeBoundingSphere(),lo.copy(t.boundingSphere).applyMatrix4(e.matrixWorld),this.intersectsSphere(lo)},intersectsSprite:function(e){return lo.center.set(0,0,0),lo.radius=.7071067811865476,lo.applyMatrix4(e.matrixWorld),this.intersectsSphere(lo)},intersectsSphere:function(e){for(var t=this.planes,n=e.center,r=-e.radius,i=0;i<6;i++){if(t[i].distanceToPoint(n)0?e.max.x:e.min.x,uo.y=r.normal.y>0?e.max.y:e.min.y,uo.z=r.normal.z>0?e.max.z:e.min.z,r.distanceToPoint(uo)<0)return!1}return!0},containsPoint:function(e){for(var t=this.planes,n=0;n<6;n++)if(t[n].distanceToPoint(e)<0)return!1;return!0}});var po={alphamap_fragment:"#ifdef USE_ALPHAMAP\\n\\tdiffuseColor.a *= texture2D( alphaMap, vUv ).g;\\n#endif",alphamap_pars_fragment:"#ifdef USE_ALPHAMAP\\n\\tuniform sampler2D alphaMap;\\n#endif",alphatest_fragment:"#ifdef ALPHATEST\\n\\tif ( diffuseColor.a < ALPHATEST ) discard;\\n#endif",aomap_fragment:"#ifdef USE_AOMAP\\n\\tfloat ambientOcclusion = ( texture2D( aoMap, vUv2 ).r - 1.0 ) * aoMapIntensity + 1.0;\\n\\treflectedLight.indirectDiffuse *= ambientOcclusion;\\n\\t#if defined( USE_ENVMAP ) && defined( STANDARD )\\n\\t\\tfloat dotNV = saturate( dot( geometry.normal, geometry.viewDir ) );\\n\\t\\treflectedLight.indirectSpecular *= computeSpecularOcclusion( dotNV, ambientOcclusion, material.specularRoughness );\\n\\t#endif\\n#endif",aomap_pars_fragment:"#ifdef USE_AOMAP\\n\\tuniform sampler2D aoMap;\\n\\tuniform float aoMapIntensity;\\n#endif",begin_vertex:"vec3 transformed = vec3( position );",beginnormal_vertex:"vec3 objectNormal = vec3( normal );\\n#ifdef USE_TANGENT\\n\\tvec3 objectTangent = vec3( tangent.xyz );\\n#endif",bsdfs:"vec2 integrateSpecularBRDF( const in float dotNV, const in float roughness ) {\\n\\tconst vec4 c0 = vec4( - 1, - 0.0275, - 0.572, 0.022 );\\n\\tconst vec4 c1 = vec4( 1, 0.0425, 1.04, - 0.04 );\\n\\tvec4 r = roughness * c0 + c1;\\n\\tfloat a004 = min( r.x * r.x, exp2( - 9.28 * dotNV ) ) * r.x + r.y;\\n\\treturn vec2( -1.04, 1.04 ) * a004 + r.zw;\\n}\\nfloat punctualLightIntensityToIrradianceFactor( const in float lightDistance, const in float cutoffDistance, const in float decayExponent ) {\\n#if defined ( PHYSICALLY_CORRECT_LIGHTS )\\n\\tfloat distanceFalloff = 1.0 / max( pow( lightDistance, decayExponent ), 0.01 );\\n\\tif( cutoffDistance > 0.0 ) {\\n\\t\\tdistanceFalloff *= pow2( saturate( 1.0 - pow4( lightDistance / cutoffDistance ) ) );\\n\\t}\\n\\treturn distanceFalloff;\\n#else\\n\\tif( cutoffDistance > 0.0 && decayExponent > 0.0 ) {\\n\\t\\treturn pow( saturate( -lightDistance / cutoffDistance + 1.0 ), decayExponent );\\n\\t}\\n\\treturn 1.0;\\n#endif\\n}\\nvec3 BRDF_Diffuse_Lambert( const in vec3 diffuseColor ) {\\n\\treturn RECIPROCAL_PI * diffuseColor;\\n}\\nvec3 F_Schlick( const in vec3 specularColor, const in float dotLH ) {\\n\\tfloat fresnel = exp2( ( -5.55473 * dotLH - 6.98316 ) * dotLH );\\n\\treturn ( 1.0 - specularColor ) * fresnel + specularColor;\\n}\\nvec3 F_Schlick_RoughnessDependent( const in vec3 F0, const in float dotNV, const in float roughness ) {\\n\\tfloat fresnel = exp2( ( -5.55473 * dotNV - 6.98316 ) * dotNV );\\n\\tvec3 Fr = max( vec3( 1.0 - roughness ), F0 ) - F0;\\n\\treturn Fr * fresnel + F0;\\n}\\nfloat G_GGX_Smith( const in float alpha, const in float dotNL, const in float dotNV ) {\\n\\tfloat a2 = pow2( alpha );\\n\\tfloat gl = dotNL + sqrt( a2 + ( 1.0 - a2 ) * pow2( dotNL ) );\\n\\tfloat gv = dotNV + sqrt( a2 + ( 1.0 - a2 ) * pow2( dotNV ) );\\n\\treturn 1.0 / ( gl * gv );\\n}\\nfloat G_GGX_SmithCorrelated( const in float alpha, const in float dotNL, const in float dotNV ) {\\n\\tfloat a2 = pow2( alpha );\\n\\tfloat gv = dotNL * sqrt( a2 + ( 1.0 - a2 ) * pow2( dotNV ) );\\n\\tfloat gl = dotNV * sqrt( a2 + ( 1.0 - a2 ) * pow2( dotNL ) );\\n\\treturn 0.5 / max( gv + gl, EPSILON );\\n}\\nfloat D_GGX( const in float alpha, const in float dotNH ) {\\n\\tfloat a2 = pow2( alpha );\\n\\tfloat denom = pow2( dotNH ) * ( a2 - 1.0 ) + 1.0;\\n\\treturn RECIPROCAL_PI * a2 / pow2( denom );\\n}\\nvec3 BRDF_Specular_GGX( const in IncidentLight incidentLight, const in vec3 viewDir, const in vec3 normal, const in vec3 specularColor, const in float roughness ) {\\n\\tfloat alpha = pow2( roughness );\\n\\tvec3 halfDir = normalize( incidentLight.direction + viewDir );\\n\\tfloat dotNL = saturate( dot( normal, incidentLight.direction ) );\\n\\tfloat dotNV = saturate( dot( normal, viewDir ) );\\n\\tfloat dotNH = saturate( dot( normal, halfDir ) );\\n\\tfloat dotLH = saturate( dot( incidentLight.direction, halfDir ) );\\n\\tvec3 F = F_Schlick( specularColor, dotLH );\\n\\tfloat G = G_GGX_SmithCorrelated( alpha, dotNL, dotNV );\\n\\tfloat D = D_GGX( alpha, dotNH );\\n\\treturn F * ( G * D );\\n}\\nvec2 LTC_Uv( const in vec3 N, const in vec3 V, const in float roughness ) {\\n\\tconst float LUT_SIZE = 64.0;\\n\\tconst float LUT_SCALE = ( LUT_SIZE - 1.0 ) / LUT_SIZE;\\n\\tconst float LUT_BIAS = 0.5 / LUT_SIZE;\\n\\tfloat dotNV = saturate( dot( N, V ) );\\n\\tvec2 uv = vec2( roughness, sqrt( 1.0 - dotNV ) );\\n\\tuv = uv * LUT_SCALE + LUT_BIAS;\\n\\treturn uv;\\n}\\nfloat LTC_ClippedSphereFormFactor( const in vec3 f ) {\\n\\tfloat l = length( f );\\n\\treturn max( ( l * l + f.z ) / ( l + 1.0 ), 0.0 );\\n}\\nvec3 LTC_EdgeVectorFormFactor( const in vec3 v1, const in vec3 v2 ) {\\n\\tfloat x = dot( v1, v2 );\\n\\tfloat y = abs( x );\\n\\tfloat a = 0.8543985 + ( 0.4965155 + 0.0145206 * y ) * y;\\n\\tfloat b = 3.4175940 + ( 4.1616724 + y ) * y;\\n\\tfloat v = a / b;\\n\\tfloat theta_sintheta = ( x > 0.0 ) ? v : 0.5 * inversesqrt( max( 1.0 - x * x, 1e-7 ) ) - v;\\n\\treturn cross( v1, v2 ) * theta_sintheta;\\n}\\nvec3 LTC_Evaluate( const in vec3 N, const in vec3 V, const in vec3 P, const in mat3 mInv, const in vec3 rectCoords[ 4 ] ) {\\n\\tvec3 v1 = rectCoords[ 1 ] - rectCoords[ 0 ];\\n\\tvec3 v2 = rectCoords[ 3 ] - rectCoords[ 0 ];\\n\\tvec3 lightNormal = cross( v1, v2 );\\n\\tif( dot( lightNormal, P - rectCoords[ 0 ] ) < 0.0 ) return vec3( 0.0 );\\n\\tvec3 T1, T2;\\n\\tT1 = normalize( V - N * dot( V, N ) );\\n\\tT2 = - cross( N, T1 );\\n\\tmat3 mat = mInv * transposeMat3( mat3( T1, T2, N ) );\\n\\tvec3 coords[ 4 ];\\n\\tcoords[ 0 ] = mat * ( rectCoords[ 0 ] - P );\\n\\tcoords[ 1 ] = mat * ( rectCoords[ 1 ] - P );\\n\\tcoords[ 2 ] = mat * ( rectCoords[ 2 ] - P );\\n\\tcoords[ 3 ] = mat * ( rectCoords[ 3 ] - P );\\n\\tcoords[ 0 ] = normalize( coords[ 0 ] );\\n\\tcoords[ 1 ] = normalize( coords[ 1 ] );\\n\\tcoords[ 2 ] = normalize( coords[ 2 ] );\\n\\tcoords[ 3 ] = normalize( coords[ 3 ] );\\n\\tvec3 vectorFormFactor = vec3( 0.0 );\\n\\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 0 ], coords[ 1 ] );\\n\\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 1 ], coords[ 2 ] );\\n\\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 2 ], coords[ 3 ] );\\n\\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 3 ], coords[ 0 ] );\\n\\tfloat result = LTC_ClippedSphereFormFactor( vectorFormFactor );\\n\\treturn vec3( result );\\n}\\nvec3 BRDF_Specular_GGX_Environment( const in vec3 viewDir, const in vec3 normal, const in vec3 specularColor, const in float roughness ) {\\n\\tfloat dotNV = saturate( dot( normal, viewDir ) );\\n\\tvec2 brdf = integrateSpecularBRDF( dotNV, roughness );\\n\\treturn specularColor * brdf.x + brdf.y;\\n}\\nvoid BRDF_Specular_Multiscattering_Environment( const in GeometricContext geometry, const in vec3 specularColor, const in float roughness, inout vec3 singleScatter, inout vec3 multiScatter ) {\\n\\tfloat dotNV = saturate( dot( geometry.normal, geometry.viewDir ) );\\n\\tvec3 F = F_Schlick_RoughnessDependent( specularColor, dotNV, roughness );\\n\\tvec2 brdf = integrateSpecularBRDF( dotNV, roughness );\\n\\tvec3 FssEss = F * brdf.x + brdf.y;\\n\\tfloat Ess = brdf.x + brdf.y;\\n\\tfloat Ems = 1.0 - Ess;\\n\\tvec3 Favg = specularColor + ( 1.0 - specularColor ) * 0.047619;\\tvec3 Fms = FssEss * Favg / ( 1.0 - Ems * Favg );\\n\\tsingleScatter += FssEss;\\n\\tmultiScatter += Fms * Ems;\\n}\\nfloat G_BlinnPhong_Implicit( ) {\\n\\treturn 0.25;\\n}\\nfloat D_BlinnPhong( const in float shininess, const in float dotNH ) {\\n\\treturn RECIPROCAL_PI * ( shininess * 0.5 + 1.0 ) * pow( dotNH, shininess );\\n}\\nvec3 BRDF_Specular_BlinnPhong( const in IncidentLight incidentLight, const in GeometricContext geometry, const in vec3 specularColor, const in float shininess ) {\\n\\tvec3 halfDir = normalize( incidentLight.direction + geometry.viewDir );\\n\\tfloat dotNH = saturate( dot( geometry.normal, halfDir ) );\\n\\tfloat dotLH = saturate( dot( incidentLight.direction, halfDir ) );\\n\\tvec3 F = F_Schlick( specularColor, dotLH );\\n\\tfloat G = G_BlinnPhong_Implicit( );\\n\\tfloat D = D_BlinnPhong( shininess, dotNH );\\n\\treturn F * ( G * D );\\n}\\nfloat GGXRoughnessToBlinnExponent( const in float ggxRoughness ) {\\n\\treturn ( 2.0 / pow2( ggxRoughness + 0.0001 ) - 2.0 );\\n}\\nfloat BlinnExponentToGGXRoughness( const in float blinnExponent ) {\\n\\treturn sqrt( 2.0 / ( blinnExponent + 2.0 ) );\\n}\\n#if defined( USE_SHEEN )\\nfloat D_Charlie(float roughness, float NoH) {\\n\\tfloat invAlpha = 1.0 / roughness;\\n\\tfloat cos2h = NoH * NoH;\\n\\tfloat sin2h = max(1.0 - cos2h, 0.0078125);\\treturn (2.0 + invAlpha) * pow(sin2h, invAlpha * 0.5) / (2.0 * PI);\\n}\\nfloat V_Neubelt(float NoV, float NoL) {\\n\\treturn saturate(1.0 / (4.0 * (NoL + NoV - NoL * NoV)));\\n}\\nvec3 BRDF_Specular_Sheen( const in float roughness, const in vec3 L, const in GeometricContext geometry, vec3 specularColor ) {\\n\\tvec3 N = geometry.normal;\\n\\tvec3 V = geometry.viewDir;\\n\\tvec3 H = normalize( V + L );\\n\\tfloat dotNH = saturate( dot( N, H ) );\\n\\treturn specularColor * D_Charlie( roughness, dotNH ) * V_Neubelt( dot(N, V), dot(N, L) );\\n}\\n#endif",bumpmap_pars_fragment:"#ifdef USE_BUMPMAP\\n\\tuniform sampler2D bumpMap;\\n\\tuniform float bumpScale;\\n\\tvec2 dHdxy_fwd() {\\n\\t\\tvec2 dSTdx = dFdx( vUv );\\n\\t\\tvec2 dSTdy = dFdy( vUv );\\n\\t\\tfloat Hll = bumpScale * texture2D( bumpMap, vUv ).x;\\n\\t\\tfloat dBx = bumpScale * texture2D( bumpMap, vUv + dSTdx ).x - Hll;\\n\\t\\tfloat dBy = bumpScale * texture2D( bumpMap, vUv + dSTdy ).x - Hll;\\n\\t\\treturn vec2( dBx, dBy );\\n\\t}\\n\\tvec3 perturbNormalArb( vec3 surf_pos, vec3 surf_norm, vec2 dHdxy ) {\\n\\t\\tvec3 vSigmaX = vec3( dFdx( surf_pos.x ), dFdx( surf_pos.y ), dFdx( surf_pos.z ) );\\n\\t\\tvec3 vSigmaY = vec3( dFdy( surf_pos.x ), dFdy( surf_pos.y ), dFdy( surf_pos.z ) );\\n\\t\\tvec3 vN = surf_norm;\\n\\t\\tvec3 R1 = cross( vSigmaY, vN );\\n\\t\\tvec3 R2 = cross( vN, vSigmaX );\\n\\t\\tfloat fDet = dot( vSigmaX, R1 );\\n\\t\\tfDet *= ( float( gl_FrontFacing ) * 2.0 - 1.0 );\\n\\t\\tvec3 vGrad = sign( fDet ) * ( dHdxy.x * R1 + dHdxy.y * R2 );\\n\\t\\treturn normalize( abs( fDet ) * surf_norm - vGrad );\\n\\t}\\n#endif",clipping_planes_fragment:"#if NUM_CLIPPING_PLANES > 0\\n\\tvec4 plane;\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < UNION_CLIPPING_PLANES; i ++ ) {\\n\\t\\tplane = clippingPlanes[ i ];\\n\\t\\tif ( dot( vViewPosition, plane.xyz ) > plane.w ) discard;\\n\\t}\\n\\t#if UNION_CLIPPING_PLANES < NUM_CLIPPING_PLANES\\n\\t\\tbool clipped = true;\\n\\t\\t#pragma unroll_loop\\n\\t\\tfor ( int i = UNION_CLIPPING_PLANES; i < NUM_CLIPPING_PLANES; i ++ ) {\\n\\t\\t\\tplane = clippingPlanes[ i ];\\n\\t\\t\\tclipped = ( dot( vViewPosition, plane.xyz ) > plane.w ) && clipped;\\n\\t\\t}\\n\\t\\tif ( clipped ) discard;\\n\\t#endif\\n#endif",clipping_planes_pars_fragment:"#if NUM_CLIPPING_PLANES > 0\\n\\t#if ! defined( STANDARD ) && ! defined( PHONG ) && ! defined( MATCAP )\\n\\t\\tvarying vec3 vViewPosition;\\n\\t#endif\\n\\tuniform vec4 clippingPlanes[ NUM_CLIPPING_PLANES ];\\n#endif",clipping_planes_pars_vertex:"#if NUM_CLIPPING_PLANES > 0 && ! defined( STANDARD ) && ! defined( PHONG ) && ! defined( MATCAP )\\n\\tvarying vec3 vViewPosition;\\n#endif",clipping_planes_vertex:"#if NUM_CLIPPING_PLANES > 0 && ! defined( STANDARD ) && ! defined( PHONG ) && ! defined( MATCAP )\\n\\tvViewPosition = - mvPosition.xyz;\\n#endif",color_fragment:"#ifdef USE_COLOR\\n\\tdiffuseColor.rgb *= vColor;\\n#endif",color_pars_fragment:"#ifdef USE_COLOR\\n\\tvarying vec3 vColor;\\n#endif",color_pars_vertex:"#ifdef USE_COLOR\\n\\tvarying vec3 vColor;\\n#endif",color_vertex:"#ifdef USE_COLOR\\n\\tvColor.xyz = color.xyz;\\n#endif",common:"#define PI 3.14159265359\\n#define PI2 6.28318530718\\n#define PI_HALF 1.5707963267949\\n#define RECIPROCAL_PI 0.31830988618\\n#define RECIPROCAL_PI2 0.15915494\\n#define LOG2 1.442695\\n#define EPSILON 1e-6\\n#ifndef saturate\\n#define saturate(a) clamp( a, 0.0, 1.0 )\\n#endif\\n#define whiteComplement(a) ( 1.0 - saturate( a ) )\\nfloat pow2( const in float x ) { return x*x; }\\nfloat pow3( const in float x ) { return x*x*x; }\\nfloat pow4( const in float x ) { float x2 = x*x; return x2*x2; }\\nfloat average( const in vec3 color ) { return dot( color, vec3( 0.3333 ) ); }\\nhighp float rand( const in vec2 uv ) {\\n\\tconst highp float a = 12.9898, b = 78.233, c = 43758.5453;\\n\\thighp float dt = dot( uv.xy, vec2( a,b ) ), sn = mod( dt, PI );\\n\\treturn fract(sin(sn) * c);\\n}\\n#ifdef HIGH_PRECISION\\n\\tfloat precisionSafeLength( vec3 v ) { return length( v ); }\\n#else\\n\\tfloat max3( vec3 v ) { return max( max( v.x, v.y ), v.z ); }\\n\\tfloat precisionSafeLength( vec3 v ) {\\n\\t\\tfloat maxComponent = max3( abs( v ) );\\n\\t\\treturn length( v / maxComponent ) * maxComponent;\\n\\t}\\n#endif\\nstruct IncidentLight {\\n\\tvec3 color;\\n\\tvec3 direction;\\n\\tbool visible;\\n};\\nstruct ReflectedLight {\\n\\tvec3 directDiffuse;\\n\\tvec3 directSpecular;\\n\\tvec3 indirectDiffuse;\\n\\tvec3 indirectSpecular;\\n};\\nstruct GeometricContext {\\n\\tvec3 position;\\n\\tvec3 normal;\\n\\tvec3 viewDir;\\n#ifdef CLEARCOAT\\n\\tvec3 clearcoatNormal;\\n#endif\\n};\\nvec3 transformDirection( in vec3 dir, in mat4 matrix ) {\\n\\treturn normalize( ( matrix * vec4( dir, 0.0 ) ).xyz );\\n}\\nvec3 inverseTransformDirection( in vec3 dir, in mat4 matrix ) {\\n\\treturn normalize( ( vec4( dir, 0.0 ) * matrix ).xyz );\\n}\\nvec3 projectOnPlane(in vec3 point, in vec3 pointOnPlane, in vec3 planeNormal ) {\\n\\tfloat distance = dot( planeNormal, point - pointOnPlane );\\n\\treturn - distance * planeNormal + point;\\n}\\nfloat sideOfPlane( in vec3 point, in vec3 pointOnPlane, in vec3 planeNormal ) {\\n\\treturn sign( dot( point - pointOnPlane, planeNormal ) );\\n}\\nvec3 linePlaneIntersect( in vec3 pointOnLine, in vec3 lineDirection, in vec3 pointOnPlane, in vec3 planeNormal ) {\\n\\treturn lineDirection * ( dot( planeNormal, pointOnPlane - pointOnLine ) / dot( planeNormal, lineDirection ) ) + pointOnLine;\\n}\\nmat3 transposeMat3( const in mat3 m ) {\\n\\tmat3 tmp;\\n\\ttmp[ 0 ] = vec3( m[ 0 ].x, m[ 1 ].x, m[ 2 ].x );\\n\\ttmp[ 1 ] = vec3( m[ 0 ].y, m[ 1 ].y, m[ 2 ].y );\\n\\ttmp[ 2 ] = vec3( m[ 0 ].z, m[ 1 ].z, m[ 2 ].z );\\n\\treturn tmp;\\n}\\nfloat linearToRelativeLuminance( const in vec3 color ) {\\n\\tvec3 weights = vec3( 0.2126, 0.7152, 0.0722 );\\n\\treturn dot( weights, color.rgb );\\n}\\nbool isPerspectiveMatrix( mat4 m ) {\\n return m[ 2 ][ 3 ] == - 1.0;\\n}",cube_uv_reflection_fragment:"#ifdef ENVMAP_TYPE_CUBE_UV\\n#define cubeUV_textureSize (1024.0)\\nint getFaceFromDirection(vec3 direction) {\\n\\tvec3 absDirection = abs(direction);\\n\\tint face = -1;\\n\\tif( absDirection.x > absDirection.z ) {\\n\\t\\tif(absDirection.x > absDirection.y )\\n\\t\\t\\tface = direction.x > 0.0 ? 0 : 3;\\n\\t\\telse\\n\\t\\t\\tface = direction.y > 0.0 ? 1 : 4;\\n\\t}\\n\\telse {\\n\\t\\tif(absDirection.z > absDirection.y )\\n\\t\\t\\tface = direction.z > 0.0 ? 2 : 5;\\n\\t\\telse\\n\\t\\t\\tface = direction.y > 0.0 ? 1 : 4;\\n\\t}\\n\\treturn face;\\n}\\n#define cubeUV_maxLods1 (log2(cubeUV_textureSize*0.25) - 1.0)\\n#define cubeUV_rangeClamp (exp2((6.0 - 1.0) * 2.0))\\nvec2 MipLevelInfo( vec3 vec, float roughnessLevel, float roughness ) {\\n\\tfloat scale = exp2(cubeUV_maxLods1 - roughnessLevel);\\n\\tfloat dxRoughness = dFdx(roughness);\\n\\tfloat dyRoughness = dFdy(roughness);\\n\\tvec3 dx = dFdx( vec * scale * dxRoughness );\\n\\tvec3 dy = dFdy( vec * scale * dyRoughness );\\n\\tfloat d = max( dot( dx, dx ), dot( dy, dy ) );\\n\\td = clamp(d, 1.0, cubeUV_rangeClamp);\\n\\tfloat mipLevel = 0.5 * log2(d);\\n\\treturn vec2(floor(mipLevel), fract(mipLevel));\\n}\\n#define cubeUV_maxLods2 (log2(cubeUV_textureSize*0.25) - 2.0)\\n#define cubeUV_rcpTextureSize (1.0 / cubeUV_textureSize)\\nvec2 getCubeUV(vec3 direction, float roughnessLevel, float mipLevel) {\\n\\tmipLevel = roughnessLevel > cubeUV_maxLods2 - 3.0 ? 0.0 : mipLevel;\\n\\tfloat a = 16.0 * cubeUV_rcpTextureSize;\\n\\tvec2 exp2_packed = exp2( vec2( roughnessLevel, mipLevel ) );\\n\\tvec2 rcp_exp2_packed = vec2( 1.0 ) / exp2_packed;\\n\\tfloat powScale = exp2_packed.x * exp2_packed.y;\\n\\tfloat scale = rcp_exp2_packed.x * rcp_exp2_packed.y * 0.25;\\n\\tfloat mipOffset = 0.75*(1.0 - rcp_exp2_packed.y) * rcp_exp2_packed.x;\\n\\tbool bRes = mipLevel == 0.0;\\n\\tscale = bRes && (scale < a) ? a : scale;\\n\\tvec3 r;\\n\\tvec2 offset;\\n\\tint face = getFaceFromDirection(direction);\\n\\tfloat rcpPowScale = 1.0 / powScale;\\n\\tif( face == 0) {\\n\\t\\tr = vec3(direction.x, -direction.z, direction.y);\\n\\t\\toffset = vec2(0.0+mipOffset,0.75 * rcpPowScale);\\n\\t\\toffset.y = bRes && (offset.y < 2.0*a) ? a : offset.y;\\n\\t}\\n\\telse if( face == 1) {\\n\\t\\tr = vec3(direction.y, direction.x, direction.z);\\n\\t\\toffset = vec2(scale+mipOffset, 0.75 * rcpPowScale);\\n\\t\\toffset.y = bRes && (offset.y < 2.0*a) ? a : offset.y;\\n\\t}\\n\\telse if( face == 2) {\\n\\t\\tr = vec3(direction.z, direction.x, direction.y);\\n\\t\\toffset = vec2(2.0*scale+mipOffset, 0.75 * rcpPowScale);\\n\\t\\toffset.y = bRes && (offset.y < 2.0*a) ? a : offset.y;\\n\\t}\\n\\telse if( face == 3) {\\n\\t\\tr = vec3(direction.x, direction.z, direction.y);\\n\\t\\toffset = vec2(0.0+mipOffset,0.5 * rcpPowScale);\\n\\t\\toffset.y = bRes && (offset.y < 2.0*a) ? 0.0 : offset.y;\\n\\t}\\n\\telse if( face == 4) {\\n\\t\\tr = vec3(direction.y, direction.x, -direction.z);\\n\\t\\toffset = vec2(scale+mipOffset, 0.5 * rcpPowScale);\\n\\t\\toffset.y = bRes && (offset.y < 2.0*a) ? 0.0 : offset.y;\\n\\t}\\n\\telse {\\n\\t\\tr = vec3(direction.z, -direction.x, direction.y);\\n\\t\\toffset = vec2(2.0*scale+mipOffset, 0.5 * rcpPowScale);\\n\\t\\toffset.y = bRes && (offset.y < 2.0*a) ? 0.0 : offset.y;\\n\\t}\\n\\tr = normalize(r);\\n\\tfloat texelOffset = 0.5 * cubeUV_rcpTextureSize;\\n\\tvec2 s = ( r.yz / abs( r.x ) + vec2( 1.0 ) ) * 0.5;\\n\\tvec2 base = offset + vec2( texelOffset );\\n\\treturn base + s * ( scale - 2.0 * texelOffset );\\n}\\n#define cubeUV_maxLods3 (log2(cubeUV_textureSize*0.25) - 3.0)\\nvec4 textureCubeUV( sampler2D envMap, vec3 reflectedDirection, float roughness ) {\\n\\tfloat roughnessVal = roughness* cubeUV_maxLods3;\\n\\tfloat r1 = floor(roughnessVal);\\n\\tfloat r2 = r1 + 1.0;\\n\\tfloat t = fract(roughnessVal);\\n\\tvec2 mipInfo = MipLevelInfo(reflectedDirection, r1, roughness);\\n\\tfloat s = mipInfo.y;\\n\\tfloat level0 = mipInfo.x;\\n\\tfloat level1 = level0 + 1.0;\\n\\tlevel1 = level1 > 5.0 ? 5.0 : level1;\\n\\tlevel0 += min( floor( s + 0.5 ), 5.0 );\\n\\tvec2 uv_10 = getCubeUV(reflectedDirection, r1, level0);\\n\\tvec4 color10 = envMapTexelToLinear(texture2D(envMap, uv_10));\\n\\tvec2 uv_20 = getCubeUV(reflectedDirection, r2, level0);\\n\\tvec4 color20 = envMapTexelToLinear(texture2D(envMap, uv_20));\\n\\tvec4 result = mix(color10, color20, t);\\n\\treturn vec4(result.rgb, 1.0);\\n}\\n#endif",defaultnormal_vertex:"vec3 transformedNormal = objectNormal;\\n#ifdef USE_INSTANCING\\n\\ttransformedNormal = mat3( instanceMatrix ) * transformedNormal;\\n#endif\\ntransformedNormal = normalMatrix * transformedNormal;\\n#ifdef FLIP_SIDED\\n\\ttransformedNormal = - transformedNormal;\\n#endif\\n#ifdef USE_TANGENT\\n\\tvec3 transformedTangent = normalMatrix * objectTangent;\\n\\t#ifdef FLIP_SIDED\\n\\t\\ttransformedTangent = - transformedTangent;\\n\\t#endif\\n#endif",displacementmap_pars_vertex:"#ifdef USE_DISPLACEMENTMAP\\n\\tuniform sampler2D displacementMap;\\n\\tuniform float displacementScale;\\n\\tuniform float displacementBias;\\n#endif",displacementmap_vertex:"#ifdef USE_DISPLACEMENTMAP\\n\\ttransformed += normalize( objectNormal ) * ( texture2D( displacementMap, vUv ).x * displacementScale + displacementBias );\\n#endif",emissivemap_fragment:"#ifdef USE_EMISSIVEMAP\\n\\tvec4 emissiveColor = texture2D( emissiveMap, vUv );\\n\\temissiveColor.rgb = emissiveMapTexelToLinear( emissiveColor ).rgb;\\n\\ttotalEmissiveRadiance *= emissiveColor.rgb;\\n#endif",emissivemap_pars_fragment:"#ifdef USE_EMISSIVEMAP\\n\\tuniform sampler2D emissiveMap;\\n#endif",encodings_fragment:"gl_FragColor = linearToOutputTexel( gl_FragColor );",encodings_pars_fragment:"\\nvec4 LinearToLinear( in vec4 value ) {\\n\\treturn value;\\n}\\nvec4 GammaToLinear( in vec4 value, in float gammaFactor ) {\\n\\treturn vec4( pow( value.rgb, vec3( gammaFactor ) ), value.a );\\n}\\nvec4 LinearToGamma( in vec4 value, in float gammaFactor ) {\\n\\treturn vec4( pow( value.rgb, vec3( 1.0 / gammaFactor ) ), value.a );\\n}\\nvec4 sRGBToLinear( in vec4 value ) {\\n\\treturn vec4( mix( pow( value.rgb * 0.9478672986 + vec3( 0.0521327014 ), vec3( 2.4 ) ), value.rgb * 0.0773993808, vec3( lessThanEqual( value.rgb, vec3( 0.04045 ) ) ) ), value.a );\\n}\\nvec4 LinearTosRGB( in vec4 value ) {\\n\\treturn 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 );\\n}\\nvec4 RGBEToLinear( in vec4 value ) {\\n\\treturn vec4( value.rgb * exp2( value.a * 255.0 - 128.0 ), 1.0 );\\n}\\nvec4 LinearToRGBE( in vec4 value ) {\\n\\tfloat maxComponent = max( max( value.r, value.g ), value.b );\\n\\tfloat fExp = clamp( ceil( log2( maxComponent ) ), -128.0, 127.0 );\\n\\treturn vec4( value.rgb / exp2( fExp ), ( fExp + 128.0 ) / 255.0 );\\n}\\nvec4 RGBMToLinear( in vec4 value, in float maxRange ) {\\n\\treturn vec4( value.rgb * value.a * maxRange, 1.0 );\\n}\\nvec4 LinearToRGBM( in vec4 value, in float maxRange ) {\\n\\tfloat maxRGB = max( value.r, max( value.g, value.b ) );\\n\\tfloat M = clamp( maxRGB / maxRange, 0.0, 1.0 );\\n\\tM = ceil( M * 255.0 ) / 255.0;\\n\\treturn vec4( value.rgb / ( M * maxRange ), M );\\n}\\nvec4 RGBDToLinear( in vec4 value, in float maxRange ) {\\n\\treturn vec4( value.rgb * ( ( maxRange / 255.0 ) / value.a ), 1.0 );\\n}\\nvec4 LinearToRGBD( in vec4 value, in float maxRange ) {\\n\\tfloat maxRGB = max( value.r, max( value.g, value.b ) );\\n\\tfloat D = max( maxRange / maxRGB, 1.0 );\\n\\tD = min( floor( D ) / 255.0, 1.0 );\\n\\treturn vec4( value.rgb * ( D * ( 255.0 / maxRange ) ), D );\\n}\\nconst mat3 cLogLuvM = mat3( 0.2209, 0.3390, 0.4184, 0.1138, 0.6780, 0.7319, 0.0102, 0.1130, 0.2969 );\\nvec4 LinearToLogLuv( in vec4 value ) {\\n\\tvec3 Xp_Y_XYZp = cLogLuvM * value.rgb;\\n\\tXp_Y_XYZp = max( Xp_Y_XYZp, vec3( 1e-6, 1e-6, 1e-6 ) );\\n\\tvec4 vResult;\\n\\tvResult.xy = Xp_Y_XYZp.xy / Xp_Y_XYZp.z;\\n\\tfloat Le = 2.0 * log2(Xp_Y_XYZp.y) + 127.0;\\n\\tvResult.w = fract( Le );\\n\\tvResult.z = ( Le - ( floor( vResult.w * 255.0 ) ) / 255.0 ) / 255.0;\\n\\treturn vResult;\\n}\\nconst mat3 cLogLuvInverseM = mat3( 6.0014, -2.7008, -1.7996, -1.3320, 3.1029, -5.7721, 0.3008, -1.0882, 5.6268 );\\nvec4 LogLuvToLinear( in vec4 value ) {\\n\\tfloat Le = value.z * 255.0 + value.w;\\n\\tvec3 Xp_Y_XYZp;\\n\\tXp_Y_XYZp.y = exp2( ( Le - 127.0 ) / 2.0 );\\n\\tXp_Y_XYZp.z = Xp_Y_XYZp.y / value.y;\\n\\tXp_Y_XYZp.x = value.x * Xp_Y_XYZp.z;\\n\\tvec3 vRGB = cLogLuvInverseM * Xp_Y_XYZp.rgb;\\n\\treturn vec4( max( vRGB, 0.0 ), 1.0 );\\n}",envmap_fragment:"#ifdef USE_ENVMAP\\n\\t#ifdef ENV_WORLDPOS\\n\\t\\tvec3 cameraToFrag;\\n\\t\\t\\n\\t\\tif ( isOrthographic ) {\\n\\t\\t\\tcameraToFrag = normalize( vec3( - viewMatrix[ 0 ][ 2 ], - viewMatrix[ 1 ][ 2 ], - viewMatrix[ 2 ][ 2 ] ) );\\n\\t\\t} else {\\n\\t\\t\\tcameraToFrag = normalize( vWorldPosition - cameraPosition );\\n\\t\\t}\\n\\t\\tvec3 worldNormal = inverseTransformDirection( normal, viewMatrix );\\n\\t\\t#ifdef ENVMAP_MODE_REFLECTION\\n\\t\\t\\tvec3 reflectVec = reflect( cameraToFrag, worldNormal );\\n\\t\\t#else\\n\\t\\t\\tvec3 reflectVec = refract( cameraToFrag, worldNormal, refractionRatio );\\n\\t\\t#endif\\n\\t#else\\n\\t\\tvec3 reflectVec = vReflect;\\n\\t#endif\\n\\t#ifdef ENVMAP_TYPE_CUBE\\n\\t\\tvec4 envColor = textureCube( envMap, vec3( flipEnvMap * reflectVec.x, reflectVec.yz ) );\\n\\t#elif defined( ENVMAP_TYPE_EQUIREC )\\n\\t\\tvec2 sampleUV;\\n\\t\\treflectVec = normalize( reflectVec );\\n\\t\\tsampleUV.y = asin( clamp( reflectVec.y, - 1.0, 1.0 ) ) * RECIPROCAL_PI + 0.5;\\n\\t\\tsampleUV.x = atan( reflectVec.z, reflectVec.x ) * RECIPROCAL_PI2 + 0.5;\\n\\t\\tvec4 envColor = texture2D( envMap, sampleUV );\\n\\t#elif defined( ENVMAP_TYPE_SPHERE )\\n\\t\\treflectVec = normalize( reflectVec );\\n\\t\\tvec3 reflectView = normalize( ( viewMatrix * vec4( reflectVec, 0.0 ) ).xyz + vec3( 0.0, 0.0, 1.0 ) );\\n\\t\\tvec4 envColor = texture2D( envMap, reflectView.xy * 0.5 + 0.5 );\\n\\t#else\\n\\t\\tvec4 envColor = vec4( 0.0 );\\n\\t#endif\\n\\tenvColor = envMapTexelToLinear( envColor );\\n\\t#ifdef ENVMAP_BLENDING_MULTIPLY\\n\\t\\toutgoingLight = mix( outgoingLight, outgoingLight * envColor.xyz, specularStrength * reflectivity );\\n\\t#elif defined( ENVMAP_BLENDING_MIX )\\n\\t\\toutgoingLight = mix( outgoingLight, envColor.xyz, specularStrength * reflectivity );\\n\\t#elif defined( ENVMAP_BLENDING_ADD )\\n\\t\\toutgoingLight += envColor.xyz * specularStrength * reflectivity;\\n\\t#endif\\n#endif",envmap_common_pars_fragment:"#ifdef USE_ENVMAP\\n\\tuniform float envMapIntensity;\\n\\tuniform float flipEnvMap;\\n\\tuniform int maxMipLevel;\\n\\t#ifdef ENVMAP_TYPE_CUBE\\n\\t\\tuniform samplerCube envMap;\\n\\t#else\\n\\t\\tuniform sampler2D envMap;\\n\\t#endif\\n\\t\\n#endif",envmap_pars_fragment:"#ifdef USE_ENVMAP\\n\\tuniform float reflectivity;\\n\\t#if defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( PHONG )\\n\\t\\t#define ENV_WORLDPOS\\n\\t#endif\\n\\t#ifdef ENV_WORLDPOS\\n\\t\\tvarying vec3 vWorldPosition;\\n\\t\\tuniform float refractionRatio;\\n\\t#else\\n\\t\\tvarying vec3 vReflect;\\n\\t#endif\\n#endif",envmap_pars_vertex:"#ifdef USE_ENVMAP\\n\\t#if defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) ||defined( PHONG )\\n\\t\\t#define ENV_WORLDPOS\\n\\t#endif\\n\\t#ifdef ENV_WORLDPOS\\n\\t\\t\\n\\t\\tvarying vec3 vWorldPosition;\\n\\t#else\\n\\t\\tvarying vec3 vReflect;\\n\\t\\tuniform float refractionRatio;\\n\\t#endif\\n#endif",envmap_physical_pars_fragment:"#if defined( USE_ENVMAP )\\n\\t#ifdef ENVMAP_MODE_REFRACTION\\n\\t\\tuniform float refractionRatio;\\n\\t#endif\\n\\tvec3 getLightProbeIndirectIrradiance( const in GeometricContext geometry, const in int maxMIPLevel ) {\\n\\t\\tvec3 worldNormal = inverseTransformDirection( geometry.normal, viewMatrix );\\n\\t\\t#ifdef ENVMAP_TYPE_CUBE\\n\\t\\t\\tvec3 queryVec = vec3( flipEnvMap * worldNormal.x, worldNormal.yz );\\n\\t\\t\\t#ifdef TEXTURE_LOD_EXT\\n\\t\\t\\t\\tvec4 envMapColor = textureCubeLodEXT( envMap, queryVec, float( maxMIPLevel ) );\\n\\t\\t\\t#else\\n\\t\\t\\t\\tvec4 envMapColor = textureCube( envMap, queryVec, float( maxMIPLevel ) );\\n\\t\\t\\t#endif\\n\\t\\t\\tenvMapColor.rgb = envMapTexelToLinear( envMapColor ).rgb;\\n\\t\\t#elif defined( ENVMAP_TYPE_CUBE_UV )\\n\\t\\t\\tvec3 queryVec = vec3( flipEnvMap * worldNormal.x, worldNormal.yz );\\n\\t\\t\\tvec4 envMapColor = textureCubeUV( envMap, queryVec, 1.0 );\\n\\t\\t#else\\n\\t\\t\\tvec4 envMapColor = vec4( 0.0 );\\n\\t\\t#endif\\n\\t\\treturn PI * envMapColor.rgb * envMapIntensity;\\n\\t}\\n\\tfloat getSpecularMIPLevel( const in float roughness, const in int maxMIPLevel ) {\\n\\t\\tfloat maxMIPLevelScalar = float( maxMIPLevel );\\n\\t\\tfloat sigma = PI * roughness * roughness / ( 1.0 + roughness );\\n\\t\\tfloat desiredMIPLevel = maxMIPLevelScalar + log2( sigma );\\n\\t\\treturn clamp( desiredMIPLevel, 0.0, maxMIPLevelScalar );\\n\\t}\\n\\tvec3 getLightProbeIndirectRadiance( const in vec3 viewDir, const in vec3 normal, const in float roughness, const in int maxMIPLevel ) {\\n\\t\\t#ifdef ENVMAP_MODE_REFLECTION\\n\\t\\t vec3 reflectVec = reflect( -viewDir, normal );\\n\\t\\t reflectVec = normalize( mix( reflectVec, normal, roughness * roughness) );\\n\\t\\t#else\\n\\t\\t vec3 reflectVec = refract( -viewDir, normal, refractionRatio );\\n\\t\\t#endif\\n\\t\\treflectVec = inverseTransformDirection( reflectVec, viewMatrix );\\n\\t\\tfloat specularMIPLevel = getSpecularMIPLevel( roughness, maxMIPLevel );\\n\\t\\t#ifdef ENVMAP_TYPE_CUBE\\n\\t\\t\\tvec3 queryReflectVec = vec3( flipEnvMap * reflectVec.x, reflectVec.yz );\\n\\t\\t\\t#ifdef TEXTURE_LOD_EXT\\n\\t\\t\\t\\tvec4 envMapColor = textureCubeLodEXT( envMap, queryReflectVec, specularMIPLevel );\\n\\t\\t\\t#else\\n\\t\\t\\t\\tvec4 envMapColor = textureCube( envMap, queryReflectVec, specularMIPLevel );\\n\\t\\t\\t#endif\\n\\t\\t\\tenvMapColor.rgb = envMapTexelToLinear( envMapColor ).rgb;\\n\\t\\t#elif defined( ENVMAP_TYPE_CUBE_UV )\\n\\t\\t\\tvec3 queryReflectVec = vec3( flipEnvMap * reflectVec.x, reflectVec.yz );\\n\\t\\t\\tvec4 envMapColor = textureCubeUV( envMap, queryReflectVec, roughness );\\n\\t\\t#elif defined( ENVMAP_TYPE_EQUIREC )\\n\\t\\t\\tvec2 sampleUV;\\n\\t\\t\\tsampleUV.y = asin( clamp( reflectVec.y, - 1.0, 1.0 ) ) * RECIPROCAL_PI + 0.5;\\n\\t\\t\\tsampleUV.x = atan( reflectVec.z, reflectVec.x ) * RECIPROCAL_PI2 + 0.5;\\n\\t\\t\\t#ifdef TEXTURE_LOD_EXT\\n\\t\\t\\t\\tvec4 envMapColor = texture2DLodEXT( envMap, sampleUV, specularMIPLevel );\\n\\t\\t\\t#else\\n\\t\\t\\t\\tvec4 envMapColor = texture2D( envMap, sampleUV, specularMIPLevel );\\n\\t\\t\\t#endif\\n\\t\\t\\tenvMapColor.rgb = envMapTexelToLinear( envMapColor ).rgb;\\n\\t\\t#elif defined( ENVMAP_TYPE_SPHERE )\\n\\t\\t\\tvec3 reflectView = normalize( ( viewMatrix * vec4( reflectVec, 0.0 ) ).xyz + vec3( 0.0,0.0,1.0 ) );\\n\\t\\t\\t#ifdef TEXTURE_LOD_EXT\\n\\t\\t\\t\\tvec4 envMapColor = texture2DLodEXT( envMap, reflectView.xy * 0.5 + 0.5, specularMIPLevel );\\n\\t\\t\\t#else\\n\\t\\t\\t\\tvec4 envMapColor = texture2D( envMap, reflectView.xy * 0.5 + 0.5, specularMIPLevel );\\n\\t\\t\\t#endif\\n\\t\\t\\tenvMapColor.rgb = envMapTexelToLinear( envMapColor ).rgb;\\n\\t\\t#endif\\n\\t\\treturn envMapColor.rgb * envMapIntensity;\\n\\t}\\n#endif",envmap_vertex:"#ifdef USE_ENVMAP\\n\\t#ifdef ENV_WORLDPOS\\n\\t\\tvWorldPosition = worldPosition.xyz;\\n\\t#else\\n\\t\\tvec3 cameraToVertex;\\n\\t\\tif ( isOrthographic ) { \\n\\t\\t\\tcameraToVertex = normalize( vec3( - viewMatrix[ 0 ][ 2 ], - viewMatrix[ 1 ][ 2 ], - viewMatrix[ 2 ][ 2 ] ) );\\n\\t\\t} else {\\n\\t\\t\\tcameraToVertex = normalize( worldPosition.xyz - cameraPosition );\\n\\t\\t}\\n\\t\\tvec3 worldNormal = inverseTransformDirection( transformedNormal, viewMatrix );\\n\\t\\t#ifdef ENVMAP_MODE_REFLECTION\\n\\t\\t\\tvReflect = reflect( cameraToVertex, worldNormal );\\n\\t\\t#else\\n\\t\\t\\tvReflect = refract( cameraToVertex, worldNormal, refractionRatio );\\n\\t\\t#endif\\n\\t#endif\\n#endif",fog_vertex:"#ifdef USE_FOG\\n\\tfogDepth = -mvPosition.z;\\n#endif",fog_pars_vertex:"#ifdef USE_FOG\\n\\tvarying float fogDepth;\\n#endif",fog_fragment:"#ifdef USE_FOG\\n\\t#ifdef FOG_EXP2\\n\\t\\tfloat fogFactor = 1.0 - exp( - fogDensity * fogDensity * fogDepth * fogDepth );\\n\\t#else\\n\\t\\tfloat fogFactor = smoothstep( fogNear, fogFar, fogDepth );\\n\\t#endif\\n\\tgl_FragColor.rgb = mix( gl_FragColor.rgb, fogColor, fogFactor );\\n#endif",fog_pars_fragment:"#ifdef USE_FOG\\n\\tuniform vec3 fogColor;\\n\\tvarying float fogDepth;\\n\\t#ifdef FOG_EXP2\\n\\t\\tuniform float fogDensity;\\n\\t#else\\n\\t\\tuniform float fogNear;\\n\\t\\tuniform float fogFar;\\n\\t#endif\\n#endif",gradientmap_pars_fragment:"#ifdef TOON\\n\\tuniform sampler2D gradientMap;\\n\\tvec3 getGradientIrradiance( vec3 normal, vec3 lightDirection ) {\\n\\t\\tfloat dotNL = dot( normal, lightDirection );\\n\\t\\tvec2 coord = vec2( dotNL * 0.5 + 0.5, 0.0 );\\n\\t\\t#ifdef USE_GRADIENTMAP\\n\\t\\t\\treturn texture2D( gradientMap, coord ).rgb;\\n\\t\\t#else\\n\\t\\t\\treturn ( coord.x < 0.7 ) ? vec3( 0.7 ) : vec3( 1.0 );\\n\\t\\t#endif\\n\\t}\\n#endif",lightmap_fragment:"#ifdef USE_LIGHTMAP\\n\\treflectedLight.indirectDiffuse += PI * texture2D( lightMap, vUv2 ).xyz * lightMapIntensity;\\n#endif",lightmap_pars_fragment:"#ifdef USE_LIGHTMAP\\n\\tuniform sampler2D lightMap;\\n\\tuniform float lightMapIntensity;\\n#endif",lights_lambert_vertex:"vec3 diffuse = vec3( 1.0 );\\nGeometricContext geometry;\\ngeometry.position = mvPosition.xyz;\\ngeometry.normal = normalize( transformedNormal );\\ngeometry.viewDir = ( isOrthographic ) ? vec3( 0, 0, 1 ) : normalize( -mvPosition.xyz );\\nGeometricContext backGeometry;\\nbackGeometry.position = geometry.position;\\nbackGeometry.normal = -geometry.normal;\\nbackGeometry.viewDir = geometry.viewDir;\\nvLightFront = vec3( 0.0 );\\nvIndirectFront = vec3( 0.0 );\\n#ifdef DOUBLE_SIDED\\n\\tvLightBack = vec3( 0.0 );\\n\\tvIndirectBack = vec3( 0.0 );\\n#endif\\nIncidentLight directLight;\\nfloat dotNL;\\nvec3 directLightColor_Diffuse;\\n#if NUM_POINT_LIGHTS > 0\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_POINT_LIGHTS; i ++ ) {\\n\\t\\tgetPointDirectLightIrradiance( pointLights[ i ], geometry, directLight );\\n\\t\\tdotNL = dot( geometry.normal, directLight.direction );\\n\\t\\tdirectLightColor_Diffuse = PI * directLight.color;\\n\\t\\tvLightFront += saturate( dotNL ) * directLightColor_Diffuse;\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\tvLightBack += saturate( -dotNL ) * directLightColor_Diffuse;\\n\\t\\t#endif\\n\\t}\\n#endif\\n#if NUM_SPOT_LIGHTS > 0\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_SPOT_LIGHTS; i ++ ) {\\n\\t\\tgetSpotDirectLightIrradiance( spotLights[ i ], geometry, directLight );\\n\\t\\tdotNL = dot( geometry.normal, directLight.direction );\\n\\t\\tdirectLightColor_Diffuse = PI * directLight.color;\\n\\t\\tvLightFront += saturate( dotNL ) * directLightColor_Diffuse;\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\tvLightBack += saturate( -dotNL ) * directLightColor_Diffuse;\\n\\t\\t#endif\\n\\t}\\n#endif\\n#if NUM_DIR_LIGHTS > 0\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_DIR_LIGHTS; i ++ ) {\\n\\t\\tgetDirectionalDirectLightIrradiance( directionalLights[ i ], geometry, directLight );\\n\\t\\tdotNL = dot( geometry.normal, directLight.direction );\\n\\t\\tdirectLightColor_Diffuse = PI * directLight.color;\\n\\t\\tvLightFront += saturate( dotNL ) * directLightColor_Diffuse;\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\tvLightBack += saturate( -dotNL ) * directLightColor_Diffuse;\\n\\t\\t#endif\\n\\t}\\n#endif\\n#if NUM_HEMI_LIGHTS > 0\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_HEMI_LIGHTS; i ++ ) {\\n\\t\\tvIndirectFront += getHemisphereLightIrradiance( hemisphereLights[ i ], geometry );\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\tvIndirectBack += getHemisphereLightIrradiance( hemisphereLights[ i ], backGeometry );\\n\\t\\t#endif\\n\\t}\\n#endif",lights_pars_begin:"uniform bool receiveShadow;\\nuniform vec3 ambientLightColor;\\nuniform vec3 lightProbe[ 9 ];\\nvec3 shGetIrradianceAt( in vec3 normal, in vec3 shCoefficients[ 9 ] ) {\\n\\tfloat x = normal.x, y = normal.y, z = normal.z;\\n\\tvec3 result = shCoefficients[ 0 ] * 0.886227;\\n\\tresult += shCoefficients[ 1 ] * 2.0 * 0.511664 * y;\\n\\tresult += shCoefficients[ 2 ] * 2.0 * 0.511664 * z;\\n\\tresult += shCoefficients[ 3 ] * 2.0 * 0.511664 * x;\\n\\tresult += shCoefficients[ 4 ] * 2.0 * 0.429043 * x * y;\\n\\tresult += shCoefficients[ 5 ] * 2.0 * 0.429043 * y * z;\\n\\tresult += shCoefficients[ 6 ] * ( 0.743125 * z * z - 0.247708 );\\n\\tresult += shCoefficients[ 7 ] * 2.0 * 0.429043 * x * z;\\n\\tresult += shCoefficients[ 8 ] * 0.429043 * ( x * x - y * y );\\n\\treturn result;\\n}\\nvec3 getLightProbeIrradiance( const in vec3 lightProbe[ 9 ], const in GeometricContext geometry ) {\\n\\tvec3 worldNormal = inverseTransformDirection( geometry.normal, viewMatrix );\\n\\tvec3 irradiance = shGetIrradianceAt( worldNormal, lightProbe );\\n\\treturn irradiance;\\n}\\nvec3 getAmbientLightIrradiance( const in vec3 ambientLightColor ) {\\n\\tvec3 irradiance = ambientLightColor;\\n\\t#ifndef PHYSICALLY_CORRECT_LIGHTS\\n\\t\\tirradiance *= PI;\\n\\t#endif\\n\\treturn irradiance;\\n}\\n#if NUM_DIR_LIGHTS > 0\\n\\tstruct DirectionalLight {\\n\\t\\tvec3 direction;\\n\\t\\tvec3 color;\\n\\t\\tint shadow;\\n\\t\\tfloat shadowBias;\\n\\t\\tfloat shadowRadius;\\n\\t\\tvec2 shadowMapSize;\\n\\t};\\n\\tuniform DirectionalLight directionalLights[ NUM_DIR_LIGHTS ];\\n\\tvoid getDirectionalDirectLightIrradiance( const in DirectionalLight directionalLight, const in GeometricContext geometry, out IncidentLight directLight ) {\\n\\t\\tdirectLight.color = directionalLight.color;\\n\\t\\tdirectLight.direction = directionalLight.direction;\\n\\t\\tdirectLight.visible = true;\\n\\t}\\n#endif\\n#if NUM_POINT_LIGHTS > 0\\n\\tstruct PointLight {\\n\\t\\tvec3 position;\\n\\t\\tvec3 color;\\n\\t\\tfloat distance;\\n\\t\\tfloat decay;\\n\\t\\tint shadow;\\n\\t\\tfloat shadowBias;\\n\\t\\tfloat shadowRadius;\\n\\t\\tvec2 shadowMapSize;\\n\\t\\tfloat shadowCameraNear;\\n\\t\\tfloat shadowCameraFar;\\n\\t};\\n\\tuniform PointLight pointLights[ NUM_POINT_LIGHTS ];\\n\\tvoid getPointDirectLightIrradiance( const in PointLight pointLight, const in GeometricContext geometry, out IncidentLight directLight ) {\\n\\t\\tvec3 lVector = pointLight.position - geometry.position;\\n\\t\\tdirectLight.direction = normalize( lVector );\\n\\t\\tfloat lightDistance = length( lVector );\\n\\t\\tdirectLight.color = pointLight.color;\\n\\t\\tdirectLight.color *= punctualLightIntensityToIrradianceFactor( lightDistance, pointLight.distance, pointLight.decay );\\n\\t\\tdirectLight.visible = ( directLight.color != vec3( 0.0 ) );\\n\\t}\\n#endif\\n#if NUM_SPOT_LIGHTS > 0\\n\\tstruct SpotLight {\\n\\t\\tvec3 position;\\n\\t\\tvec3 direction;\\n\\t\\tvec3 color;\\n\\t\\tfloat distance;\\n\\t\\tfloat decay;\\n\\t\\tfloat coneCos;\\n\\t\\tfloat penumbraCos;\\n\\t\\tint shadow;\\n\\t\\tfloat shadowBias;\\n\\t\\tfloat shadowRadius;\\n\\t\\tvec2 shadowMapSize;\\n\\t};\\n\\tuniform SpotLight spotLights[ NUM_SPOT_LIGHTS ];\\n\\tvoid getSpotDirectLightIrradiance( const in SpotLight spotLight, const in GeometricContext geometry, out IncidentLight directLight ) {\\n\\t\\tvec3 lVector = spotLight.position - geometry.position;\\n\\t\\tdirectLight.direction = normalize( lVector );\\n\\t\\tfloat lightDistance = length( lVector );\\n\\t\\tfloat angleCos = dot( directLight.direction, spotLight.direction );\\n\\t\\tif ( angleCos > spotLight.coneCos ) {\\n\\t\\t\\tfloat spotEffect = smoothstep( spotLight.coneCos, spotLight.penumbraCos, angleCos );\\n\\t\\t\\tdirectLight.color = spotLight.color;\\n\\t\\t\\tdirectLight.color *= spotEffect * punctualLightIntensityToIrradianceFactor( lightDistance, spotLight.distance, spotLight.decay );\\n\\t\\t\\tdirectLight.visible = true;\\n\\t\\t} else {\\n\\t\\t\\tdirectLight.color = vec3( 0.0 );\\n\\t\\t\\tdirectLight.visible = false;\\n\\t\\t}\\n\\t}\\n#endif\\n#if NUM_RECT_AREA_LIGHTS > 0\\n\\tstruct RectAreaLight {\\n\\t\\tvec3 color;\\n\\t\\tvec3 position;\\n\\t\\tvec3 halfWidth;\\n\\t\\tvec3 halfHeight;\\n\\t};\\n\\tuniform sampler2D ltc_1;\\tuniform sampler2D ltc_2;\\n\\tuniform RectAreaLight rectAreaLights[ NUM_RECT_AREA_LIGHTS ];\\n#endif\\n#if NUM_HEMI_LIGHTS > 0\\n\\tstruct HemisphereLight {\\n\\t\\tvec3 direction;\\n\\t\\tvec3 skyColor;\\n\\t\\tvec3 groundColor;\\n\\t};\\n\\tuniform HemisphereLight hemisphereLights[ NUM_HEMI_LIGHTS ];\\n\\tvec3 getHemisphereLightIrradiance( const in HemisphereLight hemiLight, const in GeometricContext geometry ) {\\n\\t\\tfloat dotNL = dot( geometry.normal, hemiLight.direction );\\n\\t\\tfloat hemiDiffuseWeight = 0.5 * dotNL + 0.5;\\n\\t\\tvec3 irradiance = mix( hemiLight.groundColor, hemiLight.skyColor, hemiDiffuseWeight );\\n\\t\\t#ifndef PHYSICALLY_CORRECT_LIGHTS\\n\\t\\t\\tirradiance *= PI;\\n\\t\\t#endif\\n\\t\\treturn irradiance;\\n\\t}\\n#endif",lights_phong_fragment:"BlinnPhongMaterial material;\\nmaterial.diffuseColor = diffuseColor.rgb;\\nmaterial.specularColor = specular;\\nmaterial.specularShininess = shininess;\\nmaterial.specularStrength = specularStrength;",lights_phong_pars_fragment:"varying vec3 vViewPosition;\\n#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n#endif\\nstruct BlinnPhongMaterial {\\n\\tvec3\\tdiffuseColor;\\n\\tvec3\\tspecularColor;\\n\\tfloat\\tspecularShininess;\\n\\tfloat\\tspecularStrength;\\n};\\nvoid RE_Direct_BlinnPhong( const in IncidentLight directLight, const in GeometricContext geometry, const in BlinnPhongMaterial material, inout ReflectedLight reflectedLight ) {\\n\\t#ifdef TOON\\n\\t\\tvec3 irradiance = getGradientIrradiance( geometry.normal, directLight.direction ) * directLight.color;\\n\\t#else\\n\\t\\tfloat dotNL = saturate( dot( geometry.normal, directLight.direction ) );\\n\\t\\tvec3 irradiance = dotNL * directLight.color;\\n\\t#endif\\n\\t#ifndef PHYSICALLY_CORRECT_LIGHTS\\n\\t\\tirradiance *= PI;\\n\\t#endif\\n\\treflectedLight.directDiffuse += irradiance * BRDF_Diffuse_Lambert( material.diffuseColor );\\n\\treflectedLight.directSpecular += irradiance * BRDF_Specular_BlinnPhong( directLight, geometry, material.specularColor, material.specularShininess ) * material.specularStrength;\\n}\\nvoid RE_IndirectDiffuse_BlinnPhong( const in vec3 irradiance, const in GeometricContext geometry, const in BlinnPhongMaterial material, inout ReflectedLight reflectedLight ) {\\n\\treflectedLight.indirectDiffuse += irradiance * BRDF_Diffuse_Lambert( material.diffuseColor );\\n}\\n#define RE_Direct\\t\\t\\t\\tRE_Direct_BlinnPhong\\n#define RE_IndirectDiffuse\\t\\tRE_IndirectDiffuse_BlinnPhong\\n#define Material_LightProbeLOD( material )\\t(0)",lights_physical_fragment:"PhysicalMaterial material;\\nmaterial.diffuseColor = diffuseColor.rgb * ( 1.0 - metalnessFactor );\\nmaterial.specularRoughness = clamp( roughnessFactor, 0.04, 1.0 );\\n#ifdef REFLECTIVITY\\n\\tmaterial.specularColor = mix( vec3( MAXIMUM_SPECULAR_COEFFICIENT * pow2( reflectivity ) ), diffuseColor.rgb, metalnessFactor );\\n#else\\n\\tmaterial.specularColor = mix( vec3( DEFAULT_SPECULAR_COEFFICIENT ), diffuseColor.rgb, metalnessFactor );\\n#endif\\n#ifdef CLEARCOAT\\n\\tmaterial.clearcoat = saturate( clearcoat );\\tmaterial.clearcoatRoughness = clamp( clearcoatRoughness, 0.04, 1.0 );\\n#endif\\n#ifdef USE_SHEEN\\n\\tmaterial.sheenColor = sheen;\\n#endif",lights_physical_pars_fragment:"struct PhysicalMaterial {\\n\\tvec3\\tdiffuseColor;\\n\\tfloat\\tspecularRoughness;\\n\\tvec3\\tspecularColor;\\n#ifdef CLEARCOAT\\n\\tfloat clearcoat;\\n\\tfloat clearcoatRoughness;\\n#endif\\n#ifdef USE_SHEEN\\n\\tvec3 sheenColor;\\n#endif\\n};\\n#define MAXIMUM_SPECULAR_COEFFICIENT 0.16\\n#define DEFAULT_SPECULAR_COEFFICIENT 0.04\\nfloat clearcoatDHRApprox( const in float roughness, const in float dotNL ) {\\n\\treturn DEFAULT_SPECULAR_COEFFICIENT + ( 1.0 - DEFAULT_SPECULAR_COEFFICIENT ) * ( pow( 1.0 - dotNL, 5.0 ) * pow( 1.0 - roughness, 2.0 ) );\\n}\\n#if NUM_RECT_AREA_LIGHTS > 0\\n\\tvoid RE_Direct_RectArea_Physical( const in RectAreaLight rectAreaLight, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {\\n\\t\\tvec3 normal = geometry.normal;\\n\\t\\tvec3 viewDir = geometry.viewDir;\\n\\t\\tvec3 position = geometry.position;\\n\\t\\tvec3 lightPos = rectAreaLight.position;\\n\\t\\tvec3 halfWidth = rectAreaLight.halfWidth;\\n\\t\\tvec3 halfHeight = rectAreaLight.halfHeight;\\n\\t\\tvec3 lightColor = rectAreaLight.color;\\n\\t\\tfloat roughness = material.specularRoughness;\\n\\t\\tvec3 rectCoords[ 4 ];\\n\\t\\trectCoords[ 0 ] = lightPos + halfWidth - halfHeight;\\t\\trectCoords[ 1 ] = lightPos - halfWidth - halfHeight;\\n\\t\\trectCoords[ 2 ] = lightPos - halfWidth + halfHeight;\\n\\t\\trectCoords[ 3 ] = lightPos + halfWidth + halfHeight;\\n\\t\\tvec2 uv = LTC_Uv( normal, viewDir, roughness );\\n\\t\\tvec4 t1 = texture2D( ltc_1, uv );\\n\\t\\tvec4 t2 = texture2D( ltc_2, uv );\\n\\t\\tmat3 mInv = mat3(\\n\\t\\t\\tvec3( t1.x, 0, t1.y ),\\n\\t\\t\\tvec3( 0, 1, 0 ),\\n\\t\\t\\tvec3( t1.z, 0, t1.w )\\n\\t\\t);\\n\\t\\tvec3 fresnel = ( material.specularColor * t2.x + ( vec3( 1.0 ) - material.specularColor ) * t2.y );\\n\\t\\treflectedLight.directSpecular += lightColor * fresnel * LTC_Evaluate( normal, viewDir, position, mInv, rectCoords );\\n\\t\\treflectedLight.directDiffuse += lightColor * material.diffuseColor * LTC_Evaluate( normal, viewDir, position, mat3( 1.0 ), rectCoords );\\n\\t}\\n#endif\\nvoid RE_Direct_Physical( const in IncidentLight directLight, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {\\n\\tfloat dotNL = saturate( dot( geometry.normal, directLight.direction ) );\\n\\tvec3 irradiance = dotNL * directLight.color;\\n\\t#ifndef PHYSICALLY_CORRECT_LIGHTS\\n\\t\\tirradiance *= PI;\\n\\t#endif\\n\\t#ifdef CLEARCOAT\\n\\t\\tfloat ccDotNL = saturate( dot( geometry.clearcoatNormal, directLight.direction ) );\\n\\t\\tvec3 ccIrradiance = ccDotNL * directLight.color;\\n\\t\\t#ifndef PHYSICALLY_CORRECT_LIGHTS\\n\\t\\t\\tccIrradiance *= PI;\\n\\t\\t#endif\\n\\t\\tfloat clearcoatDHR = material.clearcoat * clearcoatDHRApprox( material.clearcoatRoughness, ccDotNL );\\n\\t\\treflectedLight.directSpecular += ccIrradiance * material.clearcoat * BRDF_Specular_GGX( directLight, geometry.viewDir, geometry.clearcoatNormal, vec3( DEFAULT_SPECULAR_COEFFICIENT ), material.clearcoatRoughness );\\n\\t#else\\n\\t\\tfloat clearcoatDHR = 0.0;\\n\\t#endif\\n\\t#ifdef USE_SHEEN\\n\\t\\treflectedLight.directSpecular += ( 1.0 - clearcoatDHR ) * irradiance * BRDF_Specular_Sheen(\\n\\t\\t\\tmaterial.specularRoughness,\\n\\t\\t\\tdirectLight.direction,\\n\\t\\t\\tgeometry,\\n\\t\\t\\tmaterial.sheenColor\\n\\t\\t);\\n\\t#else\\n\\t\\treflectedLight.directSpecular += ( 1.0 - clearcoatDHR ) * irradiance * BRDF_Specular_GGX( directLight, geometry.viewDir, geometry.normal, material.specularColor, material.specularRoughness);\\n\\t#endif\\n\\treflectedLight.directDiffuse += ( 1.0 - clearcoatDHR ) * irradiance * BRDF_Diffuse_Lambert( material.diffuseColor );\\n}\\nvoid RE_IndirectDiffuse_Physical( const in vec3 irradiance, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {\\n\\treflectedLight.indirectDiffuse += irradiance * BRDF_Diffuse_Lambert( material.diffuseColor );\\n}\\nvoid RE_IndirectSpecular_Physical( const in vec3 radiance, const in vec3 irradiance, const in vec3 clearcoatRadiance, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight) {\\n\\t#ifdef CLEARCOAT\\n\\t\\tfloat ccDotNV = saturate( dot( geometry.clearcoatNormal, geometry.viewDir ) );\\n\\t\\treflectedLight.indirectSpecular += clearcoatRadiance * material.clearcoat * BRDF_Specular_GGX_Environment( geometry.viewDir, geometry.clearcoatNormal, vec3( DEFAULT_SPECULAR_COEFFICIENT ), material.clearcoatRoughness );\\n\\t\\tfloat ccDotNL = ccDotNV;\\n\\t\\tfloat clearcoatDHR = material.clearcoat * clearcoatDHRApprox( material.clearcoatRoughness, ccDotNL );\\n\\t#else\\n\\t\\tfloat clearcoatDHR = 0.0;\\n\\t#endif\\n\\tfloat clearcoatInv = 1.0 - clearcoatDHR;\\n\\tvec3 singleScattering = vec3( 0.0 );\\n\\tvec3 multiScattering = vec3( 0.0 );\\n\\tvec3 cosineWeightedIrradiance = irradiance * RECIPROCAL_PI;\\n\\tBRDF_Specular_Multiscattering_Environment( geometry, material.specularColor, material.specularRoughness, singleScattering, multiScattering );\\n\\tvec3 diffuse = material.diffuseColor * ( 1.0 - ( singleScattering + multiScattering ) );\\n\\treflectedLight.indirectSpecular += clearcoatInv * radiance * singleScattering;\\n\\treflectedLight.indirectSpecular += multiScattering * cosineWeightedIrradiance;\\n\\treflectedLight.indirectDiffuse += diffuse * cosineWeightedIrradiance;\\n}\\n#define RE_Direct\\t\\t\\t\\tRE_Direct_Physical\\n#define RE_Direct_RectArea\\t\\tRE_Direct_RectArea_Physical\\n#define RE_IndirectDiffuse\\t\\tRE_IndirectDiffuse_Physical\\n#define RE_IndirectSpecular\\t\\tRE_IndirectSpecular_Physical\\nfloat computeSpecularOcclusion( const in float dotNV, const in float ambientOcclusion, const in float roughness ) {\\n\\treturn saturate( pow( dotNV + ambientOcclusion, exp2( - 16.0 * roughness - 1.0 ) ) - 1.0 + ambientOcclusion );\\n}",lights_fragment_begin:"\\nGeometricContext geometry;\\ngeometry.position = - vViewPosition;\\ngeometry.normal = normal;\\ngeometry.viewDir = ( isOrthographic ) ? vec3( 0, 0, 1 ) : normalize( vViewPosition );\\n#ifdef CLEARCOAT\\n\\tgeometry.clearcoatNormal = clearcoatNormal;\\n#endif\\nIncidentLight directLight;\\n#if ( NUM_POINT_LIGHTS > 0 ) && defined( RE_Direct )\\n\\tPointLight pointLight;\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_POINT_LIGHTS; i ++ ) {\\n\\t\\tpointLight = pointLights[ i ];\\n\\t\\tgetPointDirectLightIrradiance( pointLight, geometry, directLight );\\n\\t\\t#if defined( USE_SHADOWMAP ) && ( UNROLLED_LOOP_INDEX < NUM_POINT_LIGHT_SHADOWS )\\n\\t\\tdirectLight.color *= all( bvec3( pointLight.shadow, directLight.visible, receiveShadow ) ) ? getPointShadow( pointShadowMap[ i ], pointLight.shadowMapSize, pointLight.shadowBias, pointLight.shadowRadius, vPointShadowCoord[ i ], pointLight.shadowCameraNear, pointLight.shadowCameraFar ) : 1.0;\\n\\t\\t#endif\\n\\t\\tRE_Direct( directLight, geometry, material, reflectedLight );\\n\\t}\\n#endif\\n#if ( NUM_SPOT_LIGHTS > 0 ) && defined( RE_Direct )\\n\\tSpotLight spotLight;\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_SPOT_LIGHTS; i ++ ) {\\n\\t\\tspotLight = spotLights[ i ];\\n\\t\\tgetSpotDirectLightIrradiance( spotLight, geometry, directLight );\\n\\t\\t#if defined( USE_SHADOWMAP ) && ( UNROLLED_LOOP_INDEX < NUM_SPOT_LIGHT_SHADOWS )\\n\\t\\tdirectLight.color *= all( bvec3( spotLight.shadow, directLight.visible, receiveShadow ) ) ? getShadow( spotShadowMap[ i ], spotLight.shadowMapSize, spotLight.shadowBias, spotLight.shadowRadius, vSpotShadowCoord[ i ] ) : 1.0;\\n\\t\\t#endif\\n\\t\\tRE_Direct( directLight, geometry, material, reflectedLight );\\n\\t}\\n#endif\\n#if ( NUM_DIR_LIGHTS > 0 ) && defined( RE_Direct )\\n\\tDirectionalLight directionalLight;\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_DIR_LIGHTS; i ++ ) {\\n\\t\\tdirectionalLight = directionalLights[ i ];\\n\\t\\tgetDirectionalDirectLightIrradiance( directionalLight, geometry, directLight );\\n\\t\\t#if defined( USE_SHADOWMAP ) && ( UNROLLED_LOOP_INDEX < NUM_DIR_LIGHT_SHADOWS )\\n\\t\\tdirectLight.color *= all( bvec3( directionalLight.shadow, directLight.visible, receiveShadow ) ) ? getShadow( directionalShadowMap[ i ], directionalLight.shadowMapSize, directionalLight.shadowBias, directionalLight.shadowRadius, vDirectionalShadowCoord[ i ] ) : 1.0;\\n\\t\\t#endif\\n\\t\\tRE_Direct( directLight, geometry, material, reflectedLight );\\n\\t}\\n#endif\\n#if ( NUM_RECT_AREA_LIGHTS > 0 ) && defined( RE_Direct_RectArea )\\n\\tRectAreaLight rectAreaLight;\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_RECT_AREA_LIGHTS; i ++ ) {\\n\\t\\trectAreaLight = rectAreaLights[ i ];\\n\\t\\tRE_Direct_RectArea( rectAreaLight, geometry, material, reflectedLight );\\n\\t}\\n#endif\\n#if defined( RE_IndirectDiffuse )\\n\\tvec3 iblIrradiance = vec3( 0.0 );\\n\\tvec3 irradiance = getAmbientLightIrradiance( ambientLightColor );\\n\\tirradiance += getLightProbeIrradiance( lightProbe, geometry );\\n\\t#if ( NUM_HEMI_LIGHTS > 0 )\\n\\t\\t#pragma unroll_loop\\n\\t\\tfor ( int i = 0; i < NUM_HEMI_LIGHTS; i ++ ) {\\n\\t\\t\\tirradiance += getHemisphereLightIrradiance( hemisphereLights[ i ], geometry );\\n\\t\\t}\\n\\t#endif\\n#endif\\n#if defined( RE_IndirectSpecular )\\n\\tvec3 radiance = vec3( 0.0 );\\n\\tvec3 clearcoatRadiance = vec3( 0.0 );\\n#endif",lights_fragment_maps:"#if defined( RE_IndirectDiffuse )\\n\\t#ifdef USE_LIGHTMAP\\n\\t\\tvec3 lightMapIrradiance = texture2D( lightMap, vUv2 ).xyz * lightMapIntensity;\\n\\t\\t#ifndef PHYSICALLY_CORRECT_LIGHTS\\n\\t\\t\\tlightMapIrradiance *= PI;\\n\\t\\t#endif\\n\\t\\tirradiance += lightMapIrradiance;\\n\\t#endif\\n\\t#if defined( USE_ENVMAP ) && defined( STANDARD ) && defined( ENVMAP_TYPE_CUBE_UV )\\n\\t\\tiblIrradiance += getLightProbeIndirectIrradiance( geometry, maxMipLevel );\\n\\t#endif\\n#endif\\n#if defined( USE_ENVMAP ) && defined( RE_IndirectSpecular )\\n\\tradiance += getLightProbeIndirectRadiance( geometry.viewDir, geometry.normal, material.specularRoughness, maxMipLevel );\\n\\t#ifdef CLEARCOAT\\n\\t\\tclearcoatRadiance += getLightProbeIndirectRadiance( geometry.viewDir, geometry.clearcoatNormal, material.clearcoatRoughness, maxMipLevel );\\n\\t#endif\\n#endif",lights_fragment_end:"#if defined( RE_IndirectDiffuse )\\n\\tRE_IndirectDiffuse( irradiance, geometry, material, reflectedLight );\\n#endif\\n#if defined( RE_IndirectSpecular )\\n\\tRE_IndirectSpecular( radiance, iblIrradiance, clearcoatRadiance, geometry, material, reflectedLight );\\n#endif",logdepthbuf_fragment:"#if defined( USE_LOGDEPTHBUF ) && defined( USE_LOGDEPTHBUF_EXT )\\n\\tgl_FragDepthEXT = vIsPerspective == 0.0 ? gl_FragCoord.z : log2( vFragDepth ) * logDepthBufFC * 0.5;\\n#endif",logdepthbuf_pars_fragment:"#if defined( USE_LOGDEPTHBUF ) && defined( USE_LOGDEPTHBUF_EXT )\\n\\tuniform float logDepthBufFC;\\n\\tvarying float vFragDepth;\\n\\tvarying float vIsPerspective;\\n#endif",logdepthbuf_pars_vertex:"#ifdef USE_LOGDEPTHBUF\\n\\t#ifdef USE_LOGDEPTHBUF_EXT\\n\\t\\tvarying float vFragDepth;\\n\\t\\tvarying float vIsPerspective;\\n\\t#else\\n\\t\\tuniform float logDepthBufFC;\\n\\t#endif\\n#endif",logdepthbuf_vertex:"#ifdef USE_LOGDEPTHBUF\\n\\t#ifdef USE_LOGDEPTHBUF_EXT\\n\\t\\tvFragDepth = 1.0 + gl_Position.w;\\n\\t\\tvIsPerspective = float( isPerspectiveMatrix( projectionMatrix ) );\\n\\t#else\\n\\t\\tif ( isPerspectiveMatrix( projectionMatrix ) ) {\\n\\t\\t\\tgl_Position.z = log2( max( EPSILON, gl_Position.w + 1.0 ) ) * logDepthBufFC - 1.0;\\n\\t\\t\\tgl_Position.z *= gl_Position.w;\\n\\t\\t}\\n\\t#endif\\n#endif",map_fragment:"#ifdef USE_MAP\\n\\tvec4 texelColor = texture2D( map, vUv );\\n\\ttexelColor = mapTexelToLinear( texelColor );\\n\\tdiffuseColor *= texelColor;\\n#endif",map_pars_fragment:"#ifdef USE_MAP\\n\\tuniform sampler2D map;\\n#endif",map_particle_fragment:"#if defined( USE_MAP ) || defined( USE_ALPHAMAP )\\n\\tvec2 uv = ( uvTransform * vec3( gl_PointCoord.x, 1.0 - gl_PointCoord.y, 1 ) ).xy;\\n#endif\\n#ifdef USE_MAP\\n\\tvec4 mapTexel = texture2D( map, uv );\\n\\tdiffuseColor *= mapTexelToLinear( mapTexel );\\n#endif\\n#ifdef USE_ALPHAMAP\\n\\tdiffuseColor.a *= texture2D( alphaMap, uv ).g;\\n#endif",map_particle_pars_fragment:"#if defined( USE_MAP ) || defined( USE_ALPHAMAP )\\n\\tuniform mat3 uvTransform;\\n#endif\\n#ifdef USE_MAP\\n\\tuniform sampler2D map;\\n#endif\\n#ifdef USE_ALPHAMAP\\n\\tuniform sampler2D alphaMap;\\n#endif",metalnessmap_fragment:"float metalnessFactor = metalness;\\n#ifdef USE_METALNESSMAP\\n\\tvec4 texelMetalness = texture2D( metalnessMap, vUv );\\n\\tmetalnessFactor *= texelMetalness.b;\\n#endif",metalnessmap_pars_fragment:"#ifdef USE_METALNESSMAP\\n\\tuniform sampler2D metalnessMap;\\n#endif",morphnormal_vertex:"#ifdef USE_MORPHNORMALS\\n\\tobjectNormal += ( morphNormal0 - normal ) * morphTargetInfluences[ 0 ];\\n\\tobjectNormal += ( morphNormal1 - normal ) * morphTargetInfluences[ 1 ];\\n\\tobjectNormal += ( morphNormal2 - normal ) * morphTargetInfluences[ 2 ];\\n\\tobjectNormal += ( morphNormal3 - normal ) * morphTargetInfluences[ 3 ];\\n#endif",morphtarget_pars_vertex:"#ifdef USE_MORPHTARGETS\\n\\t#ifndef USE_MORPHNORMALS\\n\\tuniform float morphTargetInfluences[ 8 ];\\n\\t#else\\n\\tuniform float morphTargetInfluences[ 4 ];\\n\\t#endif\\n#endif",morphtarget_vertex:"#ifdef USE_MORPHTARGETS\\n\\ttransformed += ( morphTarget0 - position ) * morphTargetInfluences[ 0 ];\\n\\ttransformed += ( morphTarget1 - position ) * morphTargetInfluences[ 1 ];\\n\\ttransformed += ( morphTarget2 - position ) * morphTargetInfluences[ 2 ];\\n\\ttransformed += ( morphTarget3 - position ) * morphTargetInfluences[ 3 ];\\n\\t#ifndef USE_MORPHNORMALS\\n\\ttransformed += ( morphTarget4 - position ) * morphTargetInfluences[ 4 ];\\n\\ttransformed += ( morphTarget5 - position ) * morphTargetInfluences[ 5 ];\\n\\ttransformed += ( morphTarget6 - position ) * morphTargetInfluences[ 6 ];\\n\\ttransformed += ( morphTarget7 - position ) * morphTargetInfluences[ 7 ];\\n\\t#endif\\n#endif",normal_fragment_begin:"#ifdef FLAT_SHADED\\n\\tvec3 fdx = vec3( dFdx( vViewPosition.x ), dFdx( vViewPosition.y ), dFdx( vViewPosition.z ) );\\n\\tvec3 fdy = vec3( dFdy( vViewPosition.x ), dFdy( vViewPosition.y ), dFdy( vViewPosition.z ) );\\n\\tvec3 normal = normalize( cross( fdx, fdy ) );\\n#else\\n\\tvec3 normal = normalize( vNormal );\\n\\t#ifdef DOUBLE_SIDED\\n\\t\\tnormal = normal * ( float( gl_FrontFacing ) * 2.0 - 1.0 );\\n\\t#endif\\n\\t#ifdef USE_TANGENT\\n\\t\\tvec3 tangent = normalize( vTangent );\\n\\t\\tvec3 bitangent = normalize( vBitangent );\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\ttangent = tangent * ( float( gl_FrontFacing ) * 2.0 - 1.0 );\\n\\t\\t\\tbitangent = bitangent * ( float( gl_FrontFacing ) * 2.0 - 1.0 );\\n\\t\\t#endif\\n\\t#endif\\n#endif\\nvec3 geometryNormal = normal;",normal_fragment_maps:"#ifdef OBJECTSPACE_NORMALMAP\\n\\tnormal = texture2D( normalMap, vUv ).xyz * 2.0 - 1.0;\\n\\t#ifdef FLIP_SIDED\\n\\t\\tnormal = - normal;\\n\\t#endif\\n\\t#ifdef DOUBLE_SIDED\\n\\t\\tnormal = normal * ( float( gl_FrontFacing ) * 2.0 - 1.0 );\\n\\t#endif\\n\\tnormal = normalize( normalMatrix * normal );\\n#elif defined( TANGENTSPACE_NORMALMAP )\\n\\t#ifdef USE_TANGENT\\n\\t\\tmat3 vTBN = mat3( tangent, bitangent, normal );\\n\\t\\tvec3 mapN = texture2D( normalMap, vUv ).xyz * 2.0 - 1.0;\\n\\t\\tmapN.xy = normalScale * mapN.xy;\\n\\t\\tnormal = normalize( vTBN * mapN );\\n\\t#else\\n\\t\\tnormal = perturbNormal2Arb( -vViewPosition, normal, normalScale, normalMap );\\n\\t#endif\\n#elif defined( USE_BUMPMAP )\\n\\tnormal = perturbNormalArb( -vViewPosition, normal, dHdxy_fwd() );\\n#endif",normalmap_pars_fragment:"#ifdef USE_NORMALMAP\\n\\tuniform sampler2D normalMap;\\n\\tuniform vec2 normalScale;\\n#endif\\n#ifdef OBJECTSPACE_NORMALMAP\\n\\tuniform mat3 normalMatrix;\\n#endif\\n#if ! defined ( USE_TANGENT ) && ( defined ( TANGENTSPACE_NORMALMAP ) || defined ( USE_CLEARCOAT_NORMALMAP ) )\\n\\tvec3 perturbNormal2Arb( vec3 eye_pos, vec3 surf_norm, vec2 normalScale, in sampler2D normalMap ) {\\n\\t\\tvec3 q0 = vec3( dFdx( eye_pos.x ), dFdx( eye_pos.y ), dFdx( eye_pos.z ) );\\n\\t\\tvec3 q1 = vec3( dFdy( eye_pos.x ), dFdy( eye_pos.y ), dFdy( eye_pos.z ) );\\n\\t\\tvec2 st0 = dFdx( vUv.st );\\n\\t\\tvec2 st1 = dFdy( vUv.st );\\n\\t\\tfloat scale = sign( st1.t * st0.s - st0.t * st1.s );\\n\\t\\tvec3 S = normalize( ( q0 * st1.t - q1 * st0.t ) * scale );\\n\\t\\tvec3 T = normalize( ( - q0 * st1.s + q1 * st0.s ) * scale );\\n\\t\\tvec3 N = normalize( surf_norm );\\n\\t\\tvec3 mapN = texture2D( normalMap, vUv ).xyz * 2.0 - 1.0;\\n\\t\\tmapN.xy *= normalScale;\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\tbool frontFacing = dot( cross( S, T ), N ) > 0.0;\\n\\t\\t\\tmapN.xy *= ( float( frontFacing ) * 2.0 - 1.0 );\\n\\t\\t#else\\n\\t\\t\\tmapN.xy *= ( float( gl_FrontFacing ) * 2.0 - 1.0 );\\n\\t\\t#endif\\n\\t\\tmat3 tsn = mat3( S, T, N );\\n\\t\\treturn normalize( tsn * mapN );\\n\\t}\\n#endif",clearcoat_normal_fragment_begin:"#ifdef CLEARCOAT\\n\\tvec3 clearcoatNormal = geometryNormal;\\n#endif",clearcoat_normal_fragment_maps:"#ifdef USE_CLEARCOAT_NORMALMAP\\n\\t#ifdef USE_TANGENT\\n\\t\\tmat3 vTBN = mat3( tangent, bitangent, clearcoatNormal );\\n\\t\\tvec3 mapN = texture2D( normalMap, vUv ).xyz * 2.0 - 1.0;\\n\\t\\tmapN.xy = clearcoatNormalScale * mapN.xy;\\n\\t\\tclearcoatNormal = normalize( vTBN * mapN );\\n\\t#else\\n\\t\\tclearcoatNormal = perturbNormal2Arb( - vViewPosition, clearcoatNormal, clearcoatNormalScale, clearcoatNormalMap );\\n\\t#endif\\n#endif",clearcoat_normalmap_pars_fragment:"#ifdef USE_CLEARCOAT_NORMALMAP\\n\\tuniform sampler2D clearcoatNormalMap;\\n\\tuniform vec2 clearcoatNormalScale;\\n#endif",packing:"vec3 packNormalToRGB( const in vec3 normal ) {\\n\\treturn normalize( normal ) * 0.5 + 0.5;\\n}\\nvec3 unpackRGBToNormal( const in vec3 rgb ) {\\n\\treturn 2.0 * rgb.xyz - 1.0;\\n}\\nconst float PackUpscale = 256. / 255.;const float UnpackDownscale = 255. / 256.;\\nconst vec3 PackFactors = vec3( 256. * 256. * 256., 256. * 256., 256. );\\nconst vec4 UnpackFactors = UnpackDownscale / vec4( PackFactors, 1. );\\nconst float ShiftRight8 = 1. / 256.;\\nvec4 packDepthToRGBA( const in float v ) {\\n\\tvec4 r = vec4( fract( v * PackFactors ), v );\\n\\tr.yzw -= r.xyz * ShiftRight8;\\treturn r * PackUpscale;\\n}\\nfloat unpackRGBAToDepth( const in vec4 v ) {\\n\\treturn dot( v, UnpackFactors );\\n}\\nvec4 encodeHalfRGBA ( vec2 v ) {\\n\\tvec4 encoded = vec4( 0.0 );\\n\\tconst vec2 offset = vec2( 1.0 / 255.0, 0.0 );\\n\\tencoded.xy = vec2( v.x, fract( v.x * 255.0 ) );\\n\\tencoded.xy = encoded.xy - ( encoded.yy * offset );\\n\\tencoded.zw = vec2( v.y, fract( v.y * 255.0 ) );\\n\\tencoded.zw = encoded.zw - ( encoded.ww * offset );\\n\\treturn encoded;\\n}\\nvec2 decodeHalfRGBA( vec4 v ) {\\n\\treturn vec2( v.x + ( v.y / 255.0 ), v.z + ( v.w / 255.0 ) );\\n}\\nfloat viewZToOrthographicDepth( const in float viewZ, const in float near, const in float far ) {\\n\\treturn ( viewZ + near ) / ( near - far );\\n}\\nfloat orthographicDepthToViewZ( const in float linearClipZ, const in float near, const in float far ) {\\n\\treturn linearClipZ * ( near - far ) - near;\\n}\\nfloat viewZToPerspectiveDepth( const in float viewZ, const in float near, const in float far ) {\\n\\treturn (( near + viewZ ) * far ) / (( far - near ) * viewZ );\\n}\\nfloat perspectiveDepthToViewZ( const in float invClipZ, const in float near, const in float far ) {\\n\\treturn ( near * far ) / ( ( far - near ) * invClipZ - far );\\n}",premultiplied_alpha_fragment:"#ifdef PREMULTIPLIED_ALPHA\\n\\tgl_FragColor.rgb *= gl_FragColor.a;\\n#endif",project_vertex:"vec4 mvPosition = vec4( transformed, 1.0 );\\n#ifdef USE_INSTANCING\\n\\tmvPosition = instanceMatrix * mvPosition;\\n#endif\\nmvPosition = modelViewMatrix * mvPosition;\\ngl_Position = projectionMatrix * mvPosition;",dithering_fragment:"#ifdef DITHERING\\n\\tgl_FragColor.rgb = dithering( gl_FragColor.rgb );\\n#endif",dithering_pars_fragment:"#ifdef DITHERING\\n\\tvec3 dithering( vec3 color ) {\\n\\t\\tfloat grid_position = rand( gl_FragCoord.xy );\\n\\t\\tvec3 dither_shift_RGB = vec3( 0.25 / 255.0, -0.25 / 255.0, 0.25 / 255.0 );\\n\\t\\tdither_shift_RGB = mix( 2.0 * dither_shift_RGB, -2.0 * dither_shift_RGB, grid_position );\\n\\t\\treturn color + dither_shift_RGB;\\n\\t}\\n#endif",roughnessmap_fragment:"float roughnessFactor = roughness;\\n#ifdef USE_ROUGHNESSMAP\\n\\tvec4 texelRoughness = texture2D( roughnessMap, vUv );\\n\\troughnessFactor *= texelRoughness.g;\\n#endif",roughnessmap_pars_fragment:"#ifdef USE_ROUGHNESSMAP\\n\\tuniform sampler2D roughnessMap;\\n#endif",shadowmap_pars_fragment:"#ifdef USE_SHADOWMAP\\n\\t#if NUM_DIR_LIGHT_SHADOWS > 0\\n\\t\\tuniform sampler2D directionalShadowMap[ NUM_DIR_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vDirectionalShadowCoord[ NUM_DIR_LIGHT_SHADOWS ];\\n\\t#endif\\n\\t#if NUM_SPOT_LIGHT_SHADOWS > 0\\n\\t\\tuniform sampler2D spotShadowMap[ NUM_SPOT_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vSpotShadowCoord[ NUM_SPOT_LIGHT_SHADOWS ];\\n\\t#endif\\n\\t#if NUM_POINT_LIGHT_SHADOWS > 0\\n\\t\\tuniform sampler2D pointShadowMap[ NUM_POINT_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vPointShadowCoord[ NUM_POINT_LIGHT_SHADOWS ];\\n\\t#endif\\n\\tfloat texture2DCompare( sampler2D depths, vec2 uv, float compare ) {\\n\\t\\treturn step( compare, unpackRGBAToDepth( texture2D( depths, uv ) ) );\\n\\t}\\n\\tvec2 texture2DDistribution( sampler2D shadow, vec2 uv ) {\\n\\t\\treturn decodeHalfRGBA( texture2D( shadow, uv ) );\\n\\t}\\n\\tfloat VSMShadow (sampler2D shadow, vec2 uv, float compare ){\\n\\t\\tfloat occlusion = 1.0;\\n\\t\\tvec2 distribution = texture2DDistribution( shadow, uv );\\n\\t\\tfloat hard_shadow = step( compare , distribution.x );\\n\\t\\tif (hard_shadow != 1.0 ) {\\n\\t\\t\\tfloat distance = compare - distribution.x ;\\n\\t\\t\\tfloat variance = max( 0.00000, distribution.y * distribution.y );\\n\\t\\t\\tfloat softness_probability = variance / (variance + distance * distance );\\t\\t\\tsoftness_probability = clamp( ( softness_probability - 0.3 ) / ( 0.95 - 0.3 ), 0.0, 1.0 );\\t\\t\\tocclusion = clamp( max( hard_shadow, softness_probability ), 0.0, 1.0 );\\n\\t\\t}\\n\\t\\treturn occlusion;\\n\\t}\\n\\tfloat texture2DShadowLerp( sampler2D depths, vec2 size, vec2 uv, float compare ) {\\n\\t\\tconst vec2 offset = vec2( 0.0, 1.0 );\\n\\t\\tvec2 texelSize = vec2( 1.0 ) / size;\\n\\t\\tvec2 centroidUV = ( floor( uv * size - 0.5 ) + 0.5 ) * texelSize;\\n\\t\\tfloat lb = texture2DCompare( depths, centroidUV + texelSize * offset.xx, compare );\\n\\t\\tfloat lt = texture2DCompare( depths, centroidUV + texelSize * offset.xy, compare );\\n\\t\\tfloat rb = texture2DCompare( depths, centroidUV + texelSize * offset.yx, compare );\\n\\t\\tfloat rt = texture2DCompare( depths, centroidUV + texelSize * offset.yy, compare );\\n\\t\\tvec2 f = fract( uv * size + 0.5 );\\n\\t\\tfloat a = mix( lb, lt, f.y );\\n\\t\\tfloat b = mix( rb, rt, f.y );\\n\\t\\tfloat c = mix( a, b, f.x );\\n\\t\\treturn c;\\n\\t}\\n\\tfloat getShadow( sampler2D shadowMap, vec2 shadowMapSize, float shadowBias, float shadowRadius, vec4 shadowCoord ) {\\n\\t\\tfloat shadow = 1.0;\\n\\t\\tshadowCoord.xyz /= shadowCoord.w;\\n\\t\\tshadowCoord.z += shadowBias;\\n\\t\\tbvec4 inFrustumVec = bvec4 ( shadowCoord.x >= 0.0, shadowCoord.x <= 1.0, shadowCoord.y >= 0.0, shadowCoord.y <= 1.0 );\\n\\t\\tbool inFrustum = all( inFrustumVec );\\n\\t\\tbvec2 frustumTestVec = bvec2( inFrustum, shadowCoord.z <= 1.0 );\\n\\t\\tbool frustumTest = all( frustumTestVec );\\n\\t\\tif ( frustumTest ) {\\n\\t\\t#if defined( SHADOWMAP_TYPE_PCF )\\n\\t\\t\\tvec2 texelSize = vec2( 1.0 ) / shadowMapSize;\\n\\t\\t\\tfloat dx0 = - texelSize.x * shadowRadius;\\n\\t\\t\\tfloat dy0 = - texelSize.y * shadowRadius;\\n\\t\\t\\tfloat dx1 = + texelSize.x * shadowRadius;\\n\\t\\t\\tfloat dy1 = + texelSize.y * shadowRadius;\\n\\t\\t\\tfloat dx2 = dx0 / 2.0;\\n\\t\\t\\tfloat dy2 = dy0 / 2.0;\\n\\t\\t\\tfloat dx3 = dx1 / 2.0;\\n\\t\\t\\tfloat dy3 = dy1 / 2.0;\\n\\t\\t\\tshadow = (\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, dy0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, dy0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx2, dy2 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy2 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx3, dy2 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx2, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy, shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx3, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx2, dy3 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy3 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx3, dy3 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, dy1 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy1 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, dy1 ), shadowCoord.z )\\n\\t\\t\\t) * ( 1.0 / 17.0 );\\n\\t\\t#elif defined( SHADOWMAP_TYPE_PCF_SOFT )\\n\\t\\t\\tvec2 texelSize = vec2( 1.0 ) / shadowMapSize;\\n\\t\\t\\tfloat dx0 = - texelSize.x * shadowRadius;\\n\\t\\t\\tfloat dy0 = - texelSize.y * shadowRadius;\\n\\t\\t\\tfloat dx1 = + texelSize.x * shadowRadius;\\n\\t\\t\\tfloat dy1 = + texelSize.y * shadowRadius;\\n\\t\\t\\tshadow = (\\n\\t\\t\\t\\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx0, dy0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( 0.0, dy0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx1, dy0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx0, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy, shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx1, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx0, dy1 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( 0.0, dy1 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx1, dy1 ), shadowCoord.z )\\n\\t\\t\\t) * ( 1.0 / 9.0 );\\n\\t\\t#elif defined( SHADOWMAP_TYPE_VSM )\\n\\t\\t\\tshadow = VSMShadow( shadowMap, shadowCoord.xy, shadowCoord.z );\\n\\t\\t#else\\n\\t\\t\\tshadow = texture2DCompare( shadowMap, shadowCoord.xy, shadowCoord.z );\\n\\t\\t#endif\\n\\t\\t}\\n\\t\\treturn shadow;\\n\\t}\\n\\tvec2 cubeToUV( vec3 v, float texelSizeY ) {\\n\\t\\tvec3 absV = abs( v );\\n\\t\\tfloat scaleToCube = 1.0 / max( absV.x, max( absV.y, absV.z ) );\\n\\t\\tabsV *= scaleToCube;\\n\\t\\tv *= scaleToCube * ( 1.0 - 2.0 * texelSizeY );\\n\\t\\tvec2 planar = v.xy;\\n\\t\\tfloat almostATexel = 1.5 * texelSizeY;\\n\\t\\tfloat almostOne = 1.0 - almostATexel;\\n\\t\\tif ( absV.z >= almostOne ) {\\n\\t\\t\\tif ( v.z > 0.0 )\\n\\t\\t\\t\\tplanar.x = 4.0 - v.x;\\n\\t\\t} else if ( absV.x >= almostOne ) {\\n\\t\\t\\tfloat signX = sign( v.x );\\n\\t\\t\\tplanar.x = v.z * signX + 2.0 * signX;\\n\\t\\t} else if ( absV.y >= almostOne ) {\\n\\t\\t\\tfloat signY = sign( v.y );\\n\\t\\t\\tplanar.x = v.x + 2.0 * signY + 2.0;\\n\\t\\t\\tplanar.y = v.z * signY - 2.0;\\n\\t\\t}\\n\\t\\treturn vec2( 0.125, 0.25 ) * planar + vec2( 0.375, 0.75 );\\n\\t}\\n\\tfloat getPointShadow( sampler2D shadowMap, vec2 shadowMapSize, float shadowBias, float shadowRadius, vec4 shadowCoord, float shadowCameraNear, float shadowCameraFar ) {\\n\\t\\tvec2 texelSize = vec2( 1.0 ) / ( shadowMapSize * vec2( 4.0, 2.0 ) );\\n\\t\\tvec3 lightToPosition = shadowCoord.xyz;\\n\\t\\tfloat dp = ( length( lightToPosition ) - shadowCameraNear ) / ( shadowCameraFar - shadowCameraNear );\\t\\tdp += shadowBias;\\n\\t\\tvec3 bd3D = normalize( lightToPosition );\\n\\t\\t#if defined( SHADOWMAP_TYPE_PCF ) || defined( SHADOWMAP_TYPE_PCF_SOFT ) || defined( SHADOWMAP_TYPE_VSM )\\n\\t\\t\\tvec2 offset = vec2( - 1, 1 ) * shadowRadius * texelSize.y;\\n\\t\\t\\treturn (\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xyy, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yyy, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xyx, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yyx, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xxy, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yxy, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xxx, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yxx, texelSize.y ), dp )\\n\\t\\t\\t) * ( 1.0 / 9.0 );\\n\\t\\t#else\\n\\t\\t\\treturn texture2DCompare( shadowMap, cubeToUV( bd3D, texelSize.y ), dp );\\n\\t\\t#endif\\n\\t}\\n#endif",shadowmap_pars_vertex:"#ifdef USE_SHADOWMAP\\n\\t#if NUM_DIR_LIGHT_SHADOWS > 0\\n\\t\\tuniform mat4 directionalShadowMatrix[ NUM_DIR_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vDirectionalShadowCoord[ NUM_DIR_LIGHT_SHADOWS ];\\n\\t#endif\\n\\t#if NUM_SPOT_LIGHT_SHADOWS > 0\\n\\t\\tuniform mat4 spotShadowMatrix[ NUM_SPOT_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vSpotShadowCoord[ NUM_SPOT_LIGHT_SHADOWS ];\\n\\t#endif\\n\\t#if NUM_POINT_LIGHT_SHADOWS > 0\\n\\t\\tuniform mat4 pointShadowMatrix[ NUM_POINT_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vPointShadowCoord[ NUM_POINT_LIGHT_SHADOWS ];\\n\\t#endif\\n#endif",shadowmap_vertex:"#ifdef USE_SHADOWMAP\\n\\t#if NUM_DIR_LIGHT_SHADOWS > 0\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_DIR_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tvDirectionalShadowCoord[ i ] = directionalShadowMatrix[ i ] * worldPosition;\\n\\t}\\n\\t#endif\\n\\t#if NUM_SPOT_LIGHT_SHADOWS > 0\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_SPOT_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tvSpotShadowCoord[ i ] = spotShadowMatrix[ i ] * worldPosition;\\n\\t}\\n\\t#endif\\n\\t#if NUM_POINT_LIGHT_SHADOWS > 0\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_POINT_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tvPointShadowCoord[ i ] = pointShadowMatrix[ i ] * worldPosition;\\n\\t}\\n\\t#endif\\n#endif",shadowmask_pars_fragment:"float getShadowMask() {\\n\\tfloat shadow = 1.0;\\n\\t#ifdef USE_SHADOWMAP\\n\\t#if NUM_DIR_LIGHT_SHADOWS > 0\\n\\tDirectionalLight directionalLight;\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_DIR_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tdirectionalLight = directionalLights[ i ];\\n\\t\\tshadow *= all( bvec2( directionalLight.shadow, receiveShadow ) ) ? getShadow( directionalShadowMap[ i ], directionalLight.shadowMapSize, directionalLight.shadowBias, directionalLight.shadowRadius, vDirectionalShadowCoord[ i ] ) : 1.0;\\n\\t}\\n\\t#endif\\n\\t#if NUM_SPOT_LIGHT_SHADOWS > 0\\n\\tSpotLight spotLight;\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_SPOT_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tspotLight = spotLights[ i ];\\n\\t\\tshadow *= all( bvec2( spotLight.shadow, receiveShadow ) ) ? getShadow( spotShadowMap[ i ], spotLight.shadowMapSize, spotLight.shadowBias, spotLight.shadowRadius, vSpotShadowCoord[ i ] ) : 1.0;\\n\\t}\\n\\t#endif\\n\\t#if NUM_POINT_LIGHT_SHADOWS > 0\\n\\tPointLight pointLight;\\n\\t#pragma unroll_loop\\n\\tfor ( int i = 0; i < NUM_POINT_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tpointLight = pointLights[ i ];\\n\\t\\tshadow *= all( bvec2( pointLight.shadow, receiveShadow ) ) ? getPointShadow( pointShadowMap[ i ], pointLight.shadowMapSize, pointLight.shadowBias, pointLight.shadowRadius, vPointShadowCoord[ i ], pointLight.shadowCameraNear, pointLight.shadowCameraFar ) : 1.0;\\n\\t}\\n\\t#endif\\n\\t#endif\\n\\treturn shadow;\\n}",skinbase_vertex:"#ifdef USE_SKINNING\\n\\tmat4 boneMatX = getBoneMatrix( skinIndex.x );\\n\\tmat4 boneMatY = getBoneMatrix( skinIndex.y );\\n\\tmat4 boneMatZ = getBoneMatrix( skinIndex.z );\\n\\tmat4 boneMatW = getBoneMatrix( skinIndex.w );\\n#endif",skinning_pars_vertex:"#ifdef USE_SKINNING\\n\\tuniform mat4 bindMatrix;\\n\\tuniform mat4 bindMatrixInverse;\\n\\t#ifdef BONE_TEXTURE\\n\\t\\tuniform highp sampler2D boneTexture;\\n\\t\\tuniform int boneTextureSize;\\n\\t\\tmat4 getBoneMatrix( const in float i ) {\\n\\t\\t\\tfloat j = i * 4.0;\\n\\t\\t\\tfloat x = mod( j, float( boneTextureSize ) );\\n\\t\\t\\tfloat y = floor( j / float( boneTextureSize ) );\\n\\t\\t\\tfloat dx = 1.0 / float( boneTextureSize );\\n\\t\\t\\tfloat dy = 1.0 / float( boneTextureSize );\\n\\t\\t\\ty = dy * ( y + 0.5 );\\n\\t\\t\\tvec4 v1 = texture2D( boneTexture, vec2( dx * ( x + 0.5 ), y ) );\\n\\t\\t\\tvec4 v2 = texture2D( boneTexture, vec2( dx * ( x + 1.5 ), y ) );\\n\\t\\t\\tvec4 v3 = texture2D( boneTexture, vec2( dx * ( x + 2.5 ), y ) );\\n\\t\\t\\tvec4 v4 = texture2D( boneTexture, vec2( dx * ( x + 3.5 ), y ) );\\n\\t\\t\\tmat4 bone = mat4( v1, v2, v3, v4 );\\n\\t\\t\\treturn bone;\\n\\t\\t}\\n\\t#else\\n\\t\\tuniform mat4 boneMatrices[ MAX_BONES ];\\n\\t\\tmat4 getBoneMatrix( const in float i ) {\\n\\t\\t\\tmat4 bone = boneMatrices[ int(i) ];\\n\\t\\t\\treturn bone;\\n\\t\\t}\\n\\t#endif\\n#endif",skinning_vertex:"#ifdef USE_SKINNING\\n\\tvec4 skinVertex = bindMatrix * vec4( transformed, 1.0 );\\n\\tvec4 skinned = vec4( 0.0 );\\n\\tskinned += boneMatX * skinVertex * skinWeight.x;\\n\\tskinned += boneMatY * skinVertex * skinWeight.y;\\n\\tskinned += boneMatZ * skinVertex * skinWeight.z;\\n\\tskinned += boneMatW * skinVertex * skinWeight.w;\\n\\ttransformed = ( bindMatrixInverse * skinned ).xyz;\\n#endif",skinnormal_vertex:"#ifdef USE_SKINNING\\n\\tmat4 skinMatrix = mat4( 0.0 );\\n\\tskinMatrix += skinWeight.x * boneMatX;\\n\\tskinMatrix += skinWeight.y * boneMatY;\\n\\tskinMatrix += skinWeight.z * boneMatZ;\\n\\tskinMatrix += skinWeight.w * boneMatW;\\n\\tskinMatrix = bindMatrixInverse * skinMatrix * bindMatrix;\\n\\tobjectNormal = vec4( skinMatrix * vec4( objectNormal, 0.0 ) ).xyz;\\n\\t#ifdef USE_TANGENT\\n\\t\\tobjectTangent = vec4( skinMatrix * vec4( objectTangent, 0.0 ) ).xyz;\\n\\t#endif\\n#endif",specularmap_fragment:"float specularStrength;\\n#ifdef USE_SPECULARMAP\\n\\tvec4 texelSpecular = texture2D( specularMap, vUv );\\n\\tspecularStrength = texelSpecular.r;\\n#else\\n\\tspecularStrength = 1.0;\\n#endif",specularmap_pars_fragment:"#ifdef USE_SPECULARMAP\\n\\tuniform sampler2D specularMap;\\n#endif",tonemapping_fragment:"#if defined( TONE_MAPPING )\\n\\tgl_FragColor.rgb = toneMapping( gl_FragColor.rgb );\\n#endif",tonemapping_pars_fragment:"#ifndef saturate\\n#define saturate(a) clamp( a, 0.0, 1.0 )\\n#endif\\nuniform float toneMappingExposure;\\nuniform float toneMappingWhitePoint;\\nvec3 LinearToneMapping( vec3 color ) {\\n\\treturn toneMappingExposure * color;\\n}\\nvec3 ReinhardToneMapping( vec3 color ) {\\n\\tcolor *= toneMappingExposure;\\n\\treturn saturate( color / ( vec3( 1.0 ) + color ) );\\n}\\n#define Uncharted2Helper( x ) max( ( ( x * ( 0.15 * x + 0.10 * 0.50 ) + 0.20 * 0.02 ) / ( x * ( 0.15 * x + 0.50 ) + 0.20 * 0.30 ) ) - 0.02 / 0.30, vec3( 0.0 ) )\\nvec3 Uncharted2ToneMapping( vec3 color ) {\\n\\tcolor *= toneMappingExposure;\\n\\treturn saturate( Uncharted2Helper( color ) / Uncharted2Helper( vec3( toneMappingWhitePoint ) ) );\\n}\\nvec3 OptimizedCineonToneMapping( vec3 color ) {\\n\\tcolor *= toneMappingExposure;\\n\\tcolor = max( vec3( 0.0 ), color - 0.004 );\\n\\treturn pow( ( color * ( 6.2 * color + 0.5 ) ) / ( color * ( 6.2 * color + 1.7 ) + 0.06 ), vec3( 2.2 ) );\\n}\\nvec3 ACESFilmicToneMapping( vec3 color ) {\\n\\tcolor *= toneMappingExposure;\\n\\treturn saturate( ( color * ( 2.51 * color + 0.03 ) ) / ( color * ( 2.43 * color + 0.59 ) + 0.14 ) );\\n}",uv_pars_fragment:"#if ( defined( USE_UV ) && ! defined( UVS_VERTEX_ONLY ) )\\n\\tvarying vec2 vUv;\\n#endif",uv_pars_vertex:"#ifdef USE_UV\\n\\t#ifdef UVS_VERTEX_ONLY\\n\\t\\tvec2 vUv;\\n\\t#else\\n\\t\\tvarying vec2 vUv;\\n\\t#endif\\n\\tuniform mat3 uvTransform;\\n#endif",uv_vertex:"#ifdef USE_UV\\n\\tvUv = ( uvTransform * vec3( uv, 1 ) ).xy;\\n#endif",uv2_pars_fragment:"#if defined( USE_LIGHTMAP ) || defined( USE_AOMAP )\\n\\tvarying vec2 vUv2;\\n#endif",uv2_pars_vertex:"#if defined( USE_LIGHTMAP ) || defined( USE_AOMAP )\\n\\tattribute vec2 uv2;\\n\\tvarying vec2 vUv2;\\n#endif",uv2_vertex:"#if defined( USE_LIGHTMAP ) || defined( USE_AOMAP )\\n\\tvUv2 = uv2;\\n#endif",worldpos_vertex:"#if defined( USE_ENVMAP ) || defined( DISTANCE ) || defined ( USE_SHADOWMAP )\\n\\tvec4 worldPosition = vec4( transformed, 1.0 );\\n\\t#ifdef USE_INSTANCING\\n\\t\\tworldPosition = instanceMatrix * worldPosition;\\n\\t#endif\\n\\tworldPosition = modelMatrix * worldPosition;\\n#endif",background_frag:"uniform sampler2D t2D;\\nvarying vec2 vUv;\\nvoid main() {\\n\\tvec4 texColor = texture2D( t2D, vUv );\\n\\tgl_FragColor = mapTexelToLinear( texColor );\\n\\t#include \\n\\t#include \\n}",background_vert:"varying vec2 vUv;\\nuniform mat3 uvTransform;\\nvoid main() {\\n\\tvUv = ( uvTransform * vec3( uv, 1 ) ).xy;\\n\\tgl_Position = vec4( position.xy, 1.0, 1.0 );\\n}",cube_frag:"uniform samplerCube tCube;\\nuniform float tFlip;\\nuniform float opacity;\\nvarying vec3 vWorldDirection;\\nvoid main() {\\n\\tvec4 texColor = textureCube( tCube, vec3( tFlip * vWorldDirection.x, vWorldDirection.yz ) );\\n\\tgl_FragColor = mapTexelToLinear( texColor );\\n\\tgl_FragColor.a *= opacity;\\n\\t#include \\n\\t#include \\n}",cube_vert:"varying vec3 vWorldDirection;\\n#include \\nvoid main() {\\n\\tvWorldDirection = transformDirection( position, modelMatrix );\\n\\t#include \\n\\t#include \\n\\tgl_Position.z = gl_Position.w;\\n}",depth_frag:"#if DEPTH_PACKING == 3200\\n\\tuniform float opacity;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( 1.0 );\\n\\t#if DEPTH_PACKING == 3200\\n\\t\\tdiffuseColor.a = opacity;\\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#if DEPTH_PACKING == 3200\\n\\t\\tgl_FragColor = vec4( vec3( 1.0 - gl_FragCoord.z ), opacity );\\n\\t#elif DEPTH_PACKING == 3201\\n\\t\\tgl_FragColor = packDepthToRGBA( gl_FragCoord.z );\\n\\t#endif\\n}",depth_vert:"#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#ifdef USE_DISPLACEMENTMAP\\n\\t\\t#include \\n\\t\\t#include \\n\\t\\t#include \\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",distanceRGBA_frag:"#define DISTANCE\\nuniform vec3 referencePosition;\\nuniform float nearDistance;\\nuniform float farDistance;\\nvarying vec3 vWorldPosition;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main () {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( 1.0 );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\tfloat dist = length( vWorldPosition - referencePosition );\\n\\tdist = ( dist - nearDistance ) / ( farDistance - nearDistance );\\n\\tdist = saturate( dist );\\n\\tgl_FragColor = packDepthToRGBA( dist );\\n}",distanceRGBA_vert:"#define DISTANCE\\nvarying vec3 vWorldPosition;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#ifdef USE_DISPLACEMENTMAP\\n\\t\\t#include \\n\\t\\t#include \\n\\t\\t#include \\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvWorldPosition = worldPosition.xyz;\\n}",equirect_frag:"uniform sampler2D tEquirect;\\nvarying vec3 vWorldDirection;\\n#include \\nvoid main() {\\n\\tvec3 direction = normalize( vWorldDirection );\\n\\tvec2 sampleUV;\\n\\tsampleUV.y = asin( clamp( direction.y, - 1.0, 1.0 ) ) * RECIPROCAL_PI + 0.5;\\n\\tsampleUV.x = atan( direction.z, direction.x ) * RECIPROCAL_PI2 + 0.5;\\n\\tvec4 texColor = texture2D( tEquirect, sampleUV );\\n\\tgl_FragColor = mapTexelToLinear( texColor );\\n\\t#include \\n\\t#include \\n}",equirect_vert:"varying vec3 vWorldDirection;\\n#include \\nvoid main() {\\n\\tvWorldDirection = transformDirection( position, modelMatrix );\\n\\t#include \\n\\t#include \\n}",linedashed_frag:"uniform vec3 diffuse;\\nuniform float opacity;\\nuniform float dashSize;\\nuniform float totalSize;\\nvarying float vLineDistance;\\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tif ( mod( vLineDistance, totalSize ) > dashSize ) {\\n\\t\\tdiscard;\\n\\t}\\n\\tvec3 outgoingLight = vec3( 0.0 );\\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\t#include \\n\\t#include \\n\\toutgoingLight = diffuseColor.rgb;\\n\\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",linedashed_vert:"uniform float scale;\\nattribute float lineDistance;\\nvarying float vLineDistance;\\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvLineDistance = scale * lineDistance;\\n\\tvec4 mvPosition = modelViewMatrix * vec4( position, 1.0 );\\n\\tgl_Position = projectionMatrix * mvPosition;\\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshbasic_frag:"uniform vec3 diffuse;\\nuniform float opacity;\\n#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\\n\\t#ifdef USE_LIGHTMAP\\n\\t\\treflectedLight.indirectDiffuse += texture2D( lightMap, vUv2 ).xyz * lightMapIntensity;\\n\\t#else\\n\\t\\treflectedLight.indirectDiffuse += vec3( 1.0 );\\n\\t#endif\\n\\t#include \\n\\treflectedLight.indirectDiffuse *= diffuseColor.rgb;\\n\\tvec3 outgoingLight = reflectedLight.indirectDiffuse;\\n\\t#include \\n\\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshbasic_vert:"#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#ifdef USE_ENVMAP\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshlambert_frag:"uniform vec3 diffuse;\\nuniform vec3 emissive;\\nuniform float opacity;\\nvarying vec3 vLightFront;\\nvarying vec3 vIndirectFront;\\n#ifdef DOUBLE_SIDED\\n\\tvarying vec3 vLightBack;\\n\\tvarying vec3 vIndirectBack;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\\n\\tvec3 totalEmissiveRadiance = emissive;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\treflectedLight.indirectDiffuse = getAmbientLightIrradiance( ambientLightColor );\\n\\t#ifdef DOUBLE_SIDED\\n\\t\\treflectedLight.indirectDiffuse += ( gl_FrontFacing ) ? vIndirectFront : vIndirectBack;\\n\\t#else\\n\\t\\treflectedLight.indirectDiffuse += vIndirectFront;\\n\\t#endif\\n\\t#include \\n\\treflectedLight.indirectDiffuse *= BRDF_Diffuse_Lambert( diffuseColor.rgb );\\n\\t#ifdef DOUBLE_SIDED\\n\\t\\treflectedLight.directDiffuse = ( gl_FrontFacing ) ? vLightFront : vLightBack;\\n\\t#else\\n\\t\\treflectedLight.directDiffuse = vLightFront;\\n\\t#endif\\n\\treflectedLight.directDiffuse *= BRDF_Diffuse_Lambert( diffuseColor.rgb ) * getShadowMask();\\n\\t#include \\n\\tvec3 outgoingLight = reflectedLight.directDiffuse + reflectedLight.indirectDiffuse + totalEmissiveRadiance;\\n\\t#include \\n\\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshlambert_vert:"#define LAMBERT\\nvarying vec3 vLightFront;\\nvarying vec3 vIndirectFront;\\n#ifdef DOUBLE_SIDED\\n\\tvarying vec3 vLightBack;\\n\\tvarying vec3 vIndirectBack;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshmatcap_frag:"#define MATCAP\\nuniform vec3 diffuse;\\nuniform float opacity;\\nuniform sampler2D matcap;\\nvarying vec3 vViewPosition;\\n#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvec3 viewDir = normalize( vViewPosition );\\n\\tvec3 x = normalize( vec3( viewDir.z, 0.0, - viewDir.x ) );\\n\\tvec3 y = cross( viewDir, x );\\n\\tvec2 uv = vec2( dot( x, normal ), dot( y, normal ) ) * 0.495 + 0.5;\\n\\t#ifdef USE_MATCAP\\n\\t\\tvec4 matcapColor = texture2D( matcap, uv );\\n\\t\\tmatcapColor = matcapTexelToLinear( matcapColor );\\n\\t#else\\n\\t\\tvec4 matcapColor = vec4( 1.0 );\\n\\t#endif\\n\\tvec3 outgoingLight = diffuseColor.rgb * matcapColor.rgb;\\n\\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshmatcap_vert:"#define MATCAP\\nvarying vec3 vViewPosition;\\n#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#ifndef FLAT_SHADED\\n\\t\\tvNormal = normalize( transformedNormal );\\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvViewPosition = - mvPosition.xyz;\\n}",meshphong_frag:"#define PHONG\\nuniform vec3 diffuse;\\nuniform vec3 emissive;\\nuniform vec3 specular;\\nuniform float shininess;\\nuniform float opacity;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\\n\\tvec3 totalEmissiveRadiance = emissive;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvec3 outgoingLight = reflectedLight.directDiffuse + reflectedLight.indirectDiffuse + reflectedLight.directSpecular + reflectedLight.indirectSpecular + totalEmissiveRadiance;\\n\\t#include \\n\\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshphong_vert:"#define PHONG\\nvarying vec3 vViewPosition;\\n#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n#ifndef FLAT_SHADED\\n\\tvNormal = normalize( transformedNormal );\\n#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvViewPosition = - mvPosition.xyz;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshphysical_frag:"#define STANDARD\\n#ifdef PHYSICAL\\n\\t#define REFLECTIVITY\\n\\t#define CLEARCOAT\\n\\t#define TRANSPARENCY\\n#endif\\nuniform vec3 diffuse;\\nuniform vec3 emissive;\\nuniform float roughness;\\nuniform float metalness;\\nuniform float opacity;\\n#ifdef TRANSPARENCY\\n\\tuniform float transparency;\\n#endif\\n#ifdef REFLECTIVITY\\n\\tuniform float reflectivity;\\n#endif\\n#ifdef CLEARCOAT\\n\\tuniform float clearcoat;\\n\\tuniform float clearcoatRoughness;\\n#endif\\n#ifdef USE_SHEEN\\n\\tuniform vec3 sheen;\\n#endif\\nvarying vec3 vViewPosition;\\n#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n\\t#ifdef USE_TANGENT\\n\\t\\tvarying vec3 vTangent;\\n\\t\\tvarying vec3 vBitangent;\\n\\t#endif\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\\n\\tvec3 totalEmissiveRadiance = emissive;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvec3 outgoingLight = reflectedLight.directDiffuse + reflectedLight.indirectDiffuse + reflectedLight.directSpecular + reflectedLight.indirectSpecular + totalEmissiveRadiance;\\n\\t#ifdef TRANSPARENCY\\n\\t\\tdiffuseColor.a *= saturate( 1. - transparency + linearToRelativeLuminance( reflectedLight.directSpecular + reflectedLight.indirectSpecular ) );\\n\\t#endif\\n\\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshphysical_vert:"#define STANDARD\\nvarying vec3 vViewPosition;\\n#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n\\t#ifdef USE_TANGENT\\n\\t\\tvarying vec3 vTangent;\\n\\t\\tvarying vec3 vBitangent;\\n\\t#endif\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n#ifndef FLAT_SHADED\\n\\tvNormal = normalize( transformedNormal );\\n\\t#ifdef USE_TANGENT\\n\\t\\tvTangent = normalize( transformedTangent );\\n\\t\\tvBitangent = normalize( cross( vNormal, vTangent ) * tangent.w );\\n\\t#endif\\n#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvViewPosition = - mvPosition.xyz;\\n\\t#include \\n\\t#include \\n\\t#include \\n}",normal_frag:"#define NORMAL\\nuniform float opacity;\\n#if defined( FLAT_SHADED ) || defined( USE_BUMPMAP ) || defined( TANGENTSPACE_NORMALMAP )\\n\\tvarying vec3 vViewPosition;\\n#endif\\n#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n\\t#ifdef USE_TANGENT\\n\\t\\tvarying vec3 vTangent;\\n\\t\\tvarying vec3 vBitangent;\\n\\t#endif\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tgl_FragColor = vec4( packNormalToRGB( normal ), opacity );\\n}",normal_vert:"#define NORMAL\\n#if defined( FLAT_SHADED ) || defined( USE_BUMPMAP ) || defined( TANGENTSPACE_NORMALMAP )\\n\\tvarying vec3 vViewPosition;\\n#endif\\n#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n\\t#ifdef USE_TANGENT\\n\\t\\tvarying vec3 vTangent;\\n\\t\\tvarying vec3 vBitangent;\\n\\t#endif\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n#ifndef FLAT_SHADED\\n\\tvNormal = normalize( transformedNormal );\\n\\t#ifdef USE_TANGENT\\n\\t\\tvTangent = normalize( transformedTangent );\\n\\t\\tvBitangent = normalize( cross( vNormal, vTangent ) * tangent.w );\\n\\t#endif\\n#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n#if defined( FLAT_SHADED ) || defined( USE_BUMPMAP ) || defined( TANGENTSPACE_NORMALMAP )\\n\\tvViewPosition = - mvPosition.xyz;\\n#endif\\n}",points_frag:"uniform vec3 diffuse;\\nuniform float opacity;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec3 outgoingLight = vec3( 0.0 );\\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\toutgoingLight = diffuseColor.rgb;\\n\\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",points_vert:"uniform float size;\\nuniform float scale;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tgl_PointSize = size;\\n\\t#ifdef USE_SIZEATTENUATION\\n\\t\\tbool isPerspective = isPerspectiveMatrix( projectionMatrix );\\n\\t\\tif ( isPerspective ) gl_PointSize *= ( scale / - mvPosition.z );\\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",shadow_frag:"uniform vec3 color;\\nuniform float opacity;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\tgl_FragColor = vec4( color, opacity * ( 1.0 - getShadowMask() ) );\\n\\t#include \\n}",shadow_vert:"#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",sprite_frag:"uniform vec3 diffuse;\\nuniform float opacity;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec3 outgoingLight = vec3( 0.0 );\\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\toutgoingLight = diffuseColor.rgb;\\n\\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\\n\\t#include \\n\\t#include \\n\\t#include \\n}",sprite_vert:"uniform float rotation;\\nuniform vec2 center;\\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 mvPosition = modelViewMatrix * vec4( 0.0, 0.0, 0.0, 1.0 );\\n\\tvec2 scale;\\n\\tscale.x = length( vec3( modelMatrix[ 0 ].x, modelMatrix[ 0 ].y, modelMatrix[ 0 ].z ) );\\n\\tscale.y = length( vec3( modelMatrix[ 1 ].x, modelMatrix[ 1 ].y, modelMatrix[ 1 ].z ) );\\n\\t#ifndef USE_SIZEATTENUATION\\n\\t\\tbool isPerspective = isPerspectiveMatrix( projectionMatrix );\\n\\t\\tif ( isPerspective ) scale *= - mvPosition.z;\\n\\t#endif\\n\\tvec2 alignedPosition = ( position.xy - ( center - vec2( 0.5 ) ) ) * scale;\\n\\tvec2 rotatedPosition;\\n\\trotatedPosition.x = cos( rotation ) * alignedPosition.x - sin( rotation ) * alignedPosition.y;\\n\\trotatedPosition.y = sin( rotation ) * alignedPosition.x + cos( rotation ) * alignedPosition.y;\\n\\tmvPosition.xy += rotatedPosition;\\n\\tgl_Position = projectionMatrix * mvPosition;\\n\\t#include \\n\\t#include \\n\\t#include \\n}"},fo={common:{diffuse:{value:new Jr(15658734)},opacity:{value:1},map:{value:null},uvTransform:{value:new An},alphaMap:{value:null}},specularmap:{specularMap:{value:null}},envmap:{envMap:{value:null},flipEnvMap:{value:-1},reflectivity:{value:1},refractionRatio:{value:.98},maxMipLevel:{value:0}},aomap:{aoMap:{value:null},aoMapIntensity:{value:1}},lightmap:{lightMap:{value:null},lightMapIntensity:{value:1}},emissivemap:{emissiveMap:{value:null}},bumpmap:{bumpMap:{value:null},bumpScale:{value:1}},normalmap:{normalMap:{value:null},normalScale:{value:new _n(1,1)}},displacementmap:{displacementMap:{value:null},displacementScale:{value:1},displacementBias:{value:0}},roughnessmap:{roughnessMap:{value:null}},metalnessmap:{metalnessMap:{value:null}},gradientmap:{gradientMap:{value:null}},fog:{fogDensity:{value:25e-5},fogNear:{value:1},fogFar:{value:2e3},fogColor:{value:new Jr(16777215)}},lights:{ambientLightColor:{value:[]},lightProbe:{value:[]},directionalLights:{value:[],properties:{direction:{},color:{},shadow:{},shadowBias:{},shadowRadius:{},shadowMapSize:{}}},directionalShadowMap:{value:[]},directionalShadowMatrix:{value:[]},spotLights:{value:[],properties:{color:{},position:{},direction:{},distance:{},coneCos:{},penumbraCos:{},decay:{},shadow:{},shadowBias:{},shadowRadius:{},shadowMapSize:{}}},spotShadowMap:{value:[]},spotShadowMatrix:{value:[]},pointLights:{value:[],properties:{color:{},position:{},decay:{},distance:{},shadow:{},shadowBias:{},shadowRadius:{},shadowMapSize:{},shadowCameraNear:{},shadowCameraFar:{}}},pointShadowMap:{value:[]},pointShadowMatrix:{value:[]},hemisphereLights:{value:[],properties:{direction:{},skyColor:{},groundColor:{}}},rectAreaLights:{value:[],properties:{color:{},position:{},width:{},height:{}}}},points:{diffuse:{value:new Jr(15658734)},opacity:{value:1},size:{value:1},scale:{value:1},map:{value:null},alphaMap:{value:null},uvTransform:{value:new An}},sprite:{diffuse:{value:new Jr(15658734)},opacity:{value:1},center:{value:new _n(.5,.5)},rotation:{value:0},map:{value:null},alphaMap:{value:null},uvTransform:{value:new An}}},mo={basic:{uniforms:Ki([fo.common,fo.specularmap,fo.envmap,fo.aomap,fo.lightmap,fo.fog]),vertexShader:po.meshbasic_vert,fragmentShader:po.meshbasic_frag},lambert:{uniforms:Ki([fo.common,fo.specularmap,fo.envmap,fo.aomap,fo.lightmap,fo.emissivemap,fo.fog,fo.lights,{emissive:{value:new Jr(0)}}]),vertexShader:po.meshlambert_vert,fragmentShader:po.meshlambert_frag},phong:{uniforms:Ki([fo.common,fo.specularmap,fo.envmap,fo.aomap,fo.lightmap,fo.emissivemap,fo.bumpmap,fo.normalmap,fo.displacementmap,fo.gradientmap,fo.fog,fo.lights,{emissive:{value:new Jr(0)},specular:{value:new Jr(1118481)},shininess:{value:30}}]),vertexShader:po.meshphong_vert,fragmentShader:po.meshphong_frag},standard:{uniforms:Ki([fo.common,fo.envmap,fo.aomap,fo.lightmap,fo.emissivemap,fo.bumpmap,fo.normalmap,fo.displacementmap,fo.roughnessmap,fo.metalnessmap,fo.fog,fo.lights,{emissive:{value:new Jr(0)},roughness:{value:.5},metalness:{value:.5},envMapIntensity:{value:1}}]),vertexShader:po.meshphysical_vert,fragmentShader:po.meshphysical_frag},matcap:{uniforms:Ki([fo.common,fo.bumpmap,fo.normalmap,fo.displacementmap,fo.fog,{matcap:{value:null}}]),vertexShader:po.meshmatcap_vert,fragmentShader:po.meshmatcap_frag},points:{uniforms:Ki([fo.points,fo.fog]),vertexShader:po.points_vert,fragmentShader:po.points_frag},dashed:{uniforms:Ki([fo.common,fo.fog,{scale:{value:1},dashSize:{value:1},totalSize:{value:2}}]),vertexShader:po.linedashed_vert,fragmentShader:po.linedashed_frag},depth:{uniforms:Ki([fo.common,fo.displacementmap]),vertexShader:po.depth_vert,fragmentShader:po.depth_frag},normal:{uniforms:Ki([fo.common,fo.bumpmap,fo.normalmap,fo.displacementmap,{opacity:{value:1}}]),vertexShader:po.normal_vert,fragmentShader:po.normal_frag},sprite:{uniforms:Ki([fo.sprite,fo.fog]),vertexShader:po.sprite_vert,fragmentShader:po.sprite_frag},background:{uniforms:{uvTransform:{value:new An},t2D:{value:null}},vertexShader:po.background_vert,fragmentShader:po.background_frag},cube:{uniforms:{tCube:{value:null},tFlip:{value:-1},opacity:{value:1}},vertexShader:po.cube_vert,fragmentShader:po.cube_frag},equirect:{uniforms:{tEquirect:{value:null}},vertexShader:po.equirect_vert,fragmentShader:po.equirect_frag},distanceRGBA:{uniforms:Ki([fo.common,fo.displacementmap,{referencePosition:{value:new En},nearDistance:{value:1},farDistance:{value:1e3}}]),vertexShader:po.distanceRGBA_vert,fragmentShader:po.distanceRGBA_frag},shadow:{uniforms:Ki([fo.lights,fo.fog,{color:{value:new Jr(0)},opacity:{value:1}}]),vertexShader:po.shadow_vert,fragmentShader:po.shadow_frag}};function go(){var e=null,t=!1,n=null;function r(i,o){!1!==t&&(n(i,o),e.requestAnimationFrame(r))}return{start:function(){!0!==t&&null!==n&&(e.requestAnimationFrame(r),t=!0)},stop:function(){t=!1},setAnimationLoop:function(e){n=e},setContext:function(t){e=t}}}function vo(e){var t=new WeakMap;return{get:function(e){return e.isInterleavedBufferAttribute&&(e=e.data),t.get(e)},remove:function(n){n.isInterleavedBufferAttribute&&(n=n.data);var r=t.get(n);r&&(e.deleteBuffer(r.buffer),t.delete(n))},update:function(n,r){n.isInterleavedBufferAttribute&&(n=n.data);var i=t.get(n);void 0===i?t.set(n,function(t,n){var r=t.array,i=t.usage,o=e.createBuffer();e.bindBuffer(n,o),e.bufferData(n,r,i),t.onUploadCallback();var a=5126;return r instanceof Float32Array?a=5126:r instanceof Float64Array?console.warn("THREE.WebGLAttributes: Unsupported data buffer format: Float64Array."):r instanceof Uint16Array?a=5123:r instanceof Int16Array?a=5122:r instanceof Uint32Array?a=5125:r instanceof Int32Array?a=5124:r instanceof Int8Array?a=5120:r instanceof Uint8Array&&(a=5121),{buffer:o,type:a,bytesPerElement:r.BYTES_PER_ELEMENT,version:t.version}}(n,r)):i.version0&&e.getShaderPrecisionFormat(35632,36338).precision>0)return"highp";t="mediump"}return"mediump"===t&&e.getShaderPrecisionFormat(35633,36337).precision>0&&e.getShaderPrecisionFormat(35632,36337).precision>0?"mediump":"lowp"}var o="undefined"!=typeof WebGL2RenderingContext&&e instanceof WebGL2RenderingContext||"undefined"!=typeof WebGL2ComputeRenderingContext&&e instanceof WebGL2ComputeRenderingContext,a=void 0!==n.precision?n.precision:"highp",s=i(a);s!==a&&(console.warn("THREE.WebGLRenderer:",a,"not supported, using",s,"instead."),a=s);var c=!0===n.logarithmicDepthBuffer,l=e.getParameter(34930),u=e.getParameter(35660),h=e.getParameter(3379),d=e.getParameter(34076),p=e.getParameter(34921),f=e.getParameter(36347),m=e.getParameter(36348),g=e.getParameter(36349),v=u>0,y=o||!!t.get("OES_texture_float");return{isWebGL2:o,getMaxAnisotropy:function(){if(void 0!==r)return r;var n=t.get("EXT_texture_filter_anisotropic");return r=null!==n?e.getParameter(n.MAX_TEXTURE_MAX_ANISOTROPY_EXT):0},getMaxPrecision:i,precision:a,logarithmicDepthBuffer:c,maxTextures:l,maxVertexTextures:u,maxTextureSize:h,maxCubemapSize:d,maxAttributes:p,maxVertexUniforms:f,maxVaryings:m,maxFragmentUniforms:g,vertexTextures:v,floatFragmentTextures:y,floatVertexTextures:v&&y,maxSamples:o?e.getParameter(36183):0}}function Mo(){var e=this,t=null,n=0,r=!1,i=!1,o=new Ir,a=new An,s={value:null,needsUpdate:!1};function c(){s.value!==t&&(s.value=t,s.needsUpdate=n>0),e.numPlanes=n,e.numIntersection=0}function l(t,n,r,i){var c=null!==t?t.length:0,l=null;if(0!==c){if(l=s.value,!0!==i||null===l){var u=r+4*c,h=n.matrixWorldInverse;a.getNormalMatrix(h),(null===l||l.length65535?ui:ci)(n,1);p.version=a,t.update(p,34963);var f=i.get(e);f&&t.remove(f),i.set(e,p)}return{get:function(e,t){var i=r.get(t);return i||(t.addEventListener("dispose",o),t.isBufferGeometry?i=t:t.isGeometry&&(void 0===t._bufferGeometry&&(t._bufferGeometry=(new wi).setFromObject(e)),i=t._bufferGeometry),r.set(t,i),n.memory.geometries++,i)},update:function(e){var n=e.index,r=e.attributes;for(var i in null!==n&&t.update(n,34963),r)t.update(r[i],34962);var o=e.morphAttributes;for(var i in o)for(var a=o[i],s=0,c=a.length;s0)return e;var i=t*n,o=Uo[i];if(void 0===o&&(o=new Float32Array(i),Uo[i]=o),0!==t){r.toArray(o,0);for(var a=1,s=0;a!==t;++a)s+=n,e[a].toArray(o,s)}return o}function Vo(e,t){if(e.length!==t.length)return!1;for(var n=0,r=e.length;n/gm;function Ua(e){return e.replace(ka,Fa)}function Fa(e,t){var n=po[t];if(void 0===n)throw new Error("Can not resolve #include <"+t+">");return Ua(n)}var za=/#pragma unroll_loop[\\s]+?for \\( int i \\= (\\d+)\\; i < (\\d+)\\; i \\+\\+ \\) \\{([\\s\\S]+?)(?=\\})\\}/g;function Ga(e){return e.replace(za,Ha)}function Ha(e,t,n,r){for(var i="",o=parseInt(t);o0?e.gammaFactor:1,M=o.isWebGL2?"":function(e,t,n){return[(e=e||{}).derivatives||t.envMapCubeUV||t.bumpMap||t.tangentSpaceNormalMap||t.clearcoatNormalMap||t.flatShading?"#extension GL_OES_standard_derivatives : enable":"",(e.fragDepth||t.logarithmicDepthBuffer)&&n.get("EXT_frag_depth")?"#extension GL_EXT_frag_depth : enable":"",e.drawBuffers&&n.get("WEBGL_draw_buffers")?"#extension GL_EXT_draw_buffers : require":"",(e.shaderTextureLOD||t.envMap)&&n.get("EXT_shader_texture_lod")?"#extension GL_EXT_shader_texture_lod : enable":""].filter(Ia).join("\\n")}(r.extensions,o,t),E=function(e){var t=[];for(var n in e){var r=e[n];!1!==r&&t.push("#define "+n+" "+r)}return t.join("\\n")}(d),T=h.createProgram(),S=o.numMultiviewViews;if(r.isRawShaderMaterial?((a=[E].filter(Ia).join("\\n")).length>0&&(a+="\\n"),(s=[M,E].filter(Ia).join("\\n")).length>0&&(s+="\\n")):(a=[ja(o),"#define SHADER_NAME "+i.name,E,o.instancing?"#define USE_INSTANCING":"",o.supportsVertexTextures?"#define VERTEX_TEXTURES":"","#define GAMMA_FACTOR "+w,"#define MAX_BONES "+o.maxBones,o.useFog&&o.fog?"#define USE_FOG":"",o.useFog&&o.fogExp2?"#define FOG_EXP2":"",o.map?"#define USE_MAP":"",o.envMap?"#define USE_ENVMAP":"",o.envMap?"#define "+_:"",o.lightMap?"#define USE_LIGHTMAP":"",o.aoMap?"#define USE_AOMAP":"",o.emissiveMap?"#define USE_EMISSIVEMAP":"",o.bumpMap?"#define USE_BUMPMAP":"",o.normalMap?"#define USE_NORMALMAP":"",o.normalMap&&o.objectSpaceNormalMap?"#define OBJECTSPACE_NORMALMAP":"",o.normalMap&&o.tangentSpaceNormalMap?"#define TANGENTSPACE_NORMALMAP":"",o.clearcoatNormalMap?"#define USE_CLEARCOAT_NORMALMAP":"",o.displacementMap&&o.supportsVertexTextures?"#define USE_DISPLACEMENTMAP":"",o.specularMap?"#define USE_SPECULARMAP":"",o.roughnessMap?"#define USE_ROUGHNESSMAP":"",o.metalnessMap?"#define USE_METALNESSMAP":"",o.alphaMap?"#define USE_ALPHAMAP":"",o.vertexTangents?"#define USE_TANGENT":"",o.vertexColors?"#define USE_COLOR":"",o.vertexUvs?"#define USE_UV":"",o.uvsVertexOnly?"#define UVS_VERTEX_ONLY":"",o.flatShading?"#define FLAT_SHADED":"",o.skinning?"#define USE_SKINNING":"",o.useVertexTexture?"#define BONE_TEXTURE":"",o.morphTargets?"#define USE_MORPHTARGETS":"",o.morphNormals&&!1===o.flatShading?"#define USE_MORPHNORMALS":"",o.doubleSided?"#define DOUBLE_SIDED":"",o.flipSided?"#define FLIP_SIDED":"",o.shadowMapEnabled?"#define USE_SHADOWMAP":"",o.shadowMapEnabled?"#define "+y:"",o.sizeAttenuation?"#define USE_SIZEATTENUATION":"",o.logarithmicDepthBuffer?"#define USE_LOGDEPTHBUF":"",o.logarithmicDepthBuffer&&(o.isWebGL2||t.get("EXT_frag_depth"))?"#define USE_LOGDEPTHBUF_EXT":"","uniform mat4 modelMatrix;","uniform mat4 modelViewMatrix;","uniform mat4 projectionMatrix;","uniform mat4 viewMatrix;","uniform mat3 normalMatrix;","uniform vec3 cameraPosition;","uniform bool isOrthographic;","#ifdef USE_INSTANCING"," attribute mat4 instanceMatrix;","#endif","attribute vec3 position;","attribute vec3 normal;","attribute vec2 uv;","#ifdef USE_TANGENT","\\tattribute vec4 tangent;","#endif","#ifdef USE_COLOR","\\tattribute vec3 color;","#endif","#ifdef USE_MORPHTARGETS","\\tattribute vec3 morphTarget0;","\\tattribute vec3 morphTarget1;","\\tattribute vec3 morphTarget2;","\\tattribute vec3 morphTarget3;","\\t#ifdef USE_MORPHNORMALS","\\t\\tattribute vec3 morphNormal0;","\\t\\tattribute vec3 morphNormal1;","\\t\\tattribute vec3 morphNormal2;","\\t\\tattribute vec3 morphNormal3;","\\t#else","\\t\\tattribute vec3 morphTarget4;","\\t\\tattribute vec3 morphTarget5;","\\t\\tattribute vec3 morphTarget6;","\\t\\tattribute vec3 morphTarget7;","\\t#endif","#endif","#ifdef USE_SKINNING","\\tattribute vec4 skinIndex;","\\tattribute vec4 skinWeight;","#endif","\\n"].filter(Ia).join("\\n"),s=[M,ja(o),"#define SHADER_NAME "+i.name,E,o.alphaTest?"#define ALPHATEST "+o.alphaTest+(o.alphaTest%1?"":".0"):"","#define GAMMA_FACTOR "+w,o.useFog&&o.fog?"#define USE_FOG":"",o.useFog&&o.fogExp2?"#define FOG_EXP2":"",o.map?"#define USE_MAP":"",o.matcap?"#define USE_MATCAP":"",o.envMap?"#define USE_ENVMAP":"",o.envMap?"#define "+b:"",o.envMap?"#define "+_:"",o.envMap?"#define "+x:"",o.lightMap?"#define USE_LIGHTMAP":"",o.aoMap?"#define USE_AOMAP":"",o.emissiveMap?"#define USE_EMISSIVEMAP":"",o.bumpMap?"#define USE_BUMPMAP":"",o.normalMap?"#define USE_NORMALMAP":"",o.normalMap&&o.objectSpaceNormalMap?"#define OBJECTSPACE_NORMALMAP":"",o.normalMap&&o.tangentSpaceNormalMap?"#define TANGENTSPACE_NORMALMAP":"",o.clearcoatNormalMap?"#define USE_CLEARCOAT_NORMALMAP":"",o.specularMap?"#define USE_SPECULARMAP":"",o.roughnessMap?"#define USE_ROUGHNESSMAP":"",o.metalnessMap?"#define USE_METALNESSMAP":"",o.alphaMap?"#define USE_ALPHAMAP":"",o.sheen?"#define USE_SHEEN":"",o.vertexTangents?"#define USE_TANGENT":"",o.vertexColors?"#define USE_COLOR":"",o.vertexUvs?"#define USE_UV":"",o.uvsVertexOnly?"#define UVS_VERTEX_ONLY":"",o.gradientMap?"#define USE_GRADIENTMAP":"",o.flatShading?"#define FLAT_SHADED":"",o.doubleSided?"#define DOUBLE_SIDED":"",o.flipSided?"#define FLIP_SIDED":"",o.shadowMapEnabled?"#define USE_SHADOWMAP":"",o.shadowMapEnabled?"#define "+y:"",o.premultipliedAlpha?"#define PREMULTIPLIED_ALPHA":"",o.physicallyCorrectLights?"#define PHYSICALLY_CORRECT_LIGHTS":"",o.logarithmicDepthBuffer?"#define USE_LOGDEPTHBUF":"",o.logarithmicDepthBuffer&&(o.isWebGL2||t.get("EXT_frag_depth"))?"#define USE_LOGDEPTHBUF_EXT":"",(r.extensions&&r.extensions.shaderTextureLOD||o.envMap)&&(o.isWebGL2||t.get("EXT_shader_texture_lod"))?"#define TEXTURE_LOD_EXT":"","uniform mat4 viewMatrix;","uniform vec3 cameraPosition;","uniform bool isOrthographic;",o.toneMapping!==re?"#define TONE_MAPPING":"",o.toneMapping!==re?po.tonemapping_pars_fragment:"",o.toneMapping!==re?Na("toneMapping",o.toneMapping):"",o.dithering?"#define DITHERING":"",o.outputEncoding||o.mapEncoding||o.matcapEncoding||o.envMapEncoding||o.emissiveMapEncoding?po.encodings_pars_fragment:"",o.mapEncoding?Oa("mapTexelToLinear",o.mapEncoding):"",o.matcapEncoding?Oa("matcapTexelToLinear",o.matcapEncoding):"",o.envMapEncoding?Oa("envMapTexelToLinear",o.envMapEncoding):"",o.emissiveMapEncoding?Oa("emissiveMapTexelToLinear",o.emissiveMapEncoding):"",o.outputEncoding?(c="linearToOutputTexel",l=o.outputEncoding,u=Ra(l),"vec4 "+c+"( vec4 value ) { return LinearTo"+u[0]+u[1]+"; }"):"",o.depthPacking?"#define DEPTH_PACKING "+r.depthPacking:"","\\n"].filter(Ia).join("\\n")),g=Ba(g=Da(g=Ua(g),o),o),v=Ba(v=Da(v=Ua(v),o),o),g=Ga(g),v=Ga(v),o.isWebGL2&&!r.isRawShaderMaterial){var A=!1,L=/^\\s*#version\\s+300\\s+es\\s*\\n/;r.isShaderMaterial&&null!==g.match(L)&&null!==v.match(L)&&(A=!0,g=g.replace(L,""),v=v.replace(L,"")),a=["#version 300 es\\n","#define attribute in","#define varying out","#define texture2D texture"].join("\\n")+"\\n"+a,s=["#version 300 es\\n","#define varying in",A?"":"out highp vec4 pc_fragColor;",A?"":"#define gl_FragColor pc_fragColor","#define gl_FragDepthEXT gl_FragDepth","#define texture2D texture","#define textureCube texture","#define texture2DProj textureProj","#define texture2DLodEXT textureLod","#define texture2DProjLodEXT textureProjLod","#define textureCubeLodEXT textureLod","#define texture2DGradEXT textureGrad","#define texture2DProjGradEXT textureProjGrad","#define textureCubeGradEXT textureGrad"].join("\\n")+"\\n"+s,S>0&&(a=(a=a.replace("#version 300 es\\n",["#version 300 es\\n","#extension GL_OVR_multiview2 : require","layout(num_views = "+S+") in;","#define VIEW_ID gl_ViewID_OVR"].join("\\n"))).replace(["uniform mat4 modelViewMatrix;","uniform mat4 projectionMatrix;","uniform mat4 viewMatrix;","uniform mat3 normalMatrix;"].join("\\n"),["uniform mat4 modelViewMatrices["+S+"];","uniform mat4 projectionMatrices["+S+"];","uniform mat4 viewMatrices["+S+"];","uniform mat3 normalMatrices["+S+"];","#define modelViewMatrix modelViewMatrices[VIEW_ID]","#define projectionMatrix projectionMatrices[VIEW_ID]","#define viewMatrix viewMatrices[VIEW_ID]","#define normalMatrix normalMatrices[VIEW_ID]"].join("\\n")),s=(s=s.replace("#version 300 es\\n",["#version 300 es\\n","#extension GL_OVR_multiview2 : require","#define VIEW_ID gl_ViewID_OVR"].join("\\n"))).replace("uniform mat4 viewMatrix;",["uniform mat4 viewMatrices["+S+"];","#define viewMatrix viewMatrices[VIEW_ID]"].join("\\n")))}var C,R,P=s+v,O=La(h,35633,a+g),N=La(h,35632,P);if(h.attachShader(T,O),h.attachShader(T,N),void 0!==r.index0AttributeName?h.bindAttribLocation(T,0,r.index0AttributeName):!0===o.morphTargets&&h.bindAttribLocation(T,0,"position"),h.linkProgram(T),e.debug.checkShaderErrors){var I=h.getProgramInfoLog(T).trim(),D=h.getShaderInfoLog(O).trim(),B=h.getShaderInfoLog(N).trim(),k=!0,U=!0;if(!1===h.getProgramParameter(T,35714)){k=!1;var F=Pa(h,O,"vertex"),z=Pa(h,N,"fragment");console.error("THREE.WebGLProgram: shader error: ",h.getError(),"35715",h.getProgramParameter(T,35715),"gl.getProgramInfoLog",I,F,z)}else""!==I?console.warn("THREE.WebGLProgram: gl.getProgramInfoLog()",I):""!==D&&""!==B||(U=!1);U&&(this.diagnostics={runnable:k,material:r,programLog:I,vertexShader:{log:D,prefix:a},fragmentShader:{log:B,prefix:s}})}return h.deleteShader(O),h.deleteShader(N),this.getUniforms=function(){return void 0===C&&(C=new Aa(h,T)),C},this.getAttributes=function(){return void 0===R&&(R=function(e,t){for(var n={},r=e.getProgramParameter(t,35721),i=0;i0,maxBones:_,useVertexTexture:a,morphTargets:t.morphTargets,morphNormals:t.morphNormals,maxMorphTargets:e.maxMorphTargets,maxMorphNormals:e.maxMorphNormals,numDirLights:r.directional.length,numPointLights:r.point.length,numSpotLights:r.spot.length,numRectAreaLights:r.rectArea.length,numHemiLights:r.hemi.length,numDirLightShadows:r.directionalShadowMap.length,numPointLightShadows:r.pointShadowMap.length,numSpotLightShadows:r.spotShadowMap.length,numClippingPlanes:f,numClipIntersection:m,dithering:t.dithering,shadowMapEnabled:e.shadowMap.enabled&&h.length>0,shadowMapType:e.shadowMap.type,toneMapping:t.toneMapped?e.toneMapping:re,physicallyCorrectLights:e.physicallyCorrectLights,premultipliedAlpha:t.premultipliedAlpha,alphaTest:t.alphaTest,doubleSided:t.side===y,flipSided:t.side===v,depthPacking:void 0!==t.depthPacking&&t.depthPacking}},this.getProgramCacheKey=function(t,n){var r=[];if(n.shaderID?r.push(n.shaderID):(r.push(t.fragmentShader),r.push(t.vertexShader)),void 0!==t.defines)for(var i in t.defines)r.push(i),r.push(t.defines[i]);for(var o=0;o1&&n.sort(Ya),r.length>1&&r.sort(Xa)}}}function Za(){var e=new WeakMap;function t(n){var r=n.target;r.removeEventListener("dispose",t),e.delete(r)}return{get:function(n,r){var i,o=e.get(n);return void 0===o?(i=new Ja,e.set(n,new WeakMap),e.get(n).set(r,i),n.addEventListener("dispose",t)):void 0===(i=o.get(r))&&(i=new Ja,o.set(r,i)),i},dispose:function(){e=new WeakMap}}}function Ka(){var e={};return{get:function(t){if(void 0!==e[t.id])return e[t.id];var n;switch(t.type){case"DirectionalLight":n={direction:new En,color:new Jr,shadow:!1,shadowBias:0,shadowRadius:1,shadowMapSize:new _n};break;case"SpotLight":n={position:new En,direction:new En,color:new Jr,distance:0,coneCos:0,penumbraCos:0,decay:0,shadow:!1,shadowBias:0,shadowRadius:1,shadowMapSize:new _n};break;case"PointLight":n={position:new En,color:new Jr,distance:0,decay:0,shadow:!1,shadowBias:0,shadowRadius:1,shadowMapSize:new _n,shadowCameraNear:1,shadowCameraFar:1e3};break;case"HemisphereLight":n={direction:new En,skyColor:new Jr,groundColor:new Jr};break;case"RectAreaLight":n={color:new Jr,position:new En,halfWidth:new En,halfHeight:new En}}return e[t.id]=n,n}}}var Qa=0;function $a(e,t){return(t.castShadow?1:0)-(e.castShadow?1:0)}function es(){for(var e=new Ka,t={version:0,hash:{directionalLength:-1,pointLength:-1,spotLength:-1,rectAreaLength:-1,hemiLength:-1,numDirectionalShadows:-1,numPointShadows:-1,numSpotShadows:-1},ambient:[0,0,0],probe:[],directional:[],directionalShadowMap:[],directionalShadowMatrix:[],spot:[],spotShadowMap:[],spotShadowMatrix:[],rectArea:[],point:[],pointShadowMap:[],pointShadowMatrix:[],hemi:[],numDirectionalShadows:-1,numPointShadows:-1,numSpotShadows:-1},n=0;n<9;n++)t.probe.push(new En);var r=new En,i=new Gn,o=new Gn;return{setup:function(n,a,s){for(var c=0,l=0,u=0,h=0;h<9;h++)t.probe[h].set(0,0,0);var d=0,p=0,f=0,m=0,g=0,v=0,y=0,b=0,_=s.matrixWorldInverse;n.sort($a),h=0;for(var x=n.length;h\\nvoid main() {\\n float mean = 0.0;\\n float squared_mean = 0.0;\\n \\n\\tfloat depth = unpackRGBAToDepth( texture2D( shadow_pass, ( gl_FragCoord.xy ) / resolution ) );\\n for ( float i = -1.0; i < 1.0 ; i += SAMPLE_RATE) {\\n #ifdef HORIZONAL_PASS\\n vec2 distribution = decodeHalfRGBA ( texture2D( shadow_pass, ( gl_FragCoord.xy + vec2( i, 0.0 ) * radius ) / resolution ) );\\n mean += distribution.x;\\n squared_mean += distribution.y * distribution.y + distribution.x * distribution.x;\\n #else\\n float depth = unpackRGBAToDepth( texture2D( shadow_pass, ( gl_FragCoord.xy + vec2( 0.0, i ) * radius ) / resolution ) );\\n mean += depth;\\n squared_mean += depth * depth;\\n #endif\\n }\\n mean = mean * HALF_SAMPLE_RATE;\\n squared_mean = squared_mean * HALF_SAMPLE_RATE;\\n float std_dev = pow( squared_mean - mean * mean, 0.5 );\\n gl_FragColor = encodeHalfRGBA( vec2( mean, std_dev ) );\\n}",as="void main() {\\n\\tgl_Position = vec4( position, 1.0 );\\n}";function ss(e,t,n){var r=new ho,i=new _n,o=new _n,a=new Pn,s=[],c=[],l={},u={0:v,1:g,2:y},h=new to({defines:{SAMPLE_RATE:.25,HALF_SAMPLE_RATE:1/8},uniforms:{shadow_pass:{value:null},resolution:{value:new _n},radius:{value:4}},vertexShader:as,fragmentShader:os}),d=h.clone();d.defines.HORIZONAL_PASS=1;var f=new wi;f.setAttribute("position",new ri(new Float32Array([-1,-1,.5,3,-1,.5,-1,3,.5]),3));var b=new zi(f,h),_=this;function x(n,r){var i=t.update(b);h.uniforms.shadow_pass.value=n.map.texture,h.uniforms.resolution.value=n.mapSize,h.uniforms.radius.value=n.radius,e.setRenderTarget(n.mapPass),e.clear(),e.renderBufferDirect(r,null,i,h,b,null),d.uniforms.shadow_pass.value=n.mapPass.texture,d.uniforms.resolution.value=n.mapSize,d.uniforms.radius.value=n.radius,e.setRenderTarget(n.map),e.clear(),e.renderBufferDirect(r,null,i,d,b,null)}function w(e,t,n){var r=e<<0|t<<1|n<<2,i=s[r];return void 0===i&&(i=new rs({depthPacking:Gt,morphTargets:e,skinning:t}),s[r]=i),i}function M(e,t,n){var r=e<<0|t<<1|n<<2,i=c[r];return void 0===i&&(i=new is({morphTargets:e,skinning:t}),c[r]=i),i}function T(t,n,r,i,o,a){var s=t.geometry,c=null,h=w,d=t.customDepthMaterial;if(!0===r.isPointLight&&(h=M,d=t.customDistanceMaterial),void 0===d){var p=!1;!0===n.morphTargets&&(!0===s.isBufferGeometry?p=s.morphAttributes&&s.morphAttributes.position&&s.morphAttributes.position.length>0:!0===s.isGeometry&&(p=s.morphTargets&&s.morphTargets.length>0));var f=!1;!0===t.isSkinnedMesh&&(!0===n.skinning?f=!0:console.warn("THREE.WebGLShadowMap: THREE.SkinnedMesh with material.skinning set to false:",t)),c=h(p,f,!0===t.isInstancedMesh)}else c=d;if(e.localClippingEnabled&&!0===n.clipShadows&&0!==n.clippingPlanes.length){var g=c.uuid,v=n.uuid,y=l[g];void 0===y&&(y={},l[g]=y);var b=y[v];void 0===b&&(b=c.clone(),y[v]=b),c=b}return c.visible=n.visible,c.wireframe=n.wireframe,c.side=a===m?null!==n.shadowSide?n.shadowSide:n.side:null!==n.shadowSide?n.shadowSide:u[n.side],c.clipShadows=n.clipShadows,c.clippingPlanes=n.clippingPlanes,c.clipIntersection=n.clipIntersection,c.wireframeLinewidth=n.wireframeLinewidth,c.linewidth=n.linewidth,!0===r.isPointLight&&!0===c.isMeshDistanceMaterial&&(c.referencePosition.setFromMatrixPosition(r.matrixWorld),c.nearDistance=i,c.farDistance=o),c}function S(n,i,o,a,s){if(!1!==n.visible){if(n.layers.test(i.layers)&&(n.isMesh||n.isLine||n.isPoints)&&(n.castShadow||n.receiveShadow&&s===m)&&(!n.frustumCulled||r.intersectsObject(n))){n.modelViewMatrix.multiplyMatrices(o.matrixWorldInverse,n.matrixWorld);var c=t.update(n),l=n.material;if(Array.isArray(l))for(var u=c.groups,h=0,d=u.length;hn||i.y>n)&&(console.warn("THREE.WebGLShadowMap:",g,"has shadow exceeding max texture size, reducing"),i.x>n&&(o.x=Math.floor(n/y.x),i.x=o.x*y.x,v.mapSize.x=o.x),i.y>n&&(o.y=Math.floor(n/y.y),i.y=o.y*y.y,v.mapSize.y=o.y)),null===v.map&&!v.isPointLightShadow&&this.type===m){var b={minFilter:Te,magFilter:Te,format:Ve};v.map=new On(i.x,i.y,b),v.map.texture.name=g.name+".shadowMap",v.mapPass=new On(i.x,i.y,b),v.camera.updateProjectionMatrix()}if(null===v.map){b={minFilter:_e,magFilter:_e,format:Ve};v.map=new On(i.x,i.y,b),v.map.texture.name=g.name+".shadowMap",v.camera.updateProjectionMatrix()}e.setRenderTarget(v.map),e.clear();for(var w=v.getViewportCount(),M=0;M=1):-1!==he.indexOf("OpenGL ES")&&(ue=parseFloat(/^OpenGL\\ ES\\ ([0-9])/.exec(he)[1]),le=ue>=2);var de=null,pe={},fe=new Pn,me=new Pn;function ge(t,n,r){var i=new Uint8Array(4),o=e.createTexture();e.bindTexture(t,o),e.texParameteri(t,10241,9728),e.texParameteri(t,10240,9728);for(var a=0;ar||e.height>r)&&(i=r/Math.max(e.width,e.height)),i<1||!0===t){if("undefined"!=typeof HTMLImageElement&&e instanceof HTMLImageElement||"undefined"!=typeof HTMLCanvasElement&&e instanceof HTMLCanvasElement||"undefined"!=typeof ImageBitmap&&e instanceof ImageBitmap){var o=t?bn.floorPowerOfTwo:Math.floor,a=o(i*e.width),c=o(i*e.height);void 0===s&&(s=m(a,c));var l=n?m(a,c):s;return l.width=a,l.height=c,l.getContext("2d").drawImage(e,0,0,a,c),console.warn("THREE.WebGLRenderer: Texture has been resized from ("+e.width+"x"+e.height+") to ("+a+"x"+c+")."),l}return"data"in e&&console.warn("THREE.WebGLRenderer: Image in DataTexture is too big ("+e.width+"x"+e.height+")."),e}return e}function v(e){return bn.isPowerOfTwo(e.width)&&bn.isPowerOfTwo(e.height)}function y(e,t){return e.generateMipmaps&&t&&e.minFilter!==_e&&e.minFilter!==Te}function b(t,n,i,o){e.generateMipmap(t),r.get(n).__maxMipLevel=Math.log(Math.max(i,o))*Math.LOG2E}function _(e,n){if(!1===c)return e;var r=e;return 6403===e&&(5126===n&&(r=33326),5131===n&&(r=33325),5121===n&&(r=33321)),6407===e&&(5126===n&&(r=34837),5131===n&&(r=34843),5121===n&&(r=32849)),6408===e&&(5126===n&&(r=34836),5131===n&&(r=34842),5121===n&&(r=32856)),33325===r||33326===r||34842===r||34836===r?t.get("EXT_color_buffer_float"):34843!==r&&34837!==r||console.warn("THREE.WebGLRenderer: Floating point textures with RGB format not supported. Please use RGBA instead."),r}function x(e){return e===_e||e===xe||e===Me?9728:9729}function w(t){var n=t.target;n.removeEventListener("dispose",w),function(t){var n=r.get(t);if(void 0===n.__webglInit)return;e.deleteTexture(n.__webglTexture),r.remove(t)}(n),n.isVideoTexture&&p.delete(n),a.memory.textures--}function M(t){var n=t.target;n.removeEventListener("dispose",M),function(t){var n=r.get(t),i=r.get(t.texture);if(!t)return;void 0!==i.__webglTexture&&e.deleteTexture(i.__webglTexture);t.depthTexture&&t.depthTexture.dispose();if(t.isWebGLRenderTargetCube)for(var o=0;o<6;o++)e.deleteFramebuffer(n.__webglFramebuffer[o]),n.__webglDepthbuffer&&e.deleteRenderbuffer(n.__webglDepthbuffer[o]);else e.deleteFramebuffer(n.__webglFramebuffer),n.__webglDepthbuffer&&e.deleteRenderbuffer(n.__webglDepthbuffer);if(t.isWebGLMultiviewRenderTarget){e.deleteTexture(n.__webglColorTexture),e.deleteTexture(n.__webglDepthStencilTexture),a.memory.textures-=2;o=0;for(var s=n.__webglViewFramebuffers.length;o0&&i.__version!==e.version){var o=e.image;if(void 0===o)console.warn("THREE.WebGLRenderer: Texture marked for update but image is undefined");else{if(!1!==o.complete)return void O(i,e,t);console.warn("THREE.WebGLRenderer: Texture marked for update but image is incomplete")}}n.activeTexture(33984+t),n.bindTexture(3553,i.__webglTexture)}function S(t,i){if(6===t.image.length){var a=r.get(t);if(t.version>0&&a.__version!==t.version){P(a,t),n.activeTexture(33984+i),n.bindTexture(34067,a.__webglTexture),e.pixelStorei(37440,t.flipY);for(var s=t&&t.isCompressedTexture,l=t.image[0]&&t.image[0].isDataTexture,h=[],d=0;d<6;d++)h[d]=s||l?l?t.image[d].image:t.image[d]:g(t.image[d],!1,!0,u);var p,f=h[0],m=v(f)||c,x=o.convert(t.format),w=o.convert(t.type),M=_(x,w);if(R(34067,t,m),s){for(d=0;d<6;d++){p=h[d].mipmaps;for(var E=0;E1||r.get(o).__currentAnisotropy)&&(e.texParameterf(n,s.TEXTURE_MAX_ANISOTROPY_EXT,Math.min(o.anisotropy,i.getMaxAnisotropy())),r.get(o).__currentAnisotropy=o.anisotropy)}}function P(t,n){void 0===t.__webglInit&&(t.__webglInit=!0,n.addEventListener("dispose",w),t.__webglTexture=e.createTexture(),a.memory.textures++)}function O(t,r,i){var a=3553;r.isDataTexture2DArray&&(a=35866),r.isDataTexture3D&&(a=32879),P(t,r),n.activeTexture(33984+i),n.bindTexture(a,t.__webglTexture),e.pixelStorei(37440,r.flipY),e.pixelStorei(37441,r.premultiplyAlpha),e.pixelStorei(3317,r.unpackAlignment);var s=function(e){return!c&&(e.wrapS!==ye||e.wrapT!==ye||e.minFilter!==_e&&e.minFilter!==Te)}(r)&&!1===v(r.image),l=g(r.image,s,!1,h),u=v(l)||c,d=o.convert(r.format),p=o.convert(r.type),f=_(d,p);R(a,r,u);var m,x=r.mipmaps;if(r.isDepthTexture){if(f=6402,r.type===Be){if(!1===c)throw new Error("Float Depth Texture only supported in WebGL2.0");f=36012}else c&&(f=33189);r.format===Xe&&6402===f&&r.type!==Ne&&r.type!==De&&(console.warn("THREE.WebGLRenderer: Use UnsignedShortType or UnsignedIntType for DepthFormat DepthTexture."),r.type=Ne,p=o.convert(r.type)),r.format===Je&&(f=34041,r.type!==Ge&&(console.warn("THREE.WebGLRenderer: Use UnsignedInt248Type for DepthStencilFormat DepthTexture."),r.type=Ge,p=o.convert(r.type))),n.texImage2D(3553,0,f,l.width,l.height,0,d,p,null)}else if(r.isDataTexture)if(x.length>0&&u){for(var w=0,M=x.length;w0&&u){for(w=0,M=x.length;w=l&&console.warn("THREE.WebGLTextures: Trying to use "+e+" texture units while this GPU supports only "+l),E+=1,e},this.resetTextureUnits=function(){E=0},this.setTexture2D=T,this.setTexture2DArray=function(e,t){var i=r.get(e);e.version>0&&i.__version!==e.version?O(i,e,t):(n.activeTexture(33984+t),n.bindTexture(35866,i.__webglTexture))},this.setTexture3D=function(e,t){var i=r.get(e);e.version>0&&i.__version!==e.version?O(i,e,t):(n.activeTexture(33984+t),n.bindTexture(32879,i.__webglTexture))},this.setTextureCube=S,this.setTextureCubeDynamic=A,this.setupRenderTarget=function(i){var s=r.get(i),l=r.get(i.texture);i.addEventListener("dispose",M),l.__webglTexture=e.createTexture(),a.memory.textures++;var u=!0===i.isWebGLRenderTargetCube,h=!0===i.isWebGLMultisampleRenderTarget,d=!0===i.isWebGLMultiviewRenderTarget,p=v(i)||c;if(u){s.__webglFramebuffer=[];for(var f=0;f<6;f++)s.__webglFramebuffer[f]=e.createFramebuffer()}else if(s.__webglFramebuffer=e.createFramebuffer(),h)if(c){s.__webglMultisampledFramebuffer=e.createFramebuffer(),s.__webglColorRenderbuffer=e.createRenderbuffer(),e.bindRenderbuffer(36161,s.__webglColorRenderbuffer);var m=_(o.convert(i.texture.format),o.convert(i.texture.type)),g=B(i);e.renderbufferStorageMultisample(36161,g,m,i.width,i.height),e.bindFramebuffer(36160,s.__webglMultisampledFramebuffer),e.framebufferRenderbuffer(36160,36064,36161,s.__webglColorRenderbuffer),e.bindRenderbuffer(36161,null),i.depthBuffer&&(s.__webglDepthRenderbuffer=e.createRenderbuffer(),I(s.__webglDepthRenderbuffer,i,!0)),e.bindFramebuffer(36160,null)}else console.warn("THREE.WebGLRenderer: WebGLMultisampleRenderTarget can only be used with WebGL2.");else if(d){var x=i.width,w=i.height,E=i.numViews;e.bindFramebuffer(36160,s.__webglFramebuffer);var T=t.get("OVR_multiview2");a.memory.textures+=2;var S=e.createTexture();e.bindTexture(35866,S),e.texParameteri(35866,10240,9728),e.texParameteri(35866,10241,9728),e.texImage3D(35866,0,32856,x,w,E,0,6408,5121,null),T.framebufferTextureMultiviewOVR(36160,36064,S,0,0,E);var A=e.createTexture();e.bindTexture(35866,A),e.texParameteri(35866,10240,9728),e.texParameteri(35866,10241,9728),e.texImage3D(35866,0,35056,x,w,E,0,34041,34042,null),T.framebufferTextureMultiviewOVR(36160,33306,A,0,0,E);var L=new Array(E);for(f=0;fd)return!1;for(var n=1,r=t.length;n=0){var l=i[s];if(void 0!==l){var u=l.normalized,h=l.itemSize;if(void 0===(M=x.get(l)))continue;var d=M.buffer,v=M.type,y=M.bytesPerElement;if(l.isInterleavedBufferAttribute){var b=l.data,_=b.stride,w=l.offset;b&&b.isInstancedInterleavedBuffer?(g.enableAttributeAndDivisor(c,b.meshPerAttribute),void 0===t.maxInstancedCount&&(t.maxInstancedCount=b.meshPerAttribute*b.count)):g.enableAttribute(c),p.bindBuffer(34962,d),p.vertexAttribPointer(c,h,v,u,_*y,w*y)}else l.isInstancedBufferAttribute?(g.enableAttributeAndDivisor(c,l.meshPerAttribute),void 0===t.maxInstancedCount&&(t.maxInstancedCount=l.meshPerAttribute*l.count)):g.enableAttribute(c),p.bindBuffer(34962,d),p.vertexAttribPointer(c,h,v,u,0,0)}else if("instanceMatrix"===s){var M;if(void 0===(M=x.get(e.instanceMatrix)))continue;d=M.buffer,v=M.type;g.enableAttributeAndDivisor(c+0,1),g.enableAttributeAndDivisor(c+1,1),g.enableAttributeAndDivisor(c+2,1),g.enableAttributeAndDivisor(c+3,1),p.bindBuffer(34962,d),p.vertexAttribPointer(c+0,4,v,!1,64,0),p.vertexAttribPointer(c+1,4,v,!1,64,16),p.vertexAttribPointer(c+2,4,v,!1,64,32),p.vertexAttribPointer(c+3,4,v,!1,64,48)}else if(void 0!==a){var E=a[s];if(void 0!==E)switch(E.length){case 2:p.vertexAttrib2fv(c,E);break;case 3:p.vertexAttrib3fv(c,E);break;case 4:p.vertexAttrib4fv(c,E);break;default:p.vertexAttrib1fv(c,E)}}}}g.disableUnusedAttributes()}(i,n,r,s),null!==u&&p.bindBuffer(34963,l.buffer));var y=1/0;null!==u?y=u.count:void 0!==h&&(y=h.count);var b=n.drawRange.start*d,_=n.drawRange.count*d,M=null!==o?o.start*d:0,E=null!==o?o.count*d:1/0,T=Math.max(b,M),S=Math.min(y,b+_,M+E)-1,A=Math.max(0,S-T+1);if(0!==A){if(i.isMesh)if(!0===r.wireframe)g.setLineWidth(r.wireframeLinewidth*oe()),v.setMode(1);else switch(i.drawMode){case Ct:v.setMode(4);break;case Rt:v.setMode(5);break;case Pt:v.setMode(6)}else if(i.isLine){var P=r.linewidth;void 0===P&&(P=1),g.setLineWidth(P*oe()),i.isLineSegments?v.setMode(1):i.isLineLoop?v.setMode(2):v.setMode(3)}else i.isPoints?v.setMode(0):i.isSprite&&v.setMode(4);i.isInstancedMesh?v.renderInstances(n,T,A,i.count):n.isInstancedBufferGeometry?v.renderInstances(n,T,A,n.maxInstancedCount):v.render(T,A)}},this.compile=function(e,t){(d=S.get(e,t)).init(),e.traverse((function(e){e.isLight&&(d.pushLight(e),e.castShadow&&d.pushShadow(e))})),d.setupLights(t),e.traverse((function(t){if(t.material)if(Array.isArray(t.material))for(var n=0;n=0&&e.numSupportedMorphTargets++}if(e.morphNormals){e.numSupportedMorphNormals=0;for(f=0;f=0&&e.numSupportedMorphNormals++}var m=r.shader.uniforms;(e.isShaderMaterial||e.isRawShaderMaterial)&&!0!==e.clipping||(r.numClippingPlanes=$.numPlanes,r.numIntersection=$.numIntersection,m.clippingPlanes=$.uniform),r.fog=t,r.needsLights=function(e){return e.isMeshLambertMaterial||e.isMeshPhongMaterial||e.isMeshStandardMaterial||e.isShadowMaterial||e.isShaderMaterial&&!0===e.lights}(e),r.lightsStateVersion=a,r.needsLights&&(m.ambientLightColor.value=i.state.ambient,m.lightProbe.value=i.state.probe,m.directionalLights.value=i.state.directional,m.spotLights.value=i.state.spot,m.rectAreaLights.value=i.state.rectArea,m.pointLights.value=i.state.point,m.hemisphereLights.value=i.state.hemi,m.directionalShadowMap.value=i.state.directionalShadowMap,m.directionalShadowMatrix.value=i.state.directionalShadowMatrix,m.spotShadowMap.value=i.state.spotShadowMap,m.spotShadowMatrix.value=i.state.spotShadowMatrix,m.pointShadowMap.value=i.state.pointShadowMap,m.pointShadowMatrix.value=i.state.pointShadowMatrix);var g=r.program.getUniforms(),v=Aa.seqWithValue(g.seq,m);r.uniformsList=v}function xe(e,t,n,r){_.resetTextureUnits();var i=b.get(n),o=d.state.lights;if(ee&&(te||e!==G)){var a=e===G&&n.id===F;$.setState(n.clippingPlanes,n.clipIntersection,n.clipShadows,e,i,a)}!1===n.needsUpdate&&(void 0===i.program?n.needsUpdate=!0:n.fog&&i.fog!==t?n.needsUpdate=!0:i.needsLights&&i.lightsStateVersion!==o.state.version?n.needsUpdate=!0:void 0===i.numClippingPlanes||i.numClippingPlanes===$.numPlanes&&i.numIntersection===$.numIntersection||(n.needsUpdate=!0)),n.needsUpdate&&(_e(n,t,r),n.needsUpdate=!1);var s,c,l=!1,u=!1,h=!1,f=i.program,y=f.getUniforms(),x=i.shader.uniforms;if(g.useProgram(f.program)&&(l=!0,u=!0,h=!0),n.id!==F&&(F=n.id,u=!0),l||G!==e){if(f.numMultiviewViews>0?le.updateCameraProjectionMatricesUniform(e,y):y.setValue(p,"projectionMatrix",e.projectionMatrix),m.logarithmicDepthBuffer&&y.setValue(p,"logDepthBufFC",2/(Math.log(e.far+1)/Math.LN2)),G!==e&&(G=e,u=!0,h=!0),n.isShaderMaterial||n.isMeshPhongMaterial||n.isMeshStandardMaterial||n.envMap){var w=y.map.cameraPosition;void 0!==w&&w.setValue(p,re.setFromMatrixPosition(e.matrixWorld))}(n.isMeshPhongMaterial||n.isMeshLambertMaterial||n.isMeshBasicMaterial||n.isMeshStandardMaterial||n.isShaderMaterial)&&y.setValue(p,"isOrthographic",!0===e.isOrthographicCamera),(n.isMeshPhongMaterial||n.isMeshLambertMaterial||n.isMeshBasicMaterial||n.isMeshStandardMaterial||n.isShaderMaterial||n.skinning)&&(f.numMultiviewViews>0?le.updateCameraViewMatricesUniform(e,y):y.setValue(p,"viewMatrix",e.matrixWorldInverse))}if(n.skinning){y.setOptional(p,r,"bindMatrix"),y.setOptional(p,r,"bindMatrixInverse");var M=r.skeleton;if(M){var E=M.bones;if(m.floatVertexTextures){if(void 0===M.boneTexture){var T=Math.sqrt(4*E.length);T=bn.ceilPowerOfTwo(T),T=Math.max(T,4);var S=new Float32Array(T*T*4);S.set(M.boneMatrices);var A=new co(S,T,T,Ve,Be);M.boneMatrices=S,M.boneTexture=A,M.boneTextureSize=T}y.setValue(p,"boneTexture",M.boneTexture,_),y.setValue(p,"boneTextureSize",M.boneTextureSize)}else y.setOptional(p,M,"boneMatrices")}}return(u||i.receiveShadow!==r.receiveShadow)&&(i.receiveShadow=r.receiveShadow,y.setValue(p,"receiveShadow",r.receiveShadow)),u&&(y.setValue(p,"toneMappingExposure",O.toneMappingExposure),y.setValue(p,"toneMappingWhitePoint",O.toneMappingWhitePoint),i.needsLights&&(c=h,(s=x).ambientLightColor.needsUpdate=c,s.lightProbe.needsUpdate=c,s.directionalLights.needsUpdate=c,s.pointLights.needsUpdate=c,s.spotLights.needsUpdate=c,s.rectAreaLights.needsUpdate=c,s.hemisphereLights.needsUpdate=c),t&&n.fog&&function(e,t){e.fogColor.value.copy(t.color),t.isFog?(e.fogNear.value=t.near,e.fogFar.value=t.far):t.isFogExp2&&(e.fogDensity.value=t.density)}(x,t),n.isMeshBasicMaterial?we(x,n):n.isMeshLambertMaterial?(we(x,n),function(e,t){t.emissiveMap&&(e.emissiveMap.value=t.emissiveMap)}(x,n)):n.isMeshPhongMaterial?(we(x,n),n.isMeshToonMaterial?function(e,t){Me(e,t),t.gradientMap&&(e.gradientMap.value=t.gradientMap)}(x,n):Me(x,n)):n.isMeshStandardMaterial?(we(x,n),n.isMeshPhysicalMaterial?function(e,t){Ee(e,t),e.reflectivity.value=t.reflectivity,e.clearcoat.value=t.clearcoat,e.clearcoatRoughness.value=t.clearcoatRoughness,t.sheen&&e.sheen.value.copy(t.sheen);t.clearcoatNormalMap&&(e.clearcoatNormalScale.value.copy(t.clearcoatNormalScale),e.clearcoatNormalMap.value=t.clearcoatNormalMap,t.side===v&&e.clearcoatNormalScale.value.negate());e.transparency.value=t.transparency}(x,n):Ee(x,n)):n.isMeshMatcapMaterial?(we(x,n),function(e,t){t.matcap&&(e.matcap.value=t.matcap);t.bumpMap&&(e.bumpMap.value=t.bumpMap,e.bumpScale.value=t.bumpScale,t.side===v&&(e.bumpScale.value*=-1));t.normalMap&&(e.normalMap.value=t.normalMap,e.normalScale.value.copy(t.normalScale),t.side===v&&e.normalScale.value.negate());t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias)}(x,n)):n.isMeshDepthMaterial?(we(x,n),function(e,t){t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias)}(x,n)):n.isMeshDistanceMaterial?(we(x,n),function(e,t){t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias);e.referencePosition.value.copy(t.referencePosition),e.nearDistance.value=t.nearDistance,e.farDistance.value=t.farDistance}(x,n)):n.isMeshNormalMaterial?(we(x,n),function(e,t){t.bumpMap&&(e.bumpMap.value=t.bumpMap,e.bumpScale.value=t.bumpScale,t.side===v&&(e.bumpScale.value*=-1));t.normalMap&&(e.normalMap.value=t.normalMap,e.normalScale.value.copy(t.normalScale),t.side===v&&e.normalScale.value.negate());t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias)}(x,n)):n.isLineBasicMaterial?(function(e,t){e.diffuse.value.copy(t.color),e.opacity.value=t.opacity}(x,n),n.isLineDashedMaterial&&function(e,t){e.dashSize.value=t.dashSize,e.totalSize.value=t.dashSize+t.gapSize,e.scale.value=t.scale}(x,n)):n.isPointsMaterial?function(e,t){e.diffuse.value.copy(t.color),e.opacity.value=t.opacity,e.size.value=t.size*X,e.scale.value=.5*Y,t.map&&(e.map.value=t.map);t.alphaMap&&(e.alphaMap.value=t.alphaMap);var n;t.map?n=t.map:t.alphaMap&&(n=t.alphaMap);void 0!==n&&(!0===n.matrixAutoUpdate&&n.updateMatrix(),e.uvTransform.value.copy(n.matrix))}(x,n):n.isSpriteMaterial?function(e,t){e.diffuse.value.copy(t.color),e.opacity.value=t.opacity,e.rotation.value=t.rotation,t.map&&(e.map.value=t.map);t.alphaMap&&(e.alphaMap.value=t.alphaMap);var n;t.map?n=t.map:t.alphaMap&&(n=t.alphaMap);void 0!==n&&(!0===n.matrixAutoUpdate&&n.updateMatrix(),e.uvTransform.value.copy(n.matrix))}(x,n):n.isShadowMaterial&&(x.color.value.copy(n.color),x.opacity.value=n.opacity),void 0!==x.ltc_1&&(x.ltc_1.value=fo.LTC_1),void 0!==x.ltc_2&&(x.ltc_2.value=fo.LTC_2),Aa.upload(p,i.uniformsList,x,_),n.isShaderMaterial&&(n.uniformsNeedUpdate=!1)),n.isShaderMaterial&&!0===n.uniformsNeedUpdate&&(Aa.upload(p,i.uniformsList,x,_),n.uniformsNeedUpdate=!1),n.isSpriteMaterial&&y.setValue(p,"center",r.center),f.numMultiviewViews>0?le.updateObjectMatricesUniforms(r,e,y):(y.setValue(p,"modelViewMatrix",r.modelViewMatrix),y.setValue(p,"normalMatrix",r.normalMatrix)),y.setValue(p,"modelMatrix",r.matrixWorld),f}function we(e,t){var n;e.opacity.value=t.opacity,t.color&&e.diffuse.value.copy(t.color),t.emissive&&e.emissive.value.copy(t.emissive).multiplyScalar(t.emissiveIntensity),t.map&&(e.map.value=t.map),t.alphaMap&&(e.alphaMap.value=t.alphaMap),t.specularMap&&(e.specularMap.value=t.specularMap),t.envMap&&(e.envMap.value=t.envMap,e.flipEnvMap.value=t.envMap.isCubeTexture?-1:1,e.reflectivity.value=t.reflectivity,e.refractionRatio.value=t.refractionRatio,e.maxMipLevel.value=b.get(t.envMap).__maxMipLevel),t.lightMap&&(e.lightMap.value=t.lightMap,e.lightMapIntensity.value=t.lightMapIntensity),t.aoMap&&(e.aoMap.value=t.aoMap,e.aoMapIntensity.value=t.aoMapIntensity),t.map?n=t.map:t.specularMap?n=t.specularMap:t.displacementMap?n=t.displacementMap:t.normalMap?n=t.normalMap:t.bumpMap?n=t.bumpMap:t.roughnessMap?n=t.roughnessMap:t.metalnessMap?n=t.metalnessMap:t.alphaMap?n=t.alphaMap:t.emissiveMap&&(n=t.emissiveMap),void 0!==n&&(n.isWebGLRenderTarget&&(n=n.texture),!0===n.matrixAutoUpdate&&n.updateMatrix(),e.uvTransform.value.copy(n.matrix))}function Me(e,t){e.specular.value.copy(t.specular),e.shininess.value=Math.max(t.shininess,1e-4),t.emissiveMap&&(e.emissiveMap.value=t.emissiveMap),t.bumpMap&&(e.bumpMap.value=t.bumpMap,e.bumpScale.value=t.bumpScale,t.side===v&&(e.bumpScale.value*=-1)),t.normalMap&&(e.normalMap.value=t.normalMap,e.normalScale.value.copy(t.normalScale),t.side===v&&e.normalScale.value.negate()),t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias)}function Ee(e,t){e.roughness.value=t.roughness,e.metalness.value=t.metalness,t.roughnessMap&&(e.roughnessMap.value=t.roughnessMap),t.metalnessMap&&(e.metalnessMap.value=t.metalnessMap),t.emissiveMap&&(e.emissiveMap.value=t.emissiveMap),t.bumpMap&&(e.bumpMap.value=t.bumpMap,e.bumpScale.value=t.bumpScale,t.side===v&&(e.bumpScale.value*=-1)),t.normalMap&&(e.normalMap.value=t.normalMap,e.normalScale.value.copy(t.normalScale),t.side===v&&e.normalScale.value.negate()),t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias),t.envMap&&(e.envMapIntensity.value=t.envMapIntensity)}ge.setAnimationLoop((function(e){ce.isPresenting()||me&&me(e)})),"undefined"!=typeof window&&ge.setContext(window),this.setAnimationLoop=function(e){me=e,ce.setAnimationLoop(e),ge.start()},this.render=function(e,t){var n,r;if(void 0!==arguments[2]&&(console.warn("THREE.WebGLRenderer.render(): the renderTarget argument has been removed. Use .setRenderTarget() instead."),n=arguments[2]),void 0!==arguments[3]&&(console.warn("THREE.WebGLRenderer.render(): the forceClear argument has been removed. Use .clear() instead."),r=arguments[3]),t&&t.isCamera){if(!N){z.geometry=null,z.program=null,z.wireframe=!1,F=-1,G=null,!0===e.autoUpdate&&e.updateMatrixWorld(),null===t.parent&&t.updateMatrixWorld(),ce.enabled&&(t=ce.getCamera(t)),(d=S.get(e,t)).init(),e.onBeforeRender(O,e,t,n||k),ne.multiplyMatrices(t.projectionMatrix,t.matrixWorldInverse),Q.setFromMatrix(ne),te=this.localClippingEnabled,ee=$.init(this.clippingPlanes,te,t),(h=T.get(e,t)).init(),ve(e,t,0,O.sortObjects),!0===O.sortObjects&&h.sort(),ee&&$.beginShadows();var i=d.state.shadowsArray;ue.render(i,e,t),d.setupLights(t),ee&&$.endShadows(),this.info.autoReset&&this.info.reset(),void 0!==n&&this.setRenderTarget(n),ce.enabled&&le.isAvailable()&&le.attachCamera(t),A.render(h,e,t,r);var o=h.opaque,a=h.transparent;if(e.overrideMaterial){var s=e.overrideMaterial;o.length&&ye(o,e,t,s),a.length&&ye(a,e,t,s)}else o.length&&ye(o,e,t),a.length&&ye(a,e,t);e.onAfterRender(O,e,t),null!==k&&(_.updateRenderTargetMipmap(k),_.updateMultisampleRenderTarget(k)),g.buffers.depth.setTest(!0),g.buffers.depth.setMask(!0),g.buffers.color.setMask(!0),g.setPolygonOffset(!1),ce.enabled&&(le.isAvailable()&&le.detachCamera(t),ce.submitFrame()),h=null,d=null}}else console.error("THREE.WebGLRenderer.render: camera is not an instance of THREE.Camera.")},this.setFramebuffer=function(e){I!==e&&null===k&&p.bindFramebuffer(36160,e),I=e},this.getActiveCubeFace=function(){return D},this.getActiveMipmapLevel=function(){return B},this.getRenderTarget=function(){return k},this.setRenderTarget=function(e,t,n){k=e,D=t,B=n,e&&void 0===b.get(e).__webglFramebuffer&&_.setupRenderTarget(e);var r=I,i=!1;if(e){var o=b.get(e).__webglFramebuffer;e.isWebGLRenderTargetCube?(r=o[t||0],i=!0):r=e.isWebGLMultisampleRenderTarget?b.get(e).__webglMultisampledFramebuffer:o,j.copy(e.viewport),V.copy(e.scissor),W=e.scissorTest}else j.copy(J).multiplyScalar(X).floor(),V.copy(Z).multiplyScalar(X).floor(),W=K;if(U!==r&&(p.bindFramebuffer(36160,r),U=r),g.viewport(j),g.scissor(V),g.setScissorTest(W),i){var a=b.get(e.texture);p.framebufferTexture2D(36160,36064,34069+(t||0),a.__webglTexture,n||0)}},this.readRenderTargetPixels=function(e,t,n,r,i,o,a){if(e&&e.isWebGLRenderTarget){var s=b.get(e).__webglFramebuffer;if(e.isWebGLRenderTargetCube&&void 0!==a&&(s=s[a]),s){var c=!1;s!==U&&(p.bindFramebuffer(36160,s),c=!0);try{var l=e.texture,u=l.format,h=l.type;if(u!==Ve&&P.convert(u)!==p.getParameter(35739))return void console.error("THREE.WebGLRenderer.readRenderTargetPixels: renderTarget is not in RGBA or implementation defined format.");if(!(h===Re||P.convert(h)===p.getParameter(35738)||h===Be&&(m.isWebGL2||f.get("OES_texture_float")||f.get("WEBGL_color_buffer_float"))||h===ke&&(m.isWebGL2?f.get("EXT_color_buffer_float"):f.get("EXT_color_buffer_half_float"))))return void console.error("THREE.WebGLRenderer.readRenderTargetPixels: renderTarget is not in UnsignedByteType or implementation defined type.");36053===p.checkFramebufferStatus(36160)?t>=0&&t<=e.width-r&&n>=0&&n<=e.height-i&&p.readPixels(t,n,r,i,P.convert(u),P.convert(h),o):console.error("THREE.WebGLRenderer.readRenderTargetPixels: readPixels from renderTarget failed. Framebuffer not complete.")}finally{c&&p.bindFramebuffer(36160,U)}}}else console.error("THREE.WebGLRenderer.readRenderTargetPixels: renderTarget is not THREE.WebGLRenderTarget.")},this.copyFramebufferToTexture=function(e,t,n){void 0===n&&(n=0);var r=Math.pow(2,-n),i=Math.floor(t.image.width*r),o=Math.floor(t.image.height*r),a=P.convert(t.format);_.setTexture2D(t,0),p.copyTexImage2D(3553,n,a,e.x,e.y,i,o,0),g.unbindTexture()},this.copyTextureToTexture=function(e,t,n,r){var i=t.image.width,o=t.image.height,a=P.convert(n.format),s=P.convert(n.type);_.setTexture2D(n,0),t.isDataTexture?p.texSubImage2D(3553,r||0,e.x,e.y,i,o,a,s,t.image.data):p.texSubImage2D(3553,r||0,e.x,e.y,a,s,t.image),g.unbindTexture()},this.initTexture=function(e){_.setTexture2D(e,0),g.unbindTexture()},"undefined"!=typeof __THREE_DEVTOOLS__&&__THREE_DEVTOOLS__.dispatchEvent(new CustomEvent("observe",{detail:this}))}function ws(e,t){this.name="",this.color=new Jr(e),this.density=void 0!==t?t:25e-5}function Ms(e,t,n){this.name="",this.color=new Jr(e),this.near=void 0!==t?t:1,this.far=void 0!==n?n:1e3}function Es(e,t){this.array=e,this.stride=t,this.count=void 0!==e?e.length/t:0,this.usage=sn,this.updateRange={offset:0,count:-1},this.version=0}function Ts(e,t,n,r){this.data=e,this.itemSize=t,this.offset=n,this.normalized=!0===r}function Ss(e){ti.call(this),this.type="SpriteMaterial",this.color=new Jr(16777215),this.map=null,this.alphaMap=null,this.rotation=0,this.sizeAttenuation=!0,this.transparent=!0,this.setValues(e)}Object.assign(bs.prototype,gn.prototype),Object.assign(_s.prototype,gn.prototype),Object.assign(ws.prototype,{isFogExp2:!0,clone:function(){return new ws(this.color,this.density)},toJSON:function(){return{type:"FogExp2",color:this.color.getHex(),density:this.density}}}),Object.assign(Ms.prototype,{isFog:!0,clone:function(){return new Ms(this.color,this.near,this.far)},toJSON:function(){return{type:"Fog",color:this.color.getHex(),near:this.near,far:this.far}}}),Object.defineProperty(Es.prototype,"needsUpdate",{set:function(e){!0===e&&this.version++}}),Object.assign(Es.prototype,{isInterleavedBuffer:!0,onUploadCallback:function(){},setUsage:function(e){return this.usage=e,this},copy:function(e){return this.array=new e.array.constructor(e.array),this.count=e.count,this.stride=e.stride,this.usage=e.usage,this},copyAt:function(e,t,n){e*=this.stride,n*=t.stride;for(var r=0,i=this.stride;re.far||t.push({distance:s,point:As.clone(),uv:Wr.getUV(As,Ns,Is,Ds,Bs,ks,Us,new _n),face:null,object:this})}},clone:function(){return new this.constructor(this.material).copy(this)},copy:function(e){return or.prototype.copy.call(this,e),void 0!==e.center&&this.center.copy(e.center),this}});var Gs=new En,Hs=new En;function js(){or.call(this),this.type="LOD",Object.defineProperties(this,{levels:{enumerable:!0,value:[]}}),this.autoUpdate=!0}function Vs(e,t){e&&e.isGeometry&&console.error("THREE.SkinnedMesh no longer supports THREE.Geometry. Use THREE.BufferGeometry instead."),zi.call(this,e,t),this.type="SkinnedMesh",this.bindMode="attached",this.bindMatrix=new Gn,this.bindMatrixInverse=new Gn}js.prototype=Object.assign(Object.create(or.prototype),{constructor:js,isLOD:!0,copy:function(e){or.prototype.copy.call(this,e,!1);for(var t=e.levels,n=0,r=t.length;n1){Gs.setFromMatrixPosition(e.matrixWorld),Hs.setFromMatrixPosition(this.matrixWorld);var n=Gs.distanceTo(Hs);t[0].object.visible=!0;for(var r=1,i=t.length;r=t[r].distance;r++)t[r-1].object.visible=!1,t[r].object.visible=!0;for(;ra))u.applyMatrix4(this.matrixWorld),(x=e.ray.origin.distanceTo(u))e.far||t.push({distance:x,point:l.clone().applyMatrix4(this.matrixWorld),index:m,face:null,faceIndex:null,object:this})}else for(m=0,g=p.length/3-1;ma))u.applyMatrix4(this.matrixWorld),(x=e.ray.origin.distanceTo(u))e.far||t.push({distance:x,point:l.clone().applyMatrix4(this.matrixWorld),index:m,face:null,faceIndex:null,object:this})}}else if(r.isGeometry){var b=r.vertices,_=b.length;for(m=0;m<_-1;m+=h){var x;if(!(ec.distanceSqToSegment(b[m],b[m+1],u,l)>a))u.applyMatrix4(this.matrixWorld),(x=e.ray.origin.distanceTo(u))e.far||t.push({distance:x,point:l.clone().applyMatrix4(this.matrixWorld),index:m,face:null,faceIndex:null,object:this})}}}},clone:function(){return new this.constructor(this.geometry,this.material).copy(this)}});var rc=new En,ic=new En;function oc(e,t){nc.call(this,e,t),this.type="LineSegments"}function ac(e,t){nc.call(this,e,t),this.type="LineLoop"}function sc(e){ti.call(this),this.type="PointsMaterial",this.color=new Jr(16777215),this.map=null,this.alphaMap=null,this.size=1,this.sizeAttenuation=!0,this.morphTargets=!1,this.setValues(e)}oc.prototype=Object.assign(Object.create(nc.prototype),{constructor:oc,isLineSegments:!0,computeLineDistances:function(){var e=this.geometry;if(e.isBufferGeometry)if(null===e.index){for(var t=e.attributes.position,n=[],r=0,i=t.count;ri.far)return;o.push({distance:l,distanceToRay:Math.sqrt(s),point:c,index:t,face:null,object:a})}}function fc(e,t,n,r,i,o,a,s,c){Rn.call(this,e,t,n,r,i,o,a,s,c),this.format=void 0!==a?a:je,this.minFilter=void 0!==o?o:Te,this.magFilter=void 0!==i?i:Te,this.generateMipmaps=!1}function mc(e,t,n,r,i,o,a,s,c,l,u,h){Rn.call(this,null,o,a,s,c,l,r,i,u,h),this.image={width:t,height:n},this.mipmaps=e,this.flipY=!1,this.generateMipmaps=!1}function gc(e,t,n,r,i,o,a,s,c){Rn.call(this,e,t,n,r,i,o,a,s,c),this.needsUpdate=!0}function vc(e,t,n,r,i,o,a,s,c,l){if((l=void 0!==l?l:Xe)!==Xe&&l!==Je)throw new Error("DepthTexture format must be either THREE.DepthFormat or THREE.DepthStencilFormat");void 0===n&&l===Xe&&(n=Ne),void 0===n&&l===Je&&(n=Ge),Rn.call(this,null,r,i,o,a,s,l,n,c),this.image={width:e,height:t},this.magFilter=void 0!==a?a:_e,this.minFilter=void 0!==s?s:_e,this.flipY=!1,this.generateMipmaps=!1}function yc(e){wi.call(this),this.type="WireframeGeometry";var t,n,r,i,o,a,s,c,l,u,h=[],d=[0,0],p={},f=["a","b","c"];if(e&&e.isGeometry){var m=e.faces;for(t=0,r=m.length;t=0?(e(g-1e-5,m,h),d.subVectors(u,h)):(e(g+1e-5,m,h),d.subVectors(h,u)),m-1e-5>=0?(e(g,m-1e-5,h),p.subVectors(u,h)):(e(g,m+1e-5,h),p.subVectors(h,u)),l.crossVectors(d,p).normalize(),s.push(l.x,l.y,l.z),c.push(g,m)}}for(r=0;r.9&&a<.1&&(t<.2&&(o[e+0]+=1),n<.2&&(o[e+2]+=1),r<.2&&(o[e+4]+=1))}}()}(),this.setAttribute("position",new hi(i,3)),this.setAttribute("normal",new hi(i.slice(),3)),this.setAttribute("uv",new hi(o,2)),0===r?this.computeVertexNormals():this.normalizeNormals()}function Mc(e,t){Yi.call(this),this.type="TetrahedronGeometry",this.parameters={radius:e,detail:t},this.fromBufferGeometry(new Ec(e,t)),this.mergeVertices()}function Ec(e,t){wc.call(this,[1,1,1,-1,-1,1,-1,1,-1,1,-1,-1],[2,1,0,0,3,2,1,3,0,2,3,1],e,t),this.type="TetrahedronBufferGeometry",this.parameters={radius:e,detail:t}}function Tc(e,t){Yi.call(this),this.type="OctahedronGeometry",this.parameters={radius:e,detail:t},this.fromBufferGeometry(new Sc(e,t)),this.mergeVertices()}function Sc(e,t){wc.call(this,[1,0,0,-1,0,0,0,1,0,0,-1,0,0,0,1,0,0,-1],[0,2,4,0,4,3,0,3,5,0,5,2,1,2,5,1,5,3,1,3,4,1,4,2],e,t),this.type="OctahedronBufferGeometry",this.parameters={radius:e,detail:t}}function Ac(e,t){Yi.call(this),this.type="IcosahedronGeometry",this.parameters={radius:e,detail:t},this.fromBufferGeometry(new Lc(e,t)),this.mergeVertices()}function Lc(e,t){var n=(1+Math.sqrt(5))/2,r=[-1,n,0,1,n,0,-1,-n,0,1,-n,0,0,-1,n,0,1,n,0,-1,-n,0,1,-n,n,0,-1,n,0,1,-n,0,-1,-n,0,1];wc.call(this,r,[0,11,5,0,5,1,0,1,7,0,7,10,0,10,11,1,5,9,5,11,4,11,10,2,10,7,6,7,1,8,3,9,4,3,4,2,3,2,6,3,6,8,3,8,9,4,9,5,2,4,11,6,2,10,8,6,7,9,8,1],e,t),this.type="IcosahedronBufferGeometry",this.parameters={radius:e,detail:t}}function Cc(e,t){Yi.call(this),this.type="DodecahedronGeometry",this.parameters={radius:e,detail:t},this.fromBufferGeometry(new Rc(e,t)),this.mergeVertices()}function Rc(e,t){var n=(1+Math.sqrt(5))/2,r=1/n,i=[-1,-1,-1,-1,-1,1,-1,1,-1,-1,1,1,1,-1,-1,1,-1,1,1,1,-1,1,1,1,0,-r,-n,0,-r,n,0,r,-n,0,r,n,-r,-n,0,-r,n,0,r,-n,0,r,n,0,-n,0,-r,n,0,-r,-n,0,r,n,0,r];wc.call(this,i,[3,11,7,3,7,15,3,15,13,7,19,17,7,17,6,7,6,15,17,4,8,17,8,10,17,10,6,8,0,16,8,16,2,8,2,10,0,12,1,0,1,18,0,18,16,6,10,2,6,2,13,6,13,15,2,16,18,2,18,3,2,3,13,18,1,9,18,9,11,18,11,3,4,14,12,4,12,0,4,0,8,11,9,5,11,5,19,11,19,7,19,5,14,19,14,4,19,4,17,1,12,14,1,14,5,1,5,9],e,t),this.type="DodecahedronBufferGeometry",this.parameters={radius:e,detail:t}}function Pc(e,t,n,r,i,o){Yi.call(this),this.type="TubeGeometry",this.parameters={path:e,tubularSegments:t,radius:n,radialSegments:r,closed:i},void 0!==o&&console.warn("THREE.TubeGeometry: taper has been removed.");var a=new Oc(e,t,n,r,i);this.tangents=a.tangents,this.normals=a.normals,this.binormals=a.binormals,this.fromBufferGeometry(a),this.mergeVertices()}function Oc(e,t,n,r,i){wi.call(this),this.type="TubeBufferGeometry",this.parameters={path:e,tubularSegments:t,radius:n,radialSegments:r,closed:i},t=t||64,n=n||1,r=r||8,i=i||!1;var o=e.computeFrenetFrames(t,i);this.tangents=o.tangents,this.normals=o.normals,this.binormals=o.binormals;var a,s,c=new En,l=new En,u=new _n,h=new En,d=[],p=[],f=[],m=[];function g(i){h=e.getPointAt(i/t,h);var a=o.normals[i],u=o.binormals[i];for(s=0;s<=r;s++){var f=s/r*Math.PI*2,m=Math.sin(f),g=-Math.cos(f);l.x=g*a.x+m*u.x,l.y=g*a.y+m*u.y,l.z=g*a.z+m*u.z,l.normalize(),p.push(l.x,l.y,l.z),c.x=h.x+n*l.x,c.y=h.y+n*l.y,c.z=h.z+n*l.z,d.push(c.x,c.y,c.z)}}!function(){for(a=0;a0){var a=i[o[0]];if(void 0!==a)for(this.morphTargetInfluences=[],this.morphTargetDictionary={},e=0,t=a.length;e0&&console.error("THREE.Points.updateMorphTargets() does not support THREE.Geometry. Use THREE.BufferGeometry instead.")}},clone:function(){return new this.constructor(this.geometry,this.material).copy(this)}}),fc.prototype=Object.assign(Object.create(Rn.prototype),{constructor:fc,isVideoTexture:!0,update:function(){var e=this.image;e.readyState>=e.HAVE_CURRENT_DATA&&(this.needsUpdate=!0)}}),mc.prototype=Object.create(Rn.prototype),mc.prototype.constructor=mc,mc.prototype.isCompressedTexture=!0,gc.prototype=Object.create(Rn.prototype),gc.prototype.constructor=gc,gc.prototype.isCanvasTexture=!0,vc.prototype=Object.create(Rn.prototype),vc.prototype.constructor=vc,vc.prototype.isDepthTexture=!0,yc.prototype=Object.create(wi.prototype),yc.prototype.constructor=yc,bc.prototype=Object.create(Yi.prototype),bc.prototype.constructor=bc,_c.prototype=Object.create(wi.prototype),_c.prototype.constructor=_c,xc.prototype=Object.create(Yi.prototype),xc.prototype.constructor=xc,wc.prototype=Object.create(wi.prototype),wc.prototype.constructor=wc,Mc.prototype=Object.create(Yi.prototype),Mc.prototype.constructor=Mc,Ec.prototype=Object.create(wc.prototype),Ec.prototype.constructor=Ec,Tc.prototype=Object.create(Yi.prototype),Tc.prototype.constructor=Tc,Sc.prototype=Object.create(wc.prototype),Sc.prototype.constructor=Sc,Ac.prototype=Object.create(Yi.prototype),Ac.prototype.constructor=Ac,Lc.prototype=Object.create(wc.prototype),Lc.prototype.constructor=Lc,Cc.prototype=Object.create(Yi.prototype),Cc.prototype.constructor=Cc,Rc.prototype=Object.create(wc.prototype),Rc.prototype.constructor=Rc,Pc.prototype=Object.create(Yi.prototype),Pc.prototype.constructor=Pc,Oc.prototype=Object.create(wi.prototype),Oc.prototype.constructor=Oc,Oc.prototype.toJSON=function(){var e=wi.prototype.toJSON.call(this);return e.path=this.parameters.path.toJSON(),e},Nc.prototype=Object.create(Yi.prototype),Nc.prototype.constructor=Nc,Ic.prototype=Object.create(wi.prototype),Ic.prototype.constructor=Ic,Dc.prototype=Object.create(Yi.prototype),Dc.prototype.constructor=Dc,Bc.prototype=Object.create(wi.prototype),Bc.prototype.constructor=Bc;var kc=function(e,t,n){n=n||2;var r,i,o,a,s,c,l,u=t&&t.length,h=u?t[0]*n:e.length,d=Uc(e,0,h,n,!0),p=[];if(!d||d.next===d.prev)return p;if(u&&(d=function(e,t,n,r){var i,o,a,s,c,l=[];for(i=0,o=t.length;i80*n){r=o=e[0],i=a=e[1];for(var f=n;fo&&(o=s),c>a&&(a=c);l=0!==(l=Math.max(o-r,a-i))?1/l:0}return zc(d,p,n,r,i,l),p};function Uc(e,t,n,r,i){var o,a;if(i===function(e,t,n,r){for(var i=0,o=t,a=n-r;o0)for(o=t;o=t;o-=r)a=nl(o,e[o],e[o+1],a);return a&&Qc(a,a.next)&&(rl(a),a=a.next),a}function Fc(e,t){if(!e)return e;t||(t=e);var n,r=e;do{if(n=!1,r.steiner||!Qc(r,r.next)&&0!==Kc(r.prev,r,r.next))r=r.next;else{if(rl(r),(r=t=r.prev)===r.next)break;n=!0}}while(n||r!==t);return t}function zc(e,t,n,r,i,o,a){if(e){!a&&o&&function(e,t,n,r){var i=e;do{null===i.z&&(i.z=Yc(i.x,i.y,t,n,r)),i.prevZ=i.prev,i.nextZ=i.next,i=i.next}while(i!==e);i.prevZ.nextZ=null,i.prevZ=null,function(e){var t,n,r,i,o,a,s,c,l=1;do{for(n=e,e=null,o=null,a=0;n;){for(a++,r=n,s=0,t=0;t0||c>0&&r;)0!==s&&(0===c||!r||n.z<=r.z)?(i=n,n=n.nextZ,s--):(i=r,r=r.nextZ,c--),o?o.nextZ=i:e=i,i.prevZ=o,o=i;n=r}o.nextZ=null,l*=2}while(a>1)}(i)}(e,r,i,o);for(var s,c,l=e;e.prev!==e.next;)if(s=e.prev,c=e.next,o?Hc(e,r,i,o):Gc(e))t.push(s.i/n),t.push(e.i/n),t.push(c.i/n),rl(e),e=c.next,l=c.next;else if((e=c)===l){a?1===a?zc(e=jc(e,t,n),t,n,r,i,o,2):2===a&&Vc(e,t,n,r,i,o):zc(Fc(e),t,n,r,i,o,1);break}}}function Gc(e){var t=e.prev,n=e,r=e.next;if(Kc(t,n,r)>=0)return!1;for(var i=e.next.next;i!==e.prev;){if(Jc(t.x,t.y,n.x,n.y,r.x,r.y,i.x,i.y)&&Kc(i.prev,i,i.next)>=0)return!1;i=i.next}return!0}function Hc(e,t,n,r){var i=e.prev,o=e,a=e.next;if(Kc(i,o,a)>=0)return!1;for(var s=i.xo.x?i.x>a.x?i.x:a.x:o.x>a.x?o.x:a.x,u=i.y>o.y?i.y>a.y?i.y:a.y:o.y>a.y?o.y:a.y,h=Yc(s,c,t,n,r),d=Yc(l,u,t,n,r),p=e.prevZ,f=e.nextZ;p&&p.z>=h&&f&&f.z<=d;){if(p!==e.prev&&p!==e.next&&Jc(i.x,i.y,o.x,o.y,a.x,a.y,p.x,p.y)&&Kc(p.prev,p,p.next)>=0)return!1;if(p=p.prevZ,f!==e.prev&&f!==e.next&&Jc(i.x,i.y,o.x,o.y,a.x,a.y,f.x,f.y)&&Kc(f.prev,f,f.next)>=0)return!1;f=f.nextZ}for(;p&&p.z>=h;){if(p!==e.prev&&p!==e.next&&Jc(i.x,i.y,o.x,o.y,a.x,a.y,p.x,p.y)&&Kc(p.prev,p,p.next)>=0)return!1;p=p.prevZ}for(;f&&f.z<=d;){if(f!==e.prev&&f!==e.next&&Jc(i.x,i.y,o.x,o.y,a.x,a.y,f.x,f.y)&&Kc(f.prev,f,f.next)>=0)return!1;f=f.nextZ}return!0}function jc(e,t,n){var r=e;do{var i=r.prev,o=r.next.next;!Qc(i,o)&&$c(i,r,r.next,o)&&el(i,o)&&el(o,i)&&(t.push(i.i/n),t.push(r.i/n),t.push(o.i/n),rl(r),rl(r.next),r=e=o),r=r.next}while(r!==e);return r}function Vc(e,t,n,r,i,o){var a=e;do{for(var s=a.next.next;s!==a.prev;){if(a.i!==s.i&&Zc(a,s)){var c=tl(a,s);return a=Fc(a,a.next),c=Fc(c,c.next),zc(a,t,n,r,i,o),void zc(c,t,n,r,i,o)}s=s.next}a=a.next}while(a!==e)}function Wc(e,t){return e.x-t.x}function qc(e,t){if(t=function(e,t){var n,r=t,i=e.x,o=e.y,a=-1/0;do{if(o<=r.y&&o>=r.next.y&&r.next.y!==r.y){var s=r.x+(o-r.y)*(r.next.x-r.x)/(r.next.y-r.y);if(s<=i&&s>a){if(a=s,s===i){if(o===r.y)return r;if(o===r.next.y)return r.next}n=r.x=r.x&&r.x>=u&&i!==r.x&&Jc(on.x)&&el(r,e)&&(n=r,d=c),r=r.next;return n}(e,t)){var n=tl(t,e);Fc(n,n.next)}}function Yc(e,t,n,r,i){return(e=1431655765&((e=858993459&((e=252645135&((e=16711935&((e=32767*(e-n)*i)|e<<8))|e<<4))|e<<2))|e<<1))|(t=1431655765&((t=858993459&((t=252645135&((t=16711935&((t=32767*(t-r)*i)|t<<8))|t<<4))|t<<2))|t<<1))<<1}function Xc(e){var t=e,n=e;do{(t.x=0&&(e-a)*(r-s)-(n-a)*(t-s)>=0&&(n-a)*(o-s)-(i-a)*(r-s)>=0}function Zc(e,t){return e.next.i!==t.i&&e.prev.i!==t.i&&!function(e,t){var n=e;do{if(n.i!==e.i&&n.next.i!==e.i&&n.i!==t.i&&n.next.i!==t.i&&$c(n,n.next,e,t))return!0;n=n.next}while(n!==e);return!1}(e,t)&&el(e,t)&&el(t,e)&&function(e,t){var n=e,r=!1,i=(e.x+t.x)/2,o=(e.y+t.y)/2;do{n.y>o!=n.next.y>o&&n.next.y!==n.y&&i<(n.next.x-n.x)*(o-n.y)/(n.next.y-n.y)+n.x&&(r=!r),n=n.next}while(n!==e);return r}(e,t)}function Kc(e,t,n){return(t.y-e.y)*(n.x-t.x)-(t.x-e.x)*(n.y-t.y)}function Qc(e,t){return e.x===t.x&&e.y===t.y}function $c(e,t,n,r){return!!(Qc(e,n)&&Qc(t,r)||Qc(e,r)&&Qc(n,t))||Kc(e,t,n)>0!=Kc(e,t,r)>0&&Kc(n,r,e)>0!=Kc(n,r,t)>0}function el(e,t){return Kc(e.prev,e,e.next)<0?Kc(e,t,e.next)>=0&&Kc(e,e.prev,t)>=0:Kc(e,t,e.prev)<0||Kc(e,e.next,t)<0}function tl(e,t){var n=new il(e.i,e.x,e.y),r=new il(t.i,t.x,t.y),i=e.next,o=t.prev;return e.next=t,t.prev=e,n.next=i,i.prev=n,r.next=n,n.prev=r,o.next=r,r.prev=o,r}function nl(e,t,n,r){var i=new il(e,t,n);return r?(i.next=r.next,i.prev=r,r.next.prev=i,r.next=i):(i.prev=i,i.next=i),i}function rl(e){e.next.prev=e.prev,e.prev.next=e.next,e.prevZ&&(e.prevZ.nextZ=e.nextZ),e.nextZ&&(e.nextZ.prevZ=e.prevZ)}function il(e,t,n){this.i=e,this.x=t,this.y=n,this.prev=null,this.next=null,this.z=null,this.prevZ=null,this.nextZ=null,this.steiner=!1}var ol={area:function(e){for(var t=e.length,n=0,r=t-1,i=0;i2&&e[t-1].equals(e[0])&&e.pop()}function sl(e,t){for(var n=0;nNumber.EPSILON){var d=Math.sqrt(u),p=Math.sqrt(c*c+l*l),f=t.x-s/d,m=t.y+a/d,g=((n.x-l/p-f)*l-(n.y+c/p-m)*c)/(a*l-s*c),v=(r=f+a*g-e.x)*r+(i=m+s*g-e.y)*i;if(v<=2)return new _n(r,i);o=Math.sqrt(v/2)}else{var y=!1;a>Number.EPSILON?c>Number.EPSILON&&(y=!0):a<-Number.EPSILON?c<-Number.EPSILON&&(y=!0):Math.sign(s)===Math.sign(l)&&(y=!0),y?(r=-s,i=a,o=Math.sqrt(u)):(r=a,i=s,o=Math.sqrt(u/2))}return new _n(r/o,i/o)}for(var z=[],G=0,H=C.length,j=H-1,V=G+1;G=0;P--){for(N=P/p,I=u*Math.cos(N*Math.PI/2),O=h*Math.sin(N*Math.PI/2)+d,G=0,H=C.length;G=0;){n=G,(r=G-1)<0&&(r=e.length-1);var i=0,o=s+2*p;for(i=0;i0)&&f.push(w,M,T),(c!==n-1||l0&&v(!0),t>0&&v(!1)),this.setIndex(l),this.setAttribute("position",new hi(u,3)),this.setAttribute("normal",new hi(h,3)),this.setAttribute("uv",new hi(d,2))}function Sl(e,t,n,r,i,o,a){El.call(this,0,e,t,n,r,i,o,a),this.type="ConeGeometry",this.parameters={radius:e,height:t,radialSegments:n,heightSegments:r,openEnded:i,thetaStart:o,thetaLength:a}}function Al(e,t,n,r,i,o,a){Tl.call(this,0,e,t,n,r,i,o,a),this.type="ConeBufferGeometry",this.parameters={radius:e,height:t,radialSegments:n,heightSegments:r,openEnded:i,thetaStart:o,thetaLength:a}}function Ll(e,t,n,r){Yi.call(this),this.type="CircleGeometry",this.parameters={radius:e,segments:t,thetaStart:n,thetaLength:r},this.fromBufferGeometry(new Cl(e,t,n,r)),this.mergeVertices()}function Cl(e,t,n,r){wi.call(this),this.type="CircleBufferGeometry",this.parameters={radius:e,segments:t,thetaStart:n,thetaLength:r},e=e||1,t=void 0!==t?Math.max(3,t):8,n=void 0!==n?n:0,r=void 0!==r?r:2*Math.PI;var i,o,a=[],s=[],c=[],l=[],u=new En,h=new _n;for(s.push(0,0,0),c.push(0,0,1),l.push(.5,.5),o=0,i=3;o<=t;o++,i+=3){var d=n+o/t*r;u.x=e*Math.cos(d),u.y=e*Math.sin(d),s.push(u.x,u.y,u.z),c.push(0,0,1),h.x=(s[i]/e+1)/2,h.y=(s[i+1]/e+1)/2,l.push(h.x,h.y)}for(i=1;i<=t;i++)a.push(i,i+1,0);this.setIndex(a),this.setAttribute("position",new hi(s,3)),this.setAttribute("normal",new hi(c,3)),this.setAttribute("uv",new hi(l,2))}dl.prototype=Object.create(Yi.prototype),dl.prototype.constructor=dl,pl.prototype=Object.create(ll.prototype),pl.prototype.constructor=pl,fl.prototype=Object.create(Yi.prototype),fl.prototype.constructor=fl,ml.prototype=Object.create(wi.prototype),ml.prototype.constructor=ml,gl.prototype=Object.create(Yi.prototype),gl.prototype.constructor=gl,vl.prototype=Object.create(wi.prototype),vl.prototype.constructor=vl,yl.prototype=Object.create(Yi.prototype),yl.prototype.constructor=yl,bl.prototype=Object.create(wi.prototype),bl.prototype.constructor=bl,_l.prototype=Object.create(Yi.prototype),_l.prototype.constructor=_l,_l.prototype.toJSON=function(){var e=Yi.prototype.toJSON.call(this);return wl(this.parameters.shapes,e)},xl.prototype=Object.create(wi.prototype),xl.prototype.constructor=xl,xl.prototype.toJSON=function(){var e=wi.prototype.toJSON.call(this);return wl(this.parameters.shapes,e)},Ml.prototype=Object.create(wi.prototype),Ml.prototype.constructor=Ml,El.prototype=Object.create(Yi.prototype),El.prototype.constructor=El,Tl.prototype=Object.create(wi.prototype),Tl.prototype.constructor=Tl,Sl.prototype=Object.create(El.prototype),Sl.prototype.constructor=Sl,Al.prototype=Object.create(Tl.prototype),Al.prototype.constructor=Al,Ll.prototype=Object.create(Yi.prototype),Ll.prototype.constructor=Ll,Cl.prototype=Object.create(wi.prototype),Cl.prototype.constructor=Cl;var Rl=Object.freeze({__proto__:null,WireframeGeometry:yc,ParametricGeometry:bc,ParametricBufferGeometry:_c,TetrahedronGeometry:Mc,TetrahedronBufferGeometry:Ec,OctahedronGeometry:Tc,OctahedronBufferGeometry:Sc,IcosahedronGeometry:Ac,IcosahedronBufferGeometry:Lc,DodecahedronGeometry:Cc,DodecahedronBufferGeometry:Rc,PolyhedronGeometry:xc,PolyhedronBufferGeometry:wc,TubeGeometry:Pc,TubeBufferGeometry:Oc,TorusKnotGeometry:Nc,TorusKnotBufferGeometry:Ic,TorusGeometry:Dc,TorusBufferGeometry:Bc,TextGeometry:dl,TextBufferGeometry:pl,SphereGeometry:fl,SphereBufferGeometry:ml,RingGeometry:gl,RingBufferGeometry:vl,PlaneGeometry:yo,PlaneBufferGeometry:bo,LatheGeometry:yl,LatheBufferGeometry:bl,ShapeGeometry:_l,ShapeBufferGeometry:xl,ExtrudeGeometry:cl,ExtrudeBufferGeometry:ll,EdgesGeometry:Ml,ConeGeometry:Sl,ConeBufferGeometry:Al,CylinderGeometry:El,CylinderBufferGeometry:Tl,CircleGeometry:Ll,CircleBufferGeometry:Cl,BoxGeometry:Xi,BoxBufferGeometry:Ji});function Pl(e){ti.call(this),this.type="ShadowMaterial",this.color=new Jr(0),this.transparent=!0,this.setValues(e)}function Ol(e){to.call(this,e),this.type="RawShaderMaterial"}function Nl(e){ti.call(this),this.defines={STANDARD:""},this.type="MeshStandardMaterial",this.color=new Jr(16777215),this.roughness=.5,this.metalness=.5,this.map=null,this.lightMap=null,this.lightMapIntensity=1,this.aoMap=null,this.aoMapIntensity=1,this.emissive=new Jr(0),this.emissiveIntensity=1,this.emissiveMap=null,this.bumpMap=null,this.bumpScale=1,this.normalMap=null,this.normalMapType=Ht,this.normalScale=new _n(1,1),this.displacementMap=null,this.displacementScale=1,this.displacementBias=0,this.roughnessMap=null,this.metalnessMap=null,this.alphaMap=null,this.envMap=null,this.envMapIntensity=1,this.refractionRatio=.98,this.wireframe=!1,this.wireframeLinewidth=1,this.wireframeLinecap="round",this.wireframeLinejoin="round",this.skinning=!1,this.morphTargets=!1,this.morphNormals=!1,this.setValues(e)}function Il(e){Nl.call(this),this.defines={STANDARD:"",PHYSICAL:""},this.type="MeshPhysicalMaterial",this.reflectivity=.5,this.clearcoat=0,this.clearcoatRoughness=0,this.sheen=null,this.clearcoatNormalScale=new _n(1,1),this.clearcoatNormalMap=null,this.transparency=0,this.setValues(e)}function Dl(e){ti.call(this),this.type="MeshPhongMaterial",this.color=new Jr(16777215),this.specular=new Jr(1118481),this.shininess=30,this.map=null,this.lightMap=null,this.lightMapIntensity=1,this.aoMap=null,this.aoMapIntensity=1,this.emissive=new Jr(0),this.emissiveIntensity=1,this.emissiveMap=null,this.bumpMap=null,this.bumpScale=1,this.normalMap=null,this.normalMapType=Ht,this.normalScale=new _n(1,1),this.displacementMap=null,this.displacementScale=1,this.displacementBias=0,this.specularMap=null,this.alphaMap=null,this.envMap=null,this.combine=ee,this.reflectivity=1,this.refractionRatio=.98,this.wireframe=!1,this.wireframeLinewidth=1,this.wireframeLinecap="round",this.wireframeLinejoin="round",this.skinning=!1,this.morphTargets=!1,this.morphNormals=!1,this.setValues(e)}function Bl(e){Dl.call(this),this.defines={TOON:""},this.type="MeshToonMaterial",this.gradientMap=null,this.setValues(e)}function kl(e){ti.call(this),this.type="MeshNormalMaterial",this.bumpMap=null,this.bumpScale=1,this.normalMap=null,this.normalMapType=Ht,this.normalScale=new _n(1,1),this.displacementMap=null,this.displacementScale=1,this.displacementBias=0,this.wireframe=!1,this.wireframeLinewidth=1,this.fog=!1,this.skinning=!1,this.morphTargets=!1,this.morphNormals=!1,this.setValues(e)}function Ul(e){ti.call(this),this.type="MeshLambertMaterial",this.color=new Jr(16777215),this.map=null,this.lightMap=null,this.lightMapIntensity=1,this.aoMap=null,this.aoMapIntensity=1,this.emissive=new Jr(0),this.emissiveIntensity=1,this.emissiveMap=null,this.specularMap=null,this.alphaMap=null,this.envMap=null,this.combine=ee,this.reflectivity=1,this.refractionRatio=.98,this.wireframe=!1,this.wireframeLinewidth=1,this.wireframeLinecap="round",this.wireframeLinejoin="round",this.skinning=!1,this.morphTargets=!1,this.morphNormals=!1,this.setValues(e)}function Fl(e){ti.call(this),this.defines={MATCAP:""},this.type="MeshMatcapMaterial",this.color=new Jr(16777215),this.matcap=null,this.map=null,this.bumpMap=null,this.bumpScale=1,this.normalMap=null,this.normalMapType=Ht,this.normalScale=new _n(1,1),this.displacementMap=null,this.displacementScale=1,this.displacementBias=0,this.alphaMap=null,this.skinning=!1,this.morphTargets=!1,this.morphNormals=!1,this.setValues(e)}function zl(e){Zs.call(this),this.type="LineDashedMaterial",this.scale=1,this.dashSize=3,this.gapSize=1,this.setValues(e)}Pl.prototype=Object.create(ti.prototype),Pl.prototype.constructor=Pl,Pl.prototype.isShadowMaterial=!0,Pl.prototype.copy=function(e){return ti.prototype.copy.call(this,e),this.color.copy(e.color),this},Ol.prototype=Object.create(to.prototype),Ol.prototype.constructor=Ol,Ol.prototype.isRawShaderMaterial=!0,Nl.prototype=Object.create(ti.prototype),Nl.prototype.constructor=Nl,Nl.prototype.isMeshStandardMaterial=!0,Nl.prototype.copy=function(e){return ti.prototype.copy.call(this,e),this.defines={STANDARD:""},this.color.copy(e.color),this.roughness=e.roughness,this.metalness=e.metalness,this.map=e.map,this.lightMap=e.lightMap,this.lightMapIntensity=e.lightMapIntensity,this.aoMap=e.aoMap,this.aoMapIntensity=e.aoMapIntensity,this.emissive.copy(e.emissive),this.emissiveMap=e.emissiveMap,this.emissiveIntensity=e.emissiveIntensity,this.bumpMap=e.bumpMap,this.bumpScale=e.bumpScale,this.normalMap=e.normalMap,this.normalMapType=e.normalMapType,this.normalScale.copy(e.normalScale),this.displacementMap=e.displacementMap,this.displacementScale=e.displacementScale,this.displacementBias=e.displacementBias,this.roughnessMap=e.roughnessMap,this.metalnessMap=e.metalnessMap,this.alphaMap=e.alphaMap,this.envMap=e.envMap,this.envMapIntensity=e.envMapIntensity,this.refractionRatio=e.refractionRatio,this.wireframe=e.wireframe,this.wireframeLinewidth=e.wireframeLinewidth,this.wireframeLinecap=e.wireframeLinecap,this.wireframeLinejoin=e.wireframeLinejoin,this.skinning=e.skinning,this.morphTargets=e.morphTargets,this.morphNormals=e.morphNormals,this},Il.prototype=Object.create(Nl.prototype),Il.prototype.constructor=Il,Il.prototype.isMeshPhysicalMaterial=!0,Il.prototype.copy=function(e){return Nl.prototype.copy.call(this,e),this.defines={STANDARD:"",PHYSICAL:""},this.reflectivity=e.reflectivity,this.clearcoat=e.clearcoat,this.clearcoatRoughness=e.clearcoatRoughness,e.sheen?this.sheen=(this.sheen||new Jr).copy(e.sheen):this.sheen=null,this.clearcoatNormalMap=e.clearcoatNormalMap,this.clearcoatNormalScale.copy(e.clearcoatNormalScale),this.transparency=e.transparency,this},Dl.prototype=Object.create(ti.prototype),Dl.prototype.constructor=Dl,Dl.prototype.isMeshPhongMaterial=!0,Dl.prototype.copy=function(e){return ti.prototype.copy.call(this,e),this.color.copy(e.color),this.specular.copy(e.specular),this.shininess=e.shininess,this.map=e.map,this.lightMap=e.lightMap,this.lightMapIntensity=e.lightMapIntensity,this.aoMap=e.aoMap,this.aoMapIntensity=e.aoMapIntensity,this.emissive.copy(e.emissive),this.emissiveMap=e.emissiveMap,this.emissiveIntensity=e.emissiveIntensity,this.bumpMap=e.bumpMap,this.bumpScale=e.bumpScale,this.normalMap=e.normalMap,this.normalMapType=e.normalMapType,this.normalScale.copy(e.normalScale),this.displacementMap=e.displacementMap,this.displacementScale=e.displacementScale,this.displacementBias=e.displacementBias,this.specularMap=e.specularMap,this.alphaMap=e.alphaMap,this.envMap=e.envMap,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.skinning=e.skinning,this.morphTargets=e.morphTargets,this.morphNormals=e.morphNormals,this},Bl.prototype=Object.create(Dl.prototype),Bl.prototype.constructor=Bl,Bl.prototype.isMeshToonMaterial=!0,Bl.prototype.copy=function(e){return Dl.prototype.copy.call(this,e),this.gradientMap=e.gradientMap,this},kl.prototype=Object.create(ti.prototype),kl.prototype.constructor=kl,kl.prototype.isMeshNormalMaterial=!0,kl.prototype.copy=function(e){return ti.prototype.copy.call(this,e),this.bumpMap=e.bumpMap,this.bumpScale=e.bumpScale,this.normalMap=e.normalMap,this.normalMapType=e.normalMapType,this.normalScale.copy(e.normalScale),this.displacementMap=e.displacementMap,this.displacementScale=e.displacementScale,this.displacementBias=e.displacementBias,this.wireframe=e.wireframe,this.wireframeLinewidth=e.wireframeLinewidth,this.skinning=e.skinning,this.morphTargets=e.morphTargets,this.morphNormals=e.morphNormals,this},Ul.prototype=Object.create(ti.prototype),Ul.prototype.constructor=Ul,Ul.prototype.isMeshLambertMaterial=!0,Ul.prototype.copy=function(e){return ti.prototype.copy.call(this,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.emissive.copy(e.emissive),this.emissiveMap=e.emissiveMap,this.emissiveIntensity=e.emissiveIntensity,this.specularMap=e.specularMap,this.alphaMap=e.alphaMap,this.envMap=e.envMap,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.skinning=e.skinning,this.morphTargets=e.morphTargets,this.morphNormals=e.morphNormals,this},Fl.prototype=Object.create(ti.prototype),Fl.prototype.constructor=Fl,Fl.prototype.isMeshMatcapMaterial=!0,Fl.prototype.copy=function(e){return ti.prototype.copy.call(this,e),this.defines={MATCAP:""},this.color.copy(e.color),this.matcap=e.matcap,this.map=e.map,this.bumpMap=e.bumpMap,this.bumpScale=e.bumpScale,this.normalMap=e.normalMap,this.normalMapType=e.normalMapType,this.normalScale.copy(e.normalScale),this.displacementMap=e.displacementMap,this.displacementScale=e.displacementScale,this.displacementBias=e.displacementBias,this.alphaMap=e.alphaMap,this.skinning=e.skinning,this.morphTargets=e.morphTargets,this.morphNormals=e.morphNormals,this},zl.prototype=Object.create(Zs.prototype),zl.prototype.constructor=zl,zl.prototype.isLineDashedMaterial=!0,zl.prototype.copy=function(e){return Zs.prototype.copy.call(this,e),this.scale=e.scale,this.dashSize=e.dashSize,this.gapSize=e.gapSize,this};var Gl=Object.freeze({__proto__:null,ShadowMaterial:Pl,SpriteMaterial:Ss,RawShaderMaterial:Ol,ShaderMaterial:to,PointsMaterial:sc,MeshPhysicalMaterial:Il,MeshStandardMaterial:Nl,MeshPhongMaterial:Dl,MeshToonMaterial:Bl,MeshNormalMaterial:kl,MeshLambertMaterial:Ul,MeshDepthMaterial:rs,MeshDistanceMaterial:is,MeshBasicMaterial:ni,MeshMatcapMaterial:Fl,LineDashedMaterial:zl,LineBasicMaterial:Zs,Material:ti}),Hl={arraySlice:function(e,t,n){return Hl.isTypedArray(e)?new e.constructor(e.subarray(t,void 0!==n?n:e.length)):e.slice(t,n)},convertArray:function(e,t,n){return!e||!n&&e.constructor===t?e:"number"==typeof t.BYTES_PER_ELEMENT?new t(e):Array.prototype.slice.call(e)},isTypedArray:function(e){return ArrayBuffer.isView(e)&&!(e instanceof DataView)},getKeyframeOrder:function(e){for(var t=e.length,n=new Array(t),r=0;r!==t;++r)n[r]=r;return n.sort((function(t,n){return e[t]-e[n]})),n},sortedArray:function(e,t,n){for(var r=e.length,i=new e.constructor(r),o=0,a=0;a!==r;++o)for(var s=n[o]*t,c=0;c!==t;++c)i[a++]=e[s+c];return i},flattenJSON:function(e,t,n,r){for(var i=1,o=e[0];void 0!==o&&void 0===o[r];)o=e[i++];if(void 0!==o){var a=o[r];if(void 0!==a)if(Array.isArray(a))do{void 0!==(a=o[r])&&(t.push(o.time),n.push.apply(n,a)),o=e[i++]}while(void 0!==o);else if(void 0!==a.toArray)do{void 0!==(a=o[r])&&(t.push(o.time),a.toArray(n,n.length)),o=e[i++]}while(void 0!==o);else do{void 0!==(a=o[r])&&(t.push(o.time),n.push(a)),o=e[i++]}while(void 0!==o)}},subclip:function(e,t,n,r,i){i=i||30;var o=e.clone();o.name=t;for(var a=[],s=0;s=r)){u.push(c.times[d]);for(var f=0;fo.tracks[s].times[0]&&(m=o.tracks[s].times[0]);for(s=0;s=i)break e;var s=t[1];e=(i=t[--n-1]))break t}o=n,n=0}for(;n>>1;et;)--o;if(++o,0!==i||o!==r){i>=o&&(i=(o=Math.max(o,1))-1);var a=this.getValueSize();this.times=Hl.arraySlice(n,i,o),this.values=Hl.arraySlice(this.values,i*a,o*a)}return this},validate:function(){var e=!0,t=this.getValueSize();t-Math.floor(t)!=0&&(console.error("THREE.KeyframeTrack: Invalid value size in track.",this),e=!1);var n=this.times,r=this.values,i=n.length;0===i&&(console.error("THREE.KeyframeTrack: Track is empty.",this),e=!1);for(var o=null,a=0;a!==i;a++){var s=n[a];if("number"==typeof s&&isNaN(s)){console.error("THREE.KeyframeTrack: Time is not a valid number.",this,a,s),e=!1;break}if(null!==o&&o>s){console.error("THREE.KeyframeTrack: Out of order keys.",this,a,s,o),e=!1;break}o=s}if(void 0!==r&&Hl.isTypedArray(r)){a=0;for(var c=r.length;a!==c;++a){var l=r[a];if(isNaN(l)){console.error("THREE.KeyframeTrack: Value is not a valid number.",this,a,l),e=!1;break}}}return e},optimize:function(){for(var e=this.times,t=this.values,n=this.getValueSize(),r=this.getInterpolation()===Tt,i=1,o=e.length-1,a=1;a0){e[i]=e[o];for(f=o*n,m=i*n,d=0;d!==n;++d)t[m+d]=t[f+d];++i}return i!==e.length&&(this.times=Hl.arraySlice(e,0,i),this.values=Hl.arraySlice(t,0,i*n)),this},clone:function(){var e=Hl.arraySlice(this.times,0),t=Hl.arraySlice(this.values,0),n=new(0,this.constructor)(this.name,e,t);return n.createInterpolant=this.createInterpolant,n}}),Xl.prototype=Object.assign(Object.create(Yl.prototype),{constructor:Xl,ValueTypeName:"bool",ValueBufferType:Array,DefaultInterpolation:Mt,InterpolantFactoryMethodLinear:void 0,InterpolantFactoryMethodSmooth:void 0}),Jl.prototype=Object.assign(Object.create(Yl.prototype),{constructor:Jl,ValueTypeName:"color"}),Zl.prototype=Object.assign(Object.create(Yl.prototype),{constructor:Zl,ValueTypeName:"number"}),Kl.prototype=Object.assign(Object.create(jl.prototype),{constructor:Kl,interpolate_:function(e,t,n,r){for(var i=this.resultBuffer,o=this.sampleValues,a=this.valueSize,s=e*a,c=(n-t)/(r-t),l=s+a;s!==l;s+=4)xn.slerpFlat(i,0,o,s-a,o,s,c);return i}}),Ql.prototype=Object.assign(Object.create(Yl.prototype),{constructor:Ql,ValueTypeName:"quaternion",DefaultInterpolation:Et,InterpolantFactoryMethodLinear:function(e){return new Kl(this.times,this.values,this.getValueSize(),e)},InterpolantFactoryMethodSmooth:void 0}),$l.prototype=Object.assign(Object.create(Yl.prototype),{constructor:$l,ValueTypeName:"string",ValueBufferType:Array,DefaultInterpolation:Mt,InterpolantFactoryMethodLinear:void 0,InterpolantFactoryMethodSmooth:void 0}),eu.prototype=Object.assign(Object.create(Yl.prototype),{constructor:eu,ValueTypeName:"vector"}),Object.assign(tu,{parse:function(e){for(var t=[],n=e.tracks,r=1/(e.fps||1),i=0,o=n.length;i!==o;++i)t.push(nu(n[i]).scale(r));return new tu(e.name,e.duration,t)},toJSON:function(e){for(var t=[],n=e.tracks,r={name:e.name,duration:e.duration,tracks:t,uuid:e.uuid},i=0,o=n.length;i!==o;++i)t.push(Yl.toJSON(n[i]));return r},CreateFromMorphTargetSequence:function(e,t,n,r){for(var i=t.length,o=[],a=0;a1){var l=r[h=c[1]];l||(r[h]=l=[]),l.push(s)}}var u=[];for(var h in r)u.push(tu.CreateFromMorphTargetSequence(h,r[h],t,n));return u},parseAnimation:function(e,t){if(!e)return console.error("THREE.AnimationClip: No animation in JSONLoader data."),null;for(var n=function(e,t,n,r,i){if(0!==n.length){var o=[],a=[];Hl.flattenJSON(n,o,a,r),0!==o.length&&i.push(new e(t,o,a))}},r=[],i=e.name||"default",o=e.length||-1,a=e.fps||30,s=e.hierarchy||[],c=0;c0||0===e.search(/^data\\:image\\/jpeg/);i.format=r?je:Ve,i.needsUpdate=!0,void 0!==t&&t(i)}),n,r),i}}),Object.assign(mu.prototype,{getPoint:function(){return console.warn("THREE.Curve: .getPoint() not implemented."),null},getPointAt:function(e,t){var n=this.getUtoTmapping(e);return this.getPoint(n,t)},getPoints:function(e){void 0===e&&(e=5);for(var t=[],n=0;n<=e;n++)t.push(this.getPoint(n/e));return t},getSpacedPoints:function(e){void 0===e&&(e=5);for(var t=[],n=0;n<=e;n++)t.push(this.getPointAt(n/e));return t},getLength:function(){var e=this.getLengths();return e[e.length-1]},getLengths:function(e){if(void 0===e&&(e=this.arcLengthDivisions),this.cacheArcLengths&&this.cacheArcLengths.length===e+1&&!this.needsUpdate)return this.cacheArcLengths;this.needsUpdate=!1;var t,n,r=[],i=this.getPoint(0),o=0;for(r.push(0),n=1;n<=e;n++)o+=(t=this.getPoint(n/e)).distanceTo(i),r.push(o),i=t;return this.cacheArcLengths=r,r},updateArcLengths:function(){this.needsUpdate=!0,this.getLengths()},getUtoTmapping:function(e,t){var n,r=this.getLengths(),i=0,o=r.length;n=t||e*r[o-1];for(var a,s=0,c=o-1;s<=c;)if((a=r[i=Math.floor(s+(c-s)/2)]-n)<0)s=i+1;else{if(!(a>0)){c=i;break}c=i-1}if(r[i=c]===n)return i/(o-1);var l=r[i];return(i+(n-l)/(r[i+1]-l))/(o-1)},getTangent:function(e){var t=e-1e-4,n=e+1e-4;t<0&&(t=0),n>1&&(n=1);var r=this.getPoint(t);return this.getPoint(n).clone().sub(r).normalize()},getTangentAt:function(e){var t=this.getUtoTmapping(e);return this.getTangent(t)},computeFrenetFrames:function(e,t){var n,r,i,o=new En,a=[],s=[],c=[],l=new En,u=new Gn;for(n=0;n<=e;n++)r=n/e,a[n]=this.getTangentAt(r),a[n].normalize();s[0]=new En,c[0]=new En;var h=Number.MAX_VALUE,d=Math.abs(a[0].x),p=Math.abs(a[0].y),f=Math.abs(a[0].z);for(d<=h&&(h=d,o.set(1,0,0)),p<=h&&(h=p,o.set(0,1,0)),f<=h&&o.set(0,0,1),l.crossVectors(a[0],o).normalize(),s[0].crossVectors(a[0],l),c[0].crossVectors(a[0],s[0]),n=1;n<=e;n++)s[n]=s[n-1].clone(),c[n]=c[n-1].clone(),l.crossVectors(a[n-1],a[n]),l.length()>Number.EPSILON&&(l.normalize(),i=Math.acos(bn.clamp(a[n-1].dot(a[n]),-1,1)),s[n].applyMatrix4(u.makeRotationAxis(l,i))),c[n].crossVectors(a[n],s[n]);if(!0===t)for(i=Math.acos(bn.clamp(s[0].dot(s[e]),-1,1)),i/=e,a[0].dot(l.crossVectors(s[0],s[e]))>0&&(i=-i),n=1;n<=e;n++)s[n].applyMatrix4(u.makeRotationAxis(a[n],i*n)),c[n].crossVectors(a[n],s[n]);return{tangents:a,normals:s,binormals:c}},clone:function(){return(new this.constructor).copy(this)},copy:function(e){return this.arcLengthDivisions=e.arcLengthDivisions,this},toJSON:function(){var e={metadata:{version:4.5,type:"Curve",generator:"Curve.toJSON"}};return e.arcLengthDivisions=this.arcLengthDivisions,e.type=this.type,e},fromJSON:function(e){return this.arcLengthDivisions=e.arcLengthDivisions,this}}),gu.prototype=Object.create(mu.prototype),gu.prototype.constructor=gu,gu.prototype.isEllipseCurve=!0,gu.prototype.getPoint=function(e,t){for(var n=t||new _n,r=2*Math.PI,i=this.aEndAngle-this.aStartAngle,o=Math.abs(i)r;)i-=r;i0?0:(Math.floor(Math.abs(u)/c)+1)*c:0===h&&u===c-1&&(u=c-2,h=1),this.closed||u>0?n=s[(u-1)%c]:(bu.subVectors(s[0],s[1]).add(s[0]),n=bu),r=s[u%c],i=s[(u+1)%c],this.closed||u+2r.length-2?r.length-1:o+1],u=r[o>r.length-3?r.length-1:o+2];return n.set(Eu(a,s.x,c.x,l.x,u.x),Eu(a,s.y,c.y,l.y,u.y)),n},Nu.prototype.copy=function(e){mu.prototype.copy.call(this,e),this.points=[];for(var t=0,n=e.points.length;t=t){var i=n[r]-t,o=this.curves[r],a=o.getLength(),s=0===a?0:1-i/a;return o.getPointAt(s)}r++}return null},getLength:function(){var e=this.getCurveLengths();return e[e.length-1]},updateArcLengths:function(){this.needsUpdate=!0,this.cacheLengths=null,this.getCurveLengths()},getCurveLengths:function(){if(this.cacheLengths&&this.cacheLengths.length===this.curves.length)return this.cacheLengths;for(var e=[],t=0,n=0,r=this.curves.length;n1&&!n[n.length-1].equals(n[0])&&n.push(n[0]),n},copy:function(e){mu.prototype.copy.call(this,e),this.curves=[];for(var t=0,n=e.curves.length;t0){var l=c.getPoint(0);l.equals(this.currentPoint)||this.lineTo(l.x,l.y)}this.curves.push(c);var u=c.getPoint(1);return this.currentPoint.copy(u),this},copy:function(e){return Du.prototype.copy.call(this,e),this.currentPoint.copy(e.currentPoint),this},toJSON:function(){var e=Du.prototype.toJSON.call(this);return e.currentPoint=this.currentPoint.toArray(),e},fromJSON:function(e){return Du.prototype.fromJSON.call(this,e),this.currentPoint.fromArray(e.currentPoint),this}}),ku.prototype=Object.assign(Object.create(Bu.prototype),{constructor:ku,getPointsHoles:function(e){for(var t=[],n=0,r=this.holes.length;n0){var o=new du(new iu(t));o.setCrossOrigin(this.crossOrigin);for(var a=0,s=e.length;a0?new Vs(a,s):new zi(a,s);break;case"InstancedMesh":a=i(e.geometry),s=o(e.material);var c=e.count,l=e.instanceMatrix;(r=new Js(a,s,c)).instanceMatrix=new ri(new Float32Array(l.array),16);break;case"LOD":r=new js;break;case"Line":r=new nc(i(e.geometry),o(e.material),e.mode);break;case"LineLoop":r=new ac(i(e.geometry),o(e.material));break;case"LineSegments":r=new oc(i(e.geometry),o(e.material));break;case"PointCloud":case"Points":r=new dc(i(e.geometry),o(e.material));break;case"Sprite":r=new Fs(o(e.material));break;case"Group":r=new ps;break;default:r=new or}if(r.uuid=e.uuid,void 0!==e.name&&(r.name=e.name),void 0!==e.matrix?(r.matrix.fromArray(e.matrix),void 0!==e.matrixAutoUpdate&&(r.matrixAutoUpdate=e.matrixAutoUpdate),r.matrixAutoUpdate&&r.matrix.decompose(r.position,r.quaternion,r.scale)):(void 0!==e.position&&r.position.fromArray(e.position),void 0!==e.rotation&&r.rotation.fromArray(e.rotation),void 0!==e.quaternion&&r.quaternion.fromArray(e.quaternion),void 0!==e.scale&&r.scale.fromArray(e.scale)),void 0!==e.castShadow&&(r.castShadow=e.castShadow),void 0!==e.receiveShadow&&(r.receiveShadow=e.receiveShadow),e.shadow&&(void 0!==e.shadow.bias&&(r.shadow.bias=e.shadow.bias),void 0!==e.shadow.radius&&(r.shadow.radius=e.shadow.radius),void 0!==e.shadow.mapSize&&r.shadow.mapSize.fromArray(e.shadow.mapSize),void 0!==e.shadow.camera&&(r.shadow.camera=this.parseObject(e.shadow.camera))),void 0!==e.visible&&(r.visible=e.visible),void 0!==e.frustumCulled&&(r.frustumCulled=e.frustumCulled),void 0!==e.renderOrder&&(r.renderOrder=e.renderOrder),void 0!==e.userData&&(r.userData=e.userData),void 0!==e.layers&&(r.layers.mask=e.layers),void 0!==e.drawMode&&r.setDrawMode(e.drawMode),void 0!==e.children)for(var u=e.children,h=0;hNumber.EPSILON){if(l<0&&(a=t[o],c=-c,s=t[i],l=-l),e.ys.y)continue;if(e.y===a.y){if(e.x===a.x)return!0}else{var u=l*(e.x-a.x)-c*(e.y-a.y);if(0===u)return!0;if(u<0)continue;r=!r}}else{if(e.y!==a.y)continue;if(s.x<=e.x&&e.x<=a.x||a.x<=e.x&&e.x<=s.x)return!0}}return r}var i=ol.isClockWise,o=this.subPaths;if(0===o.length)return[];if(!0===t)return n(o);var a,s,c,l=[];if(1===o.length)return s=o[0],(c=new ku).curves=s.curves,l.push(c),l;var u=!i(o[0].getPoints());u=e?!u:u;var h,d,p=[],f=[],m=[],g=0;f[g]=void 0,m[g]=[];for(var v=0,y=o.length;v1){for(var b=!1,_=[],x=0,w=f.length;x0&&(b||(m=p))}v=0;for(var L=f.length;v0){this.source.connect(this.filters[0]);for(var e=1,t=this.filters.length;e0){this.source.disconnect(this.filters[0]);for(var e=1,t=this.filters.length;e=.5)for(var o=0;o!==i;++o)e[t+o]=e[n+o]},_slerp:function(e,t,n,r){xn.slerpFlat(e,t,e,t,e,n,r)},_lerp:function(e,t,n,r,i){for(var o=1-r,a=0;a!==i;++a){var s=t+a;e[s]=e[s]*o+e[n+a]*r}}});var Dh=new RegExp("[\\\\[\\\\]\\\\.:\\\\/]","g"),Bh="[^"+"\\\\[\\\\]\\\\.:\\\\/".replace("\\\\.","")+"]",kh=/((?:WC+[\\/:])*)/.source.replace("WC","[^\\\\[\\\\]\\\\.:\\\\/]"),Uh=/(WCOD+)?/.source.replace("WCOD",Bh),Fh=/(?:\\.(WC+)(?:\\[(.+)\\])?)?/.source.replace("WC","[^\\\\[\\\\]\\\\.:\\\\/]"),zh=/\\.(WC+)(?:\\[(.+)\\])?/.source.replace("WC","[^\\\\[\\\\]\\\\.:\\\\/]"),Gh=new RegExp("^"+kh+Uh+Fh+zh+"$"),Hh=["material","materials","bones"];function jh(e,t,n){var r=n||Vh.parseTrackName(t);this._targetGroup=e,this._bindings=e.subscribe_(t,r)}function Vh(e,t,n){this.path=t,this.parsedPath=n||Vh.parseTrackName(t),this.node=Vh.findNode(e,this.parsedPath.nodeName)||e,this.rootNode=e}function Wh(){this.uuid=bn.generateUUID(),this._objects=Array.prototype.slice.call(arguments),this.nCachedObjects_=0;var e={};this._indicesByUUID=e;for(var t=0,n=arguments.length;t!==n;++t)e[arguments[t].uuid]=t;this._paths=[],this._parsedPaths=[],this._bindings=[],this._bindingsIndicesByPath={};var r=this;this.stats={objects:{get total(){return r._objects.length},get inUse(){return this.total-r.nCachedObjects_}},get bindingsPerObject(){return r._bindings.length}}}function qh(e,t,n){this._mixer=e,this._clip=t,this._localRoot=n||null;for(var r=t.tracks,i=r.length,o=new Array(i),a={endingStart:St,endingEnd:St},s=0;s!==i;++s){var c=r[s].createInterpolant(null);o[s]=c,c.settings=a}this._interpolantSettings=a,this._interpolants=o,this._propertyBindings=new Array(i),this._cacheIndex=null,this._byClipCacheIndex=null,this._timeScaleInterpolant=null,this._weightInterpolant=null,this.loop=xt,this._loopCount=-1,this._startTime=null,this.time=0,this.timeScale=1,this._effectiveTimeScale=1,this.weight=1,this._effectiveWeight=1,this.repetitions=1/0,this.paused=!1,this.enabled=!0,this.clampWhenFinished=!1,this.zeroSlopeAtStart=!0,this.zeroSlopeAtEnd=!0}function Yh(e){this._root=e,this._initMemoryManager(),this._accuIndex=0,this.time=0,this.timeScale=1}function Xh(e){"string"==typeof e&&(console.warn("THREE.Uniform: Type parameter is no longer needed."),e=arguments[1]),this.value=e}function Jh(e,t,n){Es.call(this,e,t),this.meshPerAttribute=n||1}function Zh(e,t,n,r){this.ray=new Rr(e,t),this.near=n||0,this.far=r||1/0,this.camera=null,this.params={Mesh:{},Line:{},LOD:{},Points:{threshold:1},Sprite:{}},Object.defineProperties(this.params,{PointCloud:{get:function(){return console.warn("THREE.Raycaster: params.PointCloud has been renamed to params.Points."),this.Points}}})}function Kh(e,t){return e.distance-t.distance}function Qh(e,t,n,r){if(!1!==e.visible&&(e.raycast(t,n),!0===r))for(var i=e.children,o=0,a=i.length;o=t){var u=t++,h=e[u];n[h.uuid]=l,e[l]=h,n[c]=u,e[u]=s;for(var d=0,p=i;d!==p;++d){var f=r[d],m=f[u],g=f[l];f[l]=m,f[u]=g}}}this.nCachedObjects_=t},uncache:function(){for(var e=this._objects,t=e.length,n=this.nCachedObjects_,r=this._indicesByUUID,i=this._bindings,o=i.length,a=0,s=arguments.length;a!==s;++a){var c=arguments[a],l=c.uuid,u=r[l];if(void 0!==u)if(delete r[l],u0)for(var c=this._interpolants,l=this._propertyBindings,u=0,h=c.length;u!==h;++u)c[u].evaluate(a),l[u].accumulate(r,s)}else this._updateWeight(e)},_updateWeight:function(e){var t=0;if(this.enabled){t=this.weight;var n=this._weightInterpolant;if(null!==n){var r=n.evaluate(e)[0];t*=r,e>n.parameterPositions[1]&&(this.stopFading(),0===r&&(this.enabled=!1))}}return this._effectiveWeight=t,t},_updateTimeScale:function(e){var t=0;if(!this.paused){t=this.timeScale;var n=this._timeScaleInterpolant;if(null!==n)t*=n.evaluate(e)[0],e>n.parameterPositions[1]&&(this.stopWarping(),0===t?this.paused=!0:this.timeScale=t)}return this._effectiveTimeScale=t,t},_updateTime:function(e){var t=this.time+e,n=this._clip.duration,r=this.loop,i=this._loopCount,o=r===wt;if(0===e)return-1===i?t:o&&1==(1&i)?n-t:t;if(r===_t){-1===i&&(this._loopCount=0,this._setEndings(!0,!0,!1));e:{if(t>=n)t=n;else{if(!(t<0)){this.time=t;break e}t=0}this.clampWhenFinished?this.paused=!0:this.enabled=!1,this.time=t,this._mixer.dispatchEvent({type:"finished",action:this,direction:e<0?-1:1})}}else{if(-1===i&&(e>=0?(i=0,this._setEndings(!0,0===this.repetitions,o)):this._setEndings(0===this.repetitions,!0,o)),t>=n||t<0){var a=Math.floor(t/n);t-=n*a,i+=Math.abs(a);var s=this.repetitions-i;if(s<=0)this.clampWhenFinished?this.paused=!0:this.enabled=!1,t=e>0?n:0,this.time=t,this._mixer.dispatchEvent({type:"finished",action:this,direction:e>0?1:-1});else{if(1===s){var c=e<0;this._setEndings(c,!c,o)}else this._setEndings(!1,!1,o);this._loopCount=i,this.time=t,this._mixer.dispatchEvent({type:"loop",action:this,loopDelta:a})}}else this.time=t;if(o&&1==(1&i))return n-t}return t},_setEndings:function(e,t,n){var r=this._interpolantSettings;n?(r.endingStart=At,r.endingEnd=At):(r.endingStart=e?this.zeroSlopeAtStart?At:St:Lt,r.endingEnd=t?this.zeroSlopeAtEnd?At:St:Lt)},_scheduleFading:function(e,t,n){var r=this._mixer,i=r.time,o=this._weightInterpolant;null===o&&(o=r._lendControlInterpolant(),this._weightInterpolant=o);var a=o.parameterPositions,s=o.sampleValues;return a[0]=i,s[0]=t,a[1]=i+e,s[1]=n,this}}),Yh.prototype=Object.assign(Object.create(gn.prototype),{constructor:Yh,_bindAction:function(e,t){var n=e._localRoot||this._root,r=e._clip.tracks,i=r.length,o=e._propertyBindings,a=e._interpolants,s=n.uuid,c=this._bindingsByRootAndName,l=c[s];void 0===l&&(l={},c[s]=l);for(var u=0;u!==i;++u){var h=r[u],d=h.name,p=l[d];if(void 0!==p)o[u]=p;else{if(void 0!==(p=o[u])){null===p._cacheIndex&&(++p.referenceCount,this._addInactiveBinding(p,s,d));continue}var f=t&&t._propertyBindings[u].binding.parsedPath;++(p=new Ih(Vh.create(n,d,f),h.ValueTypeName,h.getValueSize())).referenceCount,this._addInactiveBinding(p,s,d),o[u]=p}a[u].resultBuffer=p.buffer}},_activateAction:function(e){if(!this._isActiveAction(e)){if(null===e._cacheIndex){var t=(e._localRoot||this._root).uuid,n=e._clip.uuid,r=this._actionsByClip[n];this._bindAction(e,r&&r.knownActions[0]),this._addInactiveAction(e,n,t)}for(var i=e._propertyBindings,o=0,a=i.length;o!==a;++o){var s=i[o];0==s.useCount++&&(this._lendBinding(s),s.saveOriginalState())}this._lendAction(e)}},_deactivateAction:function(e){if(this._isActiveAction(e)){for(var t=e._propertyBindings,n=0,r=t.length;n!==r;++n){var i=t[n];0==--i.useCount&&(i.restoreOriginalState(),this._takeBackBinding(i))}this._takeBackAction(e)}},_initMemoryManager:function(){this._actions=[],this._nActiveActions=0,this._actionsByClip={},this._bindings=[],this._nActiveBindings=0,this._bindingsByRootAndName={},this._controlInterpolants=[],this._nActiveControlInterpolants=0;var e=this;this.stats={actions:{get total(){return e._actions.length},get inUse(){return e._nActiveActions}},bindings:{get total(){return e._bindings.length},get inUse(){return e._nActiveBindings}},controlInterpolants:{get total(){return e._controlInterpolants.length},get inUse(){return e._nActiveControlInterpolants}}}},_isActiveAction:function(e){var t=e._cacheIndex;return null!==t&&tthis.max.x||e.ythis.max.y)},containsBox:function(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},getParameter:function(e,t){return void 0===t&&(console.warn("THREE.Box2: .getParameter() target is now required"),t=new _n),t.set((e.x-this.min.x)/(this.max.x-this.min.x),(e.y-this.min.y)/(this.max.y-this.min.y))},intersectsBox:function(e){return!(e.max.xthis.max.x||e.max.ythis.max.y)},clampPoint:function(e,t){return void 0===t&&(console.warn("THREE.Box2: .clampPoint() target is now required"),t=new _n),t.copy(e).clamp(this.min,this.max)},distanceToPoint:function(e){return td.copy(e).clamp(this.min,this.max).sub(e).length()},intersect:function(e){return this.min.max(e.min),this.max.min(e.max),this},union:function(e){return this.min.min(e.min),this.max.max(e.max),this},translate:function(e){return this.min.add(e),this.max.add(e),this},equals:function(e){return e.min.equals(this.min)&&e.max.equals(this.max)}});var rd=new En,id=new En;function od(e,t){this.start=void 0!==e?e:new En,this.end=void 0!==t?t:new En}function ad(e){or.call(this),this.material=e,this.render=function(){}}Object.assign(od.prototype,{set:function(e,t){return this.start.copy(e),this.end.copy(t),this},clone:function(){return(new this.constructor).copy(this)},copy:function(e){return this.start.copy(e.start),this.end.copy(e.end),this},getCenter:function(e){return void 0===e&&(console.warn("THREE.Line3: .getCenter() target is now required"),e=new En),e.addVectors(this.start,this.end).multiplyScalar(.5)},delta:function(e){return void 0===e&&(console.warn("THREE.Line3: .delta() target is now required"),e=new En),e.subVectors(this.end,this.start)},distanceSq:function(){return this.start.distanceToSquared(this.end)},distance:function(){return this.start.distanceTo(this.end)},at:function(e,t){return void 0===t&&(console.warn("THREE.Line3: .at() target is now required"),t=new En),this.delta(t).multiplyScalar(e).add(this.start)},closestPointToPointParameter:function(e,t){rd.subVectors(e,this.start),id.subVectors(this.end,this.start);var n=id.dot(id),r=id.dot(rd)/n;return t&&(r=bn.clamp(r,0,1)),r},closestPointToPoint:function(e,t,n){var r=this.closestPointToPointParameter(e,t);return void 0===n&&(console.warn("THREE.Line3: .closestPointToPoint() target is now required"),n=new En),this.delta(n).multiplyScalar(r).add(this.start)},applyMatrix4:function(e){return this.start.applyMatrix4(e),this.end.applyMatrix4(e),this},equals:function(e){return e.start.equals(this.start)&&e.end.equals(this.end)}}),ad.prototype=Object.create(or.prototype),ad.prototype.constructor=ad,ad.prototype.isImmediateRenderObject=!0;var sd=new En,cd=new En,ld=new An,ud=["a","b","c"];function hd(e,t,n,r){this.object=e,this.size=void 0!==t?t:1;var i=void 0!==n?n:16711680,o=void 0!==r?r:1,a=0,s=this.object.geometry;s&&s.isGeometry?a=3*s.faces.length:s&&s.isBufferGeometry&&(a=s.attributes.normal.count);var c=new wi,l=new hi(2*a*3,3);c.setAttribute("position",l),oc.call(this,c,new Zs({color:i,linewidth:o})),this.matrixAutoUpdate=!1,this.update()}hd.prototype=Object.create(oc.prototype),hd.prototype.constructor=hd,hd.prototype.update=function(){this.object.updateMatrixWorld(!0),ld.getNormalMatrix(this.object.matrixWorld);var e=this.object.matrixWorld,t=this.geometry.attributes.position,n=this.object.geometry;if(n&&n.isGeometry)for(var r=n.vertices,i=n.faces,o=0,a=0,s=i.length;a1&&e.multiplyScalar(1/t),this.children[0].material.color.copy(this.material.color)}},bd.prototype.dispose=function(){this.geometry.dispose(),this.material.dispose(),this.children[0].geometry.dispose(),this.children[0].material.dispose()};var _d=new En,xd=new Jr,wd=new Jr;function Md(e,t,n){or.call(this),this.light=e,this.light.updateMatrixWorld(),this.matrix=e.matrixWorld,this.matrixAutoUpdate=!1,this.color=n;var r=new Sc(t);r.rotateY(.5*Math.PI),this.material=new ni({wireframe:!0,fog:!1}),void 0===this.color&&(this.material.vertexColors=M);var i=r.getAttribute("position"),o=new Float32Array(3*i.count);r.setAttribute("color",new ri(o,3)),this.add(new zi(r,this.material)),this.update()}function Ed(e,t){this.lightProbe=e,this.size=t;var n={GAMMA_OUTPUT:""},r=new to({defines:n,uniforms:{sh:{value:this.lightProbe.sh.coefficients},intensity:{value:this.lightProbe.intensity}},vertexShader:["varying vec3 vNormal;","void main() {","\\tvNormal = normalize( normalMatrix * normal );","\\tgl_Position = projectionMatrix * modelViewMatrix * vec4( position, 1.0 );","}"].join("\\n"),fragmentShader:["#define RECIPROCAL_PI 0.318309886","vec3 inverseTransformDirection( in vec3 normal, in mat4 matrix ) {","\\t// matrix is assumed to be orthogonal","\\treturn normalize( ( vec4( normal, 0.0 ) * matrix ).xyz );","}","vec3 linearToOutput( in vec3 a ) {","\\t#ifdef GAMMA_OUTPUT","\\t\\treturn pow( a, vec3( 1.0 / float( GAMMA_FACTOR ) ) );","\\t#else","\\t\\treturn a;","\\t#endif","}","// source: https://graphics.stanford.edu/papers/envmap/envmap.pdf","vec3 shGetIrradianceAt( in vec3 normal, in vec3 shCoefficients[ 9 ] ) {","\\t// normal is assumed to have unit length","\\tfloat x = normal.x, y = normal.y, z = normal.z;","\\t// band 0","\\tvec3 result = shCoefficients[ 0 ] * 0.886227;","\\t// band 1","\\tresult += shCoefficients[ 1 ] * 2.0 * 0.511664 * y;","\\tresult += shCoefficients[ 2 ] * 2.0 * 0.511664 * z;","\\tresult += shCoefficients[ 3 ] * 2.0 * 0.511664 * x;","\\t// band 2","\\tresult += shCoefficients[ 4 ] * 2.0 * 0.429043 * x * y;","\\tresult += shCoefficients[ 5 ] * 2.0 * 0.429043 * y * z;","\\tresult += shCoefficients[ 6 ] * ( 0.743125 * z * z - 0.247708 );","\\tresult += shCoefficients[ 7 ] * 2.0 * 0.429043 * x * z;","\\tresult += shCoefficients[ 8 ] * 0.429043 * ( x * x - y * y );","\\treturn result;","}","uniform vec3 sh[ 9 ]; // sh coefficients","uniform float intensity; // light probe intensity","varying vec3 vNormal;","void main() {","\\tvec3 normal = normalize( vNormal );","\\tvec3 worldNormal = inverseTransformDirection( normal, viewMatrix );","\\tvec3 irradiance = shGetIrradianceAt( worldNormal, sh );","\\tvec3 outgoingLight = RECIPROCAL_PI * irradiance * intensity;","\\toutgoingLight = linearToOutput( outgoingLight );","\\tgl_FragColor = vec4( outgoingLight, 1.0 );","}"].join("\\n")}),i=new ml(1,32,16);zi.call(this,i,r),this.onBeforeRender()}function Td(e,t,n,r){e=e||10,t=t||10,n=new Jr(void 0!==n?n:4473924),r=new Jr(void 0!==r?r:8947848);for(var i=t/2,o=e/t,a=e/2,s=[],c=[],l=0,u=0,h=-a;l<=t;l++,h+=o){s.push(-a,0,h,a,0,h),s.push(h,0,-a,h,0,a);var d=l===i?n:r;d.toArray(c,u),u+=3,d.toArray(c,u),u+=3,d.toArray(c,u),u+=3,d.toArray(c,u),u+=3}var p=new wi;p.setAttribute("position",new hi(s,3)),p.setAttribute("color",new hi(c,3));var f=new Zs({vertexColors:M});oc.call(this,p,f)}function Sd(e,t,n,r,i,o){e=e||10,t=t||16,n=n||8,r=r||64,i=new Jr(void 0!==i?i:4473924),o=new Jr(void 0!==o?o:8947848);var a,s,c,l,u,h,d,p=[],f=[];for(l=0;l<=t;l++)c=l/t*(2*Math.PI),a=Math.sin(c)*e,s=Math.cos(c)*e,p.push(0,0,0),p.push(a,0,s),d=1&l?i:o,f.push(d.r,d.g,d.b),f.push(d.r,d.g,d.b);for(l=0;l<=n;l++)for(d=1&l?i:o,h=e-e/n*l,u=0;u.99999)this.quaternion.set(0,0,0,1);else if(e.y<-.99999)this.quaternion.set(1,0,0,0);else{qd.set(e.z,0,-e.x).normalize();var t=Math.acos(e.y);this.quaternion.setFromAxisAngle(qd,t)}},Yd.prototype.setLength=function(e,t,n){void 0===t&&(t=.2*e),void 0===n&&(n=.2*t),this.line.scale.set(1,Math.max(1e-4,e-t),1),this.line.updateMatrix(),this.cone.scale.set(n,t,n),this.cone.position.y=e,this.cone.updateMatrix()},Yd.prototype.setColor=function(e){this.line.material.color.set(e),this.cone.material.color.set(e)},Yd.prototype.copy=function(e){return or.prototype.copy.call(this,e,!1),this.line.copy(e.line),this.cone.copy(e.cone),this},Yd.prototype.clone=function(){return(new this.constructor).copy(this)},Xd.prototype=Object.create(oc.prototype),Xd.prototype.constructor=Xd;var Zd=0,Kd=1;function Qd(e){return console.warn("THREE.MeshFaceMaterial has been removed. Use an Array instead."),e}function $d(e){return void 0===e&&(e=[]),console.warn("THREE.MultiMaterial has been removed. Use an Array instead."),e.isMultiMaterial=!0,e.materials=e,e.clone=function(){return e.slice()},e}function ep(e,t){return console.warn("THREE.PointCloud has been renamed to THREE.Points."),new dc(e,t)}function tp(e){return console.warn("THREE.Particle has been renamed to THREE.Sprite."),new Fs(e)}function np(e,t){return console.warn("THREE.ParticleSystem has been renamed to THREE.Points."),new dc(e,t)}function rp(e){return console.warn("THREE.PointCloudMaterial has been renamed to THREE.PointsMaterial."),new sc(e)}function ip(e){return console.warn("THREE.ParticleBasicMaterial has been renamed to THREE.PointsMaterial."),new sc(e)}function op(e){return console.warn("THREE.ParticleSystemMaterial has been renamed to THREE.PointsMaterial."),new sc(e)}function ap(e,t,n){return console.warn("THREE.Vertex has been removed. Use THREE.Vector3 instead."),new En(e,t,n)}function sp(e,t){return console.warn("THREE.DynamicBufferAttribute has been removed. Use new THREE.BufferAttribute().setDynamic( true ) instead."),new ri(e,t).setDynamic(!0)}function cp(e,t){return console.warn("THREE.Int8Attribute has been removed. Use new THREE.Int8BufferAttribute() instead."),new ii(e,t)}function lp(e,t){return console.warn("THREE.Uint8Attribute has been removed. Use new THREE.Uint8BufferAttribute() instead."),new oi(e,t)}function up(e,t){return console.warn("THREE.Uint8ClampedAttribute has been removed. Use new THREE.Uint8ClampedBufferAttribute() instead."),new ai(e,t)}function hp(e,t){return console.warn("THREE.Int16Attribute has been removed. Use new THREE.Int16BufferAttribute() instead."),new si(e,t)}function dp(e,t){return console.warn("THREE.Uint16Attribute has been removed. Use new THREE.Uint16BufferAttribute() instead."),new ci(e,t)}function pp(e,t){return console.warn("THREE.Int32Attribute has been removed. Use new THREE.Int32BufferAttribute() instead."),new li(e,t)}function fp(e,t){return console.warn("THREE.Uint32Attribute has been removed. Use new THREE.Uint32BufferAttribute() instead."),new ui(e,t)}function mp(e,t){return console.warn("THREE.Float32Attribute has been removed. Use new THREE.Float32BufferAttribute() instead."),new hi(e,t)}function gp(e,t){return console.warn("THREE.Float64Attribute has been removed. Use new THREE.Float64BufferAttribute() instead."),new di(e,t)}function vp(e){console.warn("THREE.ClosedSplineCurve3 has been deprecated. Use THREE.CatmullRomCurve3 instead."),Mu.call(this,e),this.type="catmullrom",this.closed=!0}function yp(e){console.warn("THREE.SplineCurve3 has been deprecated. Use THREE.CatmullRomCurve3 instead."),Mu.call(this,e),this.type="catmullrom"}function bp(e){console.warn("THREE.Spline has been removed. Use THREE.CatmullRomCurve3 instead."),Mu.call(this,e),this.type="catmullrom"}function _p(e){return console.warn("THREE.AxisHelper has been renamed to THREE.AxesHelper."),new Xd(e)}function xp(e,t){return console.warn("THREE.BoundingBoxHelper has been deprecated. Creating a THREE.BoxHelper instead."),new Gd(e,t)}function wp(e,t){return console.warn("THREE.EdgesHelper has been removed. Use THREE.EdgesGeometry instead."),new oc(new Ml(e.geometry),new Zs({color:void 0!==t?t:16777215}))}function Mp(e,t){return console.warn("THREE.WireframeHelper has been removed. Use THREE.WireframeGeometry instead."),new oc(new yc(e.geometry),new Zs({color:void 0!==t?t:16777215}))}function Ep(e){return console.warn("THREE.XHRLoader has been renamed to THREE.FileLoader."),new cu(e)}function Tp(e){return console.warn("THREE.BinaryTextureLoader has been renamed to THREE.DataTextureLoader."),new hu(e)}mu.create=function(e,t){return console.log("THREE.Curve.create() has been deprecated"),e.prototype=Object.create(mu.prototype),e.prototype.constructor=e,e.prototype.getPoint=t,e},Object.assign(Du.prototype,{createPointsGeometry:function(e){console.warn("THREE.CurvePath: .createPointsGeometry() has been removed. Use new THREE.Geometry().setFromPoints( points ) instead.");var t=this.getPoints(e);return this.createGeometry(t)},createSpacedPointsGeometry:function(e){console.warn("THREE.CurvePath: .createSpacedPointsGeometry() has been removed. Use new THREE.Geometry().setFromPoints( points ) instead.");var t=this.getSpacedPoints(e);return this.createGeometry(t)},createGeometry:function(e){console.warn("THREE.CurvePath: .createGeometry() has been removed. Use new THREE.Geometry().setFromPoints( points ) instead.");for(var t=new Yi,n=0,r=e.length;n=0?c.substring(0,l):c;u=u.toLowerCase();var h=l>=0?c.substring(l+1):"";if(h=h.trim(),"newmtl"===u)r={name:h},a[h]=r;else if("ka"===u||"kd"===u||"ks"===u||"ke"===u){var d=h.split(o,3);r[u]=[parseFloat(d[0]),parseFloat(d[1]),parseFloat(d[2])]}else r[u]=h}}var p=new i.MaterialCreator(this.resourcePath||t,this.materialOptions);return p.setCrossOrigin(this.crossOrigin),p.setManager(this.manager),p.setMaterials(a),p}}),i.MaterialCreator=function(e,t){this.baseUrl=e||"",this.options=t,this.materialsInfo={},this.materials={},this.materialsArray=[],this.nameLookup={},this.side=this.options&&this.options.side?this.options.side:r.FrontSide,this.wrap=this.options&&this.options.wrap?this.options.wrap:r.RepeatWrapping},i.MaterialCreator.prototype={constructor:i.MaterialCreator,crossOrigin:"anonymous",setCrossOrigin:function(e){return this.crossOrigin=e,this},setManager:function(e){this.manager=e},setMaterials:function(e){this.materialsInfo=this.convert(e),this.materials={},this.materialsArray=[],this.nameLookup={}},convert:function(e){if(!this.options)return e;var t={};for(var n in e){var r=e[n],i={};for(var o in t[n]=i,r){var a=!0,s=r[o],c=o.toLowerCase();switch(c){case"kd":case"ka":case"ks":this.options&&this.options.normalizeRGB&&(s=[s[0]/255,s[1]/255,s[2]/255]),this.options&&this.options.ignoreZeroRGBs&&0===s[0]&&0===s[1]&&0===s[2]&&(a=!1)}a&&(i[c]=s)}}return t},preload:function(){for(var e in this.materialsInfo)this.create(e)},getIndex:function(e){return this.nameLookup[e]},getAsArray:function(){var e=0;for(var t in this.materialsInfo)this.materialsArray[e]=this.create(t),this.nameLookup[t]=e,e++;return this.materialsArray},create:function(e){return void 0===this.materials[e]&&this.createMaterial_(e),this.materials[e]},createMaterial_:function(e){var t=this,n=this.materialsInfo[e],i={name:e,side:this.side};function o(e,n){if(!i[e]){var r,o,a=t.getTextureParams(n,i),s=t.loadTexture((r=t.baseUrl,"string"!=typeof(o=a.url)||""===o?"":/^https?:\\/\\//i.test(o)?o:r+o));s.repeat.copy(a.scale),s.offset.copy(a.offset),s.wrapS=t.wrap,s.wrapT=t.wrap,i[e]=s}}for(var a in n){var s,c=n[a];if(""!==c)switch(a.toLowerCase()){case"kd":i.color=(new r.Color).fromArray(c);break;case"ks":i.specular=(new r.Color).fromArray(c);break;case"ke":i.emissive=(new r.Color).fromArray(c);break;case"map_kd":o("map",c);break;case"map_ks":o("specularMap",c);break;case"map_ke":o("emissiveMap",c);break;case"norm":o("normalMap",c);break;case"map_bump":case"bump":o("bumpMap",c);break;case"map_d":o("alphaMap",c),i.transparent=!0;break;case"ns":i.shininess=parseFloat(c);break;case"d":(s=parseFloat(c))<1&&(i.opacity=s,i.transparent=!0);break;case"tr":s=parseFloat(c),this.options&&this.options.invertTrProperty&&(s=1-s),s>0&&(i.opacity=1-s,i.transparent=!0)}}return this.materials[e]=new r.MeshPhongMaterial(i),this.materials[e]},getTextureParams:function(e,t){var n,i={scale:new r.Vector2(1,1),offset:new r.Vector2(0,0)},o=e.split(/\\s+/);return(n=o.indexOf("-bm"))>=0&&(t.bumpScale=parseFloat(o[n+1]),o.splice(n,2)),(n=o.indexOf("-s"))>=0&&(i.scale.set(parseFloat(o[n+1]),parseFloat(o[n+2])),o.splice(n,4)),(n=o.indexOf("-o"))>=0&&(i.offset.set(parseFloat(o[n+1]),parseFloat(o[n+2])),o.splice(n,4)),i.url=o.join(" ").trim(),i},loadTexture:function(e,t,n,i,o){var a,s=void 0!==this.manager?this.manager:r.DefaultLoadingManager,c=s.getHandler(e);return null===c&&(c=new r.TextureLoader(s)),c.setCrossOrigin&&c.setCrossOrigin(this.crossOrigin),a=c.load(e,n,i,o),void 0!==t&&(a.mapping=t),a}}},function(e,t,n){var r=n(6).ExtBuffer,i=n(35),o=n(36),a=n(3);function s(){var e=this.options;return this.encode=function(e){var t=o.getWriteType(e);return function(e,n){var r=t[typeof n];if(!r)throw new Error('Unsupported type "'+typeof n+'": '+n);r(e,n)}}(e),e&&e.preset&&i.setExtPackers(this),this}a.install({addExtPacker:function(e,t,n){n=a.filter(n);var i=t.name;if(i&&"Object"!==i){(this.extPackers||(this.extPackers={}))[i]=o}else{(this.extEncoderList||(this.extEncoderList=[])).unshift([t,o])}function o(t){return n&&(t=n(t)),new r(t,e)}},getExtPacker:function(e){var t=this.extPackers||(this.extPackers={}),n=e.constructor,r=n&&n.name&&t[n.name];if(r)return r;for(var i=this.extEncoderList||(this.extEncoderList=[]),o=i.length,a=0;a>1,u=-7,h=n?i-1:0,d=n?-1:1,p=e[t+h];for(h+=d,o=p&(1<<-u)-1,p>>=-u,u+=s;u>0;o=256*o+e[t+h],h+=d,u-=8);for(a=o&(1<<-u)-1,o>>=-u,u+=r;u>0;a=256*a+e[t+h],h+=d,u-=8);if(0===o)o=1-l;else{if(o===c)return a?NaN:1/0*(p?-1:1);a+=Math.pow(2,r),o-=l}return(p?-1:1)*a*Math.pow(2,o-r)},t.write=function(e,t,n,r,i,o){var a,s,c,l=8*o-i-1,u=(1<>1,d=23===i?Math.pow(2,-24)-Math.pow(2,-77):0,p=r?0:o-1,f=r?1:-1,m=t<0||0===t&&1/t<0?1:0;for(t=Math.abs(t),isNaN(t)||t===1/0?(s=isNaN(t)?1:0,a=u):(a=Math.floor(Math.log(t)/Math.LN2),t*(c=Math.pow(2,-a))<1&&(a--,c*=2),(t+=a+h>=1?d/c:d*Math.pow(2,1-h))*c>=2&&(a++,c/=2),a+h>=u?(s=0,a=u):a+h>=1?(s=(t*c-1)*Math.pow(2,i),a+=h):(s=t*Math.pow(2,h-1)*Math.pow(2,i),a=0));i>=8;e[n+p]=255&s,p+=f,s/=256,i-=8);for(a=a<0;e[n+p]=255&a,p+=f,a/=256,l-=8);e[n+p-f]|=128*m}},function(e,t,n){var r,i=n(34);t.copy=l,t.slice=u,t.toString=function(e,t,n){return(!s&&o.isBuffer(this)?this.toString:i.toString).apply(this,arguments)},t.write=(r="write",function(){return(this[r]||i[r]).apply(this,arguments)});var o=n(1),a=o.global,s=o.hasBuffer&&"TYPED_ARRAY_SUPPORT"in a,c=s&&!a.TYPED_ARRAY_SUPPORT;function l(e,t,n,r){var a=o.isBuffer(this),s=o.isBuffer(e);if(a&&s)return this.copy(e,t,n,r);if(c||a||s||!o.isView(this)||!o.isView(e))return i.copy.call(this,e,t,n,r);var l=n||null!=r?u.call(this,n,r):this;return e.set(l,t),l.length}function u(e,t){var n=this.slice||!c&&this.subarray;if(n)return n.call(this,e,t);var r=o.alloc.call(this,t-e);return l.call(this,r,0,e,t),r}},function(e,t,n){(function(e){!function(t){var n,r="undefined",i=r!==typeof e&&e,o=r!==typeof Uint8Array&&Uint8Array,a=r!==typeof ArrayBuffer&&ArrayBuffer,s=[0,0,0,0,0,0,0,0],c=Array.isArray||function(e){return!!e&&"[object Array]"==Object.prototype.toString.call(e)},l=4294967296,u=16777216;function h(e,c,h){var w=c?0:4,M=c?4:0,E=c?0:3,T=c?1:2,S=c?2:1,A=c?3:0,L=c?y:_,C=c?b:x,R=N.prototype,P="is"+e,O="_"+P;return R.buffer=void 0,R.offset=0,R[O]=!0,R.toNumber=I,R.toString=function(e){var t=this.buffer,n=this.offset,r=B(t,n+w),i=B(t,n+M),o="",a=!h&&2147483648&r;a&&(r=~r,i=l-i);e=e||10;for(;;){var s=r%e*l+i;if(r=Math.floor(r/e),i=Math.floor(s/e),o=(s%e).toString(e)+o,!r&&!i)break}a&&(o="-"+o);return o},R.toJSON=I,R.toArray=d,i&&(R.toBuffer=p),o&&(R.toArrayBuffer=f),N[P]=function(e){return!(!e||!e[O])},t[e]=N,N;function N(e,t,i,c){return this instanceof N?function(e,t,i,c,u){o&&a&&(t instanceof a&&(t=new o(t)),c instanceof a&&(c=new o(c)));if(!(t||i||c||n))return void(e.buffer=v(s,0));if(!m(t,i)){u=i,c=t,i=0,t=new(n||Array)(8)}if(e.buffer=t,e.offset=i|=0,r===typeof c)return;"string"==typeof c?function(e,t,n,r){var i=0,o=n.length,a=0,s=0;"-"===n[0]&&i++;var c=i;for(;i=0))break;s=s*r+u,a=a*r+Math.floor(s/l),s%=l}c&&(a=~a,s?s=l-s:a++);D(e,t+w,a),D(e,t+M,s)}(t,i,c,u||10):m(c,u)?g(t,i,c,u):"number"==typeof u?(D(t,i+w,c),D(t,i+M,u)):c>0?L(t,i,c):c<0?C(t,i,c):g(t,i,s,0)}(this,e,t,i,c):new N(e,t,i,c)}function I(){var e=this.buffer,t=this.offset,n=B(e,t+w),r=B(e,t+M);return h||(n|=0),n?n*l+r:r}function D(e,t,n){e[t+A]=255&n,n>>=8,e[t+S]=255&n,n>>=8,e[t+T]=255&n,n>>=8,e[t+E]=255&n}function B(e,t){return e[t+E]*u+(e[t+T]<<16)+(e[t+S]<<8)+e[t+A]}}function d(e){var t=this.buffer,r=this.offset;return n=null,!1!==e&&0===r&&8===t.length&&c(t)?t:v(t,r)}function p(t){var r=this.buffer,o=this.offset;if(n=i,!1!==t&&0===o&&8===r.length&&e.isBuffer(r))return r;var a=new i(8);return g(a,0,r,o),a}function f(e){var t=this.buffer,r=this.offset,i=t.buffer;if(n=o,!1!==e&&0===r&&i instanceof a&&8===i.byteLength)return i;var s=new o(8);return g(s,0,t,r),s.buffer}function m(e,t){var n=e&&e.length;return t|=0,n&&t+8<=n&&"string"!=typeof e[t]}function g(e,t,n,r){t|=0,r|=0;for(var i=0;i<8;i++)e[t++]=255&n[r++]}function v(e,t){return Array.prototype.slice.call(e,t,t+8)}function y(e,t,n){for(var r=t+8;r>t;)e[--r]=255&n,n/=256}function b(e,t,n){var r=t+8;for(n++;r>t;)e[--r]=255&-n^255,n/=256}function _(e,t,n){for(var r=t+8;t>5&31)/31,i=(w>>10&31)/31):(t=a,n=s,i=c)}for(var M=1;M<=3;M++){var E=y+12*M,T=3*v*3+3*(M-1);m[T]=u.getFloat32(E,!0),m[T+1]=u.getFloat32(E+4,!0),m[T+2]=u.getFloat32(E+8,!0),g[T]=b,g[T+1]=_,g[T+2]=x,d&&(o[T]=t,o[T+1]=n,o[T+2]=i)}}return f.setAttribute("position",new r.BufferAttribute(m,3)),f.setAttribute("normal",new r.BufferAttribute(g,3)),d&&(f.setAttribute("color",new r.BufferAttribute(o,3)),f.hasColors=!0,f.alpha=l),f}(i):function(e){for(var t,n=new r.BufferGeometry,i=/solid([\\s\\S]*?)endsolid/g,o=/facet([\\s\\S]*?)endfacet/g,a=0,s=/[\\s]+([+-]?(?:\\d*)(?:\\.\\d*)?(?:[eE][+-]?\\d+)?)/.source,c=new RegExp("vertex"+s+s+s,"g"),l=new RegExp("normal"+s+s+s,"g"),u=[],h=[],d=new r.Vector3,p=[],f=0,m=0,g=0;null!==(t=i.exec(e));){m=g;for(var v=t[0];null!==(t=o.exec(v));){for(var y=0,b=0,_=t[0];null!==(t=l.exec(_));)d.x=parseFloat(t[1]),d.y=parseFloat(t[2]),d.z=parseFloat(t[3]),b++;for(;null!==(t=c.exec(_));)u.push(parseFloat(t[1]),parseFloat(t[2]),parseFloat(t[3])),h.push(d.x,d.y,d.z),y++,g++;1!==b&&console.error("THREE.STLLoader: Something isn't right with the normal of face number "+a),3!==y&&console.error("THREE.STLLoader: Something isn't right with the vertices of face number "+a),a++}p.push({startVertex:m,endVertex:g}),f++}if(n.setAttribute("position",new r.Float32BufferAttribute(u,3)),n.setAttribute("normal",new r.Float32BufferAttribute(h,3)),f>0)for(var x=0;x0?"\\n\\tmaterialNames:\\n\\t\\t- "+e.join("\\n\\t\\t- "):"\\n\\tmaterialNames: None")+"\\n\\tmaterialPerSmoothingGroup: "+this.materialPerSmoothingGroup+"\\n\\tuseOAsMesh: "+this.useOAsMesh+"\\n\\tuseIndices: "+this.useIndices+"\\n\\tdisregardNormals: "+this.disregardNormals;t+="\\n\\tcallbacks.onProgress: "+this.callbacks.onProgress.name,t+="\\n\\tcallbacks.onAssetAvailable: "+this.callbacks.onAssetAvailable.name,t+="\\n\\tcallbacks.onError: "+this.callbacks.onError.name,console.info(t)}},execute:function(e){this.logging.enabled&&console.time("OBJLoader2Parser.execute"),this._configure();let t=new Uint8Array(e);this.contentRef=t;let n=t.byteLength;this.globalCounts.totalBytes=n;let r=new Array(128);for(let e,i="",o=0,a=0,s=0;s0&&(r[o++]=i),i="";break;case 47:i.length>0&&(r[o++]=i),a++,i="";break;case 10:i.length>0&&(r[o++]=i),i="",this.globalCounts.lineByte=this.globalCounts.currentByte,this.globalCounts.currentByte=s,this._processLine(r,o,a),o=0,a=0;break;case 13:break;default:i+=String.fromCharCode(e)}this._finalizeParsing(),this.logging.enabled&&console.timeEnd("OBJLoader2Parser.execute")},executeLegacy:function(e){this.logging.enabled&&console.time("OBJLoader2Parser.executeLegacy"),this._configure(),this.legacyMode=!0,this.contentRef=e;let t=e.length;this.globalCounts.totalBytes=t;let n=new Array(128);for(let r,i="",o=0,a=0,s=0;s0&&(n[o++]=i),i="";break;case"/":i.length>0&&(n[o++]=i),a++,i="";break;case"\\n":i.length>0&&(n[o++]=i),i="",this.globalCounts.lineByte=this.globalCounts.currentByte,this.globalCounts.currentByte=s,this._processLine(n,o,a),o=0,a=0;break;case"\\r":break;default:i+=r}this._finalizeParsing(),this.logging.enabled&&console.timeEnd("OBJLoader2Parser.executeLegacy")},_processLine:function(e,t,n){if(t<1)return;let r,i,o,a,s=function(e,t,n,r){let i="";if(r>n){let o;if(t)for(o=n;o4&&(this.colors.push(parseFloat(e[4])),this.colors.push(parseFloat(e[5])),this.colors.push(parseFloat(e[6])));break;case"vt":this.uvs.push(parseFloat(e[1])),this.uvs.push(parseFloat(e[2]));break;case"vn":this.normals.push(parseFloat(e[1])),this.normals.push(parseFloat(e[2])),this.normals.push(parseFloat(e[3]));break;case"f":if(r=t-1,0===n)for(this._checkFaceType(0),o=2,i=r;o0?o-1:o+i.vertices.length/3),s=i.colors.length>0?a:null,c=r.vertices;if(c.push(i.vertices[a++]),c.push(i.vertices[a++]),c.push(i.vertices[a]),null!==s){let e=r.colors;e.push(i.colors[s++]),e.push(i.colors[s++]),e.push(i.colors[s])}if(t){let e=parseInt(t),n=2*(e>0?e-1:e+i.uvs.length/2),o=r.uvs;o.push(i.uvs[n++]),o.push(i.uvs[n])}if(n&&!i.disregardNormals){let e=parseInt(n),t=3*(e>0?e-1:e+i.normals.length/3),o=r.normals;o.push(i.normals[t++]),o.push(i.normals[t++]),o.push(i.normals[t])}};if(this.useIndices){this.disregardNormals&&(n=void 0);let i=e+(t?"_"+t:"_n")+(n?"_"+n:"_n"),a=r.indexMappings[i];null==a?(a=this.rawMesh.subGroupInUse.vertices.length/3,o(),r.indexMappings[i]=a,r.indexMappingsCount++):this.rawMesh.counts.doubleIndicesCount++,r.indices.push(a)}else o();this.rawMesh.counts.faceCount++},_createRawMeshReport:function(e){return"Input Object number: "+e+"\\n\\tObject name: "+this.rawMesh.objectName+"\\n\\tGroup name: "+this.rawMesh.groupName+"\\n\\tMtllib name: "+this.rawMesh.mtllibName+"\\n\\tVertex count: "+this.vertices.length/3+"\\n\\tNormal count: "+this.normals.length/3+"\\n\\tUV count: "+this.uvs.length/2+"\\n\\tSmoothingGroup count: "+this.rawMesh.counts.smoothingGroupCount+"\\n\\tMaterial count: "+this.rawMesh.counts.mtlCount+"\\n\\tReal MeshOutputGroup count: "+this.rawMesh.subGroups.length},_finalizeRawMesh:function(){let e,t,n=[],r=0,i=0,o=0,a=0,s=0,c=0;for(let l in this.rawMesh.subGroups)if(e=this.rawMesh.subGroups[l],e.vertices.length>0){if(t=e.indices,t.length>0&&i>0)for(let e=0;e0&&(l={name:""!==this.rawMesh.groupName?this.rawMesh.groupName:this.rawMesh.objectName,subGroups:n,absoluteVertexCount:r,absoluteIndexCount:o,absoluteColorCount:a,absoluteNormalCount:s,absoluteUvCount:c,faceCount:this.rawMesh.counts.faceCount,doubleIndicesCount:this.rawMesh.counts.doubleIndicesCount}),l},_processCompletedMesh:function(){let e=this._finalizeRawMesh(),t=null!==e;if(t){this.colors.length>0&&this.colors.length!==this.vertices.length&&this.callbacks.onError("Vertex Colors were detected, but vertex count and color count do not match!"),this.logging.enabled&&this.logging.debug&&console.debug(this._createRawMeshReport(this.inputObjectCount)),this.inputObjectCount++,this._buildMesh(e);let t=this.globalCounts.currentByte/this.globalCounts.totalBytes;this._onProgress("Completed [o: "+this.rawMesh.objectName+" g:"+this.rawMesh.groupName+"] Total progress: "+(100*t).toFixed(2)+"%"),this._resetRawMesh()}return t},_buildMesh:function(e){let t=e.subGroups,n=new Float32Array(e.absoluteVertexCount);this.globalCounts.vertices+=e.absoluteVertexCount/3,this.globalCounts.faces+=e.faceCount,this.globalCounts.doubleIndicesCount+=e.doubleIndicesCount;let r,i,o,a,s,c,l,u=e.absoluteIndexCount>0?new Uint32Array(e.absoluteIndexCount):null,h=e.absoluteColorCount>0?new Float32Array(e.absoluteColorCount):null,d=e.absoluteNormalCount>0?new Float32Array(e.absoluteNormalCount):null,p=e.absoluteUvCount>0?new Float32Array(e.absoluteUvCount):null,f=null!==h,m=[],g=t.length>1,v=0,y=[],b=[],_=0,x=0,w=0,M=0,E=0,T=0,S=0;for(let e in t)if(t.hasOwnProperty(e)){if(r=t[e],l=r.materialName,c=this.rawMesh.faceType<4?l+(f?"_vertexColor":"")+(0===r.smoothingGroup?"_flat":""):6===this.rawMesh.faceType?"defaultPointMaterial":"defaultLineMaterial",a=this.materials[l],s=this.materials[c],null==a&&null==s&&(c=f?"defaultVertexColorMaterial":"defaultMaterial",s=this.materials[c],this.logging.enabled&&console.info('object_group "'+r.objectName+"_"+r.groupName+'" was defined with unresolvable material "'+l+'"! Assigning "'+c+'".')),null==s){let e={materialNameOrg:l,materialName:c,materialProperties:{vertexColors:f?2:0,flatShading:0===r.smoothingGroup}},t={cmd:"assetAvailable",type:"material",materials:{materialCloneInstructions:e}};this.callbacks.onAssetAvailable(t);let n=this.materials[c];null==n&&(this.materials[c]=e)}if(g?(i=y[c],i||(i=v,y[c]=v,m.push(c),v++),S=this.useIndices?r.indices.length:r.vertices.length/3,o={start:T,count:S,index:i},b.push(o),T+=S):m.push(c),n.set(r.vertices,_),_+=r.vertices.length,u&&(u.set(r.indices,x),x+=r.indices.length),h&&(h.set(r.colors,w),w+=r.colors.length),d&&(d.set(r.normals,M),M+=r.normals.length),p&&(p.set(r.uvs,E),E+=r.uvs.length),this.logging.enabled&&this.logging.debug){let e=null==i?"":"\\n\\t\\tmaterialIndex: "+i,t="\\tOutput Object no.: "+this.outputObjectCount+"\\n\\t\\tgroupName: "+r.groupName+"\\n\\t\\tIndex: "+r.index+"\\n\\t\\tfaceType: "+this.rawMesh.faceType+"\\n\\t\\tmaterialName: "+r.materialName+"\\n\\t\\tsmoothingGroup: "+r.smoothingGroup+e+"\\n\\t\\tobjectName: "+r.objectName+"\\n\\t\\t#vertices: "+r.vertices.length/3+"\\n\\t\\t#indices: "+r.indices.length+"\\n\\t\\t#colors: "+r.colors.length/3+"\\n\\t\\t#uvs: "+r.uvs.length/2+"\\n\\t\\t#normals: "+r.normals.length/3;console.debug(t)}}this.outputObjectCount++,this.callbacks.onAssetAvailable({cmd:"assetAvailable",type:"mesh",progress:{numericalValue:this.globalCounts.currentByte/this.globalCounts.totalBytes},params:{meshName:e.name},materials:{multiMaterial:g,materialNames:m,materialGroups:b},buffers:{vertices:n,indices:u,colors:h,normals:d,uvs:p},geometryType:this.rawMesh.faceType<4?0:6===this.rawMesh.faceType?2:1},[n.buffer],null!==u?[u.buffer]:null,null!==h?[h.buffer]:null,null!==d?[d.buffer]:null,null!==p?[p.buffer]:null)},_finalizeParsing:function(){if(this.logging.enabled&&console.info("Global output object count: "+this.outputObjectCount),this._processCompletedMesh()&&this.logging.enabled){let e="Overall counts: \\n\\tVertices: "+this.globalCounts.vertices+"\\n\\tFaces: "+this.globalCounts.faces+"\\n\\tMultiple definitions: "+this.globalCounts.doubleIndicesCount;console.info(e)}}};const o=function(e){this.logging={enabled:!1,debug:!1},this.callbacks={onProgress:null,onMeshAlter:null},this.materialHandler=e};o.prototype={constructor:o,setLogging:function(e,t){this.logging.enabled=!0===e,this.logging.debug=!0===t},_setCallbacks:function(e,t){null!=e&&e instanceof Function&&(this.callbacks.onProgress=e),null!=t&&t instanceof Function&&(this.callbacks.onMeshAlter=t)},buildMeshes:function(e){let t,n,i,o=e.params.meshName,a=e.buffers,s=new r.BufferGeometry;void 0!==a.vertices&&null!==a.vertices&&s.setAttribute("position",new r.BufferAttribute(new Float32Array(a.vertices),3)),void 0!==a.indices&&null!==a.indices&&s.setIndex(new r.BufferAttribute(new Uint32Array(a.indices),1)),void 0!==a.colors&&null!==a.colors&&s.setAttribute("color",new r.BufferAttribute(new Float32Array(a.colors),3)),void 0!==a.normals&&null!==a.normals?s.setAttribute("normal",new r.BufferAttribute(new Float32Array(a.normals),3)):s.computeVertexNormals(),void 0!==a.uvs&&null!==a.uvs&&s.setAttribute("uv",new r.BufferAttribute(new Float32Array(a.uvs),2)),void 0!==a.skinIndex&&null!==a.skinIndex&&s.setAttribute("skinIndex",new r.BufferAttribute(new Uint16Array(a.skinIndex),4)),void 0!==a.skinWeight&&null!==a.skinWeight&&s.setAttribute("skinWeight",new r.BufferAttribute(new Float32Array(a.skinWeight),4));let c=e.materials.materialNames,l=e.materials.multiMaterial,u=[];for(i in c)n=c[i],t=this.materialHandler.getMaterial(n),l&&u.push(t);if(l){t=u;let n,r=e.materials.materialGroups;for(i in r)n=r[i],s.addGroup(n.start,n.count,n.index)}let h,d,p=[],f=!0,m=null===e.geometryType?0:e.geometryType;if(this.callbacks.onMeshAlter&&(d=this.callbacks.onMeshAlter({detail:{meshName:o,bufferGeometry:s,material:t,geometryType:m}})),d)if(d.isDisregardMesh())f=!1;else if(d.providesAlteredMeshes()){for(let e in d.meshes)p.push(d.meshes[e]);f=!1}f&&(e.computeBoundingSphere&&s.computeBoundingSphere(),h=0===m?new r.Mesh(s,t):1===m?new r.LineSegments(s,t):new r.Points(s,t),h.name=o,p.push(h));let g=e.params.meshName;if(p.length>0){let t=[];for(let e in p)h=p[e],t[e]=h.name;g+=": Adding mesh(es) ("+t.length+": "+t+") from input mesh: "+o,g+=" ("+(100*e.progress.numericalValue).toFixed(2)+"%)"}else g+=": Not adding mesh: "+o,g+=" ("+(100*e.progress.numericalValue).toFixed(2)+"%)";return this.callbacks.onProgress&&this.callbacks.onProgress("progress",g,e.progress.numericalValue),p}};const a=function(e,t){this.disregardMesh=!0===e,this.alteredMesh=!0===t,this.meshes=[]};a.prototype={constructor:a,addMesh:function(e){this.meshes.push(e),this.alteredMesh=!0},isDisregardMesh:function(){return this.disregardMesh},providesAlteredMeshes:function(){return this.alteredMesh}};const s=function(){this.logging={enabled:!1,debug:!1},this.callbacks={onLoadMaterials:null},this.materials={}};s.prototype={constructor:s,setLogging:function(e,t){this.logging.enabled=!0===e,this.logging.debug=!0===t},_setCallbacks:function(e){null!=e&&e instanceof Function&&(this.callbacks.onLoadMaterials=e)},createDefaultMaterials:function(e){let t=new r.MeshStandardMaterial({color:14479871});t.name="defaultMaterial";let n=new r.MeshStandardMaterial({color:14479871});n.name="defaultVertexColorMaterial",n.vertexColors=r.VertexColors;let i=new r.LineBasicMaterial;i.name="defaultLineMaterial";let o=new r.PointsMaterial({size:.1});o.name="defaultPointMaterial";let a={};a[t.name]=t,a[n.name]=n,a[i.name]=i,a[o.name]=o,this.addMaterials(a,e)},addPayloadMaterials:function(e){let t,n,i=e.materials.materialCloneInstructions,o={};if(null!=i){let e=i.materialNameOrg;e=null!=e?e:"";let r=this.materials[e];r?(t=r.clone(),n=i.materialName,t.name=n,Object.assign(t,i.materialProperties),this.materials[n]=t,o[n]=t):this.logging.enabled&&console.info('Requested material "'+e+'" is not available!')}let a=e.materials.serializedMaterials;if(null!=a&&Object.keys(a).length>0){let e,i=new r.MaterialLoader;for(n in a)e=a[n],null!=e&&(t=i.parse(e),this.logging.enabled&&console.info('De-serialized material with name "'+n+'" will be added.'),this.materials[n]=t,o[n]=t)}return a=e.materials.runtimeMaterials,o=this.addMaterials(a,!0,o),o},addMaterials:function(e,t,n){if(null==n&&(n={}),null!=e&&Object.keys(e).length>0){let r,i,o;for(let a in e)r=e[a],o=!0===t,o||(i=this.materials[a],o=null==i),o&&(this.materials[a]=r,n[a]=r),this.logging.enabled&&this.logging.debug&&console.info('Material with name "'+a+'" was added.')}return this.callbacks.onLoadMaterials&&this.callbacks.onLoadMaterials(n),n},getMaterials:function(){return this.materials},getMaterial:function(e){return this.materials[e]},getMaterialsJSON:function(){let e,t={};for(let n in this.materials)e=this.materials[n],t[n]=e.toJSON();return t},clearMaterials:function(){this.materials={}}},n.d(t,"a",(function(){return c}));const c=function(e){r.Loader.call(this,e),this.parser=new i,this.modelName="",this.instanceNo=0,this.baseObject3d=new r.Object3D,this.materialHandler=new s,this.meshReceiver=new o(this.materialHandler);let t=this;this.parser.setCallbackOnAssetAvailable((function(e){t._onAssetAvailable(e)}))};c.OBJLOADER2_VERSION="3.1.1",console.info("Using OBJLoader2 version: "+c.OBJLOADER2_VERSION),c.prototype=Object.assign(Object.create(r.Loader.prototype),{constructor:c,setLogging:function(e,t){return this.parser.setLogging(e,t),this},setMaterialPerSmoothingGroup:function(e){return this.parser.setMaterialPerSmoothingGroup(e),this},setUseOAsMesh:function(e){return this.parser.setUseOAsMesh(e),this},setUseIndices:function(e){return this.parser.setUseIndices(e),this},setDisregardNormals:function(e){return this.parser.setDisregardNormals(e),this},setModelName:function(e){return this.modelName=e||this.modelName,this},setBaseObject3d:function(e){return this.baseObject3d=null==e?this.baseObject3d:e,this},addMaterials:function(e,t){return this.materialHandler.addMaterials(e,t),this},setCallbackOnAssetAvailable:function(e){return this.parser.setCallbackOnAssetAvailable(e),this},setCallbackOnProgress:function(e){return this.parser.setCallbackOnProgress(e),this},setCallbackOnError:function(e){return this.parser.setCallbackOnError(e),this},setCallbackOnLoad:function(e){return this.parser.setCallbackOnLoad(e),this},setCallbackOnMeshAlter:function(e){return this.meshReceiver._setCallbacks(this.parser.callbacks.onProgress,e),this},setCallbackOnLoadMaterials:function(e){return this.materialHandler._setCallbacks(e),this},load:function(e,t,n,i,o){let a=this;if(!(null!=t&&t instanceof Function)){let e="onLoad is not a function! Aborting...";throw a.parser.callbacks.onError(e),e}this.parser.setCallbackOnLoad(t),null!=i&&i instanceof Function||(i=function(e){let t=e;e.currentTarget&&null!==e.currentTarget.statusText&&(t="Error occurred while downloading!\\nurl: "+e.currentTarget.responseURL+"\\nstatus: "+e.currentTarget.statusText),a.parser.callbacks.onError(t)}),e||i("An invalid url was provided. Unable to continue!");let s=new URL(e,window.location.href).href,c=s,l=s.split("/");if(l.length>2){c=l[l.length-1];let e=l.slice(0,l.length-1).join("/")+"/";null!=e&&(this.path=e)}if(null==n||!(n instanceof Function)){let t=0,r=0;n=function(n){if(n.lengthComputable&&(r=n.loaded/n.total,r>t)){t=r;let n='Download of "'+e+'": '+(100*r).toFixed(2)+"%";a.parser.callbacks.onProgress("progressLoad",n,r)}}}this.setCallbackOnMeshAlter(o);let u=new r.FileLoader(this.manager);u.setPath(this.path||this.resourcePath),u.setResponseType("arraybuffer"),u.load(c,(function(e){a.parser.callbacks.onLoad(a.parse(e),"OBJLoader2#load: Parsing completed")}),n,i)},parse:function(e){if(null==e)throw"Provided content is not a valid ArrayBuffer or String. Unable to continue parsing";return this.parser.logging.enabled&&console.time("OBJLoader parse: "+this.modelName),this.materialHandler.createDefaultMaterials(!1),this.parser.setMaterials(this.materialHandler.getMaterials()),e instanceof ArrayBuffer||e instanceof Uint8Array?(this.parser.logging.enabled&&console.info("Parsing arrayBuffer..."),this.parser.execute(e)):"string"==typeof e||e instanceof String?(this.parser.logging.enabled&&console.info("Parsing text..."),this.parser.executeLegacy(e)):this.parser.callbacks.onError("Provided content was neither of type String nor Uint8Array! Aborting..."),this.parser.logging.enabled&&console.timeEnd("OBJLoader parse: "+this.modelName),this.baseObject3d},_onAssetAvailable:function(e){if("assetAvailable"===e.cmd)if("mesh"===e.type){let t=this.meshReceiver.buildMeshes(e);for(let e of t)this.baseObject3d.add(e)}else"material"===e.type&&this.materialHandler.addPayloadMaterials(e)}})},function(e,t,n){"use strict";var r=n(0),i=function(e){r.Loader.call(this,e)};i.prototype=Object.assign(Object.create(r.Loader.prototype),{constructor:i,load:function(e,t,n,i){var o=this,a=new r.Texture,s=new r.FileLoader(this.manager);return s.setResponseType("arraybuffer"),s.setPath(this.path),s.load(e,(function(e){a.image=o.parse(e),a.needsUpdate=!0,void 0!==t&&t(a)}),n,i),a},parse:function(e){var t=0,n=1,r=2,i=3,o=9,a=10,s=11,c=48,l=4,u=0,h=1,d=2,p=3;e.length<19&&console.error("THREE.TGALoader: Not enough data to contain header.");var f=new Uint8Array(e),m=0,g={id_length:f[m++],colormap_type:f[m++],image_type:f[m++],colormap_index:f[m++]|f[m++]<<8,colormap_length:f[m++]|f[m++]<<8,colormap_size:f[m++],origin:[f[m++]|f[m++]<<8,f[m++]|f[m++]<<8],width:f[m++]|f[m++]<<8,height:f[m++]|f[m++]<<8,pixel_size:f[m++],flags:f[m++]};!function(e){switch(e.image_type){case n:case o:(e.colormap_length>256||24!==e.colormap_size||1!==e.colormap_type)&&console.error("THREE.TGALoader: Invalid type colormap data for indexed type.");break;case r:case i:case a:case s:e.colormap_type&&console.error("THREE.TGALoader: Invalid type colormap data for colormap type.");break;case t:console.error("THREE.TGALoader: No data.");default:console.error('THREE.TGALoader: Invalid type "%s".',e.image_type)}(e.width<=0||e.height<=0)&&console.error("THREE.TGALoader: Invalid image size."),8!==e.pixel_size&&16!==e.pixel_size&&24!==e.pixel_size&&32!==e.pixel_size&&console.error('THREE.TGALoader: Invalid pixel size "%s".',e.pixel_size)}(g),g.id_length+m>e.length&&console.error("THREE.TGALoader: No data."),m+=g.id_length;var v=!1,y=!1,b=!1;switch(g.image_type){case o:v=!0,y=!0;break;case n:y=!0;break;case a:v=!0;break;case r:break;case s:v=!0,b=!0;break;case i:b=!0}var _="undefined"!=typeof OffscreenCanvas,x=_?new OffscreenCanvas(g.width,g.height):document.createElement("canvas");x.width=g.width,x.height=g.height;var w=x.getContext("2d"),M=w.createImageData(g.width,g.height),E=function(e,t,n,r,i){var o,a,s,c;if(a=n.pixel_size>>3,s=n.width*n.height*a,t&&(c=i.subarray(r,r+=n.colormap_length*(n.colormap_size>>3))),e){var l,u,h;o=new Uint8Array(s);for(var d=0,p=new Uint8Array(a);d>l){default:case d:o=0,s=1,m=t,a=0,f=1,v=n;break;case u:o=0,s=1,m=t,a=n-1,f=-1,v=-1;break;case p:o=t-1,s=-1,m=-1,a=0,f=1,v=n;break;case h:o=t-1,s=-1,m=-1,a=n-1,f=-1,v=-1}if(b)switch(g.pixel_size){case 8:!function(e,t,n,r,i,o,a,s){var c,l,u,h=0,d=g.width;for(u=t;u!==r;u+=n)for(l=i;l!==a;l+=o,h++)c=s[h],e[4*(l+d*u)+0]=c,e[4*(l+d*u)+1]=c,e[4*(l+d*u)+2]=c,e[4*(l+d*u)+3]=255}(e,a,f,v,o,s,m,r);break;case 16:!function(e,t,n,r,i,o,a,s){var c,l,u=0,h=g.width;for(l=t;l!==r;l+=n)for(c=i;c!==a;c+=o,u+=2)e[4*(c+h*l)+0]=s[u+0],e[4*(c+h*l)+1]=s[u+0],e[4*(c+h*l)+2]=s[u+0],e[4*(c+h*l)+3]=s[u+1]}(e,a,f,v,o,s,m,r);break;default:console.error("THREE.TGALoader: Format not supported.")}else switch(g.pixel_size){case 8:!function(e,t,n,r,i,o,a,s,c){var l,u,h,d=c,p=0,f=g.width;for(h=t;h!==r;h+=n)for(u=i;u!==a;u+=o,p++)l=s[p],e[4*(u+f*h)+3]=255,e[4*(u+f*h)+2]=d[3*l+0],e[4*(u+f*h)+1]=d[3*l+1],e[4*(u+f*h)+0]=d[3*l+2]}(e,a,f,v,o,s,m,r,i);break;case 16:!function(e,t,n,r,i,o,a,s){var c,l,u,h=0,d=g.width;for(u=t;u!==r;u+=n)for(l=i;l!==a;l+=o,h+=2)c=s[h+0]+(s[h+1]<<8),e[4*(l+d*u)+0]=(31744&c)>>7,e[4*(l+d*u)+1]=(992&c)>>2,e[4*(l+d*u)+2]=(31&c)>>3,e[4*(l+d*u)+3]=32768&c?0:255}(e,a,f,v,o,s,m,r);break;case 24:!function(e,t,n,r,i,o,a,s){var c,l,u=0,h=g.width;for(l=t;l!==r;l+=n)for(c=i;c!==a;c+=o,u+=3)e[4*(c+h*l)+3]=255,e[4*(c+h*l)+2]=s[u+0],e[4*(c+h*l)+1]=s[u+1],e[4*(c+h*l)+0]=s[u+2]}(e,a,f,v,o,s,m,r);break;case 32:!function(e,t,n,r,i,o,a,s){var c,l,u=0,h=g.width;for(l=t;l!==r;l+=n)for(c=i;c!==a;c+=o,u+=4)e[4*(c+h*l)+2]=s[u+0],e[4*(c+h*l)+1]=s[u+1],e[4*(c+h*l)+0]=s[u+2],e[4*(c+h*l)+3]=s[u+3]}(e,a,f,v,o,s,m,r);break;default:console.error("THREE.TGALoader: Format not supported.")}}(M.data,g.width,g.height,E.pixel_data,E.palettes);return w.putImageData(M,0,0),_?x.transferToImageBitmap():x}}),n.d(t,"a",(function(){return o}));var o=function(e){r.Loader.call(this,e)};o.prototype=Object.assign(Object.create(r.Loader.prototype),{constructor:o,load:function(e,t,n,i){var o=this,a=""===o.path?r.LoaderUtils.extractUrlBase(e):o.path,s=new r.FileLoader(o.manager);s.setPath(o.path),s.load(e,(function(e){t(o.parse(e,a))}),n,i)},options:{set convertUpAxis(e){console.warn("THREE.ColladaLoader: options.convertUpAxis() has been removed. Up axis is converted automatically.")}},parse:function(e,t){function n(e,t){for(var n=[],r=e.childNodes,i=0,o=r.length;i0&&t.push(new r.VectorKeyframeTrack(i+".position",o,a)),s.length>0&&t.push(new r.QuaternionKeyframeTrack(i+".quaternion",o,s)),c.length>0&&t.push(new r.VectorKeyframeTrack(i+".scale",o,c)),t}function E(e,t,n){var r,i,o,a=!0;for(i=0,o=e.length;i=0;){var r=e[t];if(null!==r.value[n])return r;t--}return null}function S(e,t,n){for(;t>>0));switch(n=n.toLowerCase()){case"tga":t=qe;break;default:t=Xe}return t}(n);if(void 0!==o){var a=o.load(n),s=e.extra;if(void 0!==s&&void 0!==s.technique&&!1===l(s.technique)){var c=s.technique;a.wrapS=c.wrapU?r.RepeatWrapping:r.ClampToEdgeWrapping,a.wrapT=c.wrapV?r.RepeatWrapping:r.ClampToEdgeWrapping,a.offset.set(c.offsetU||0,c.offsetV||0),a.repeat.set(c.repeatU||1,c.repeatV||1)}else a.wrapS=r.RepeatWrapping,a.wrapT=r.RepeatWrapping;return a}return console.warn("THREE.ColladaLoader: Loader for texture %s not found.",n),null}return console.warn("THREE.ColladaLoader: Couldn't create texture with ID:",e.id),null}n.name=e.name||"";var c=o.parameters;for(var u in c){var h=c[u];switch(u){case"diffuse":h.color&&n.color.fromArray(h.color),h.texture&&(n.map=s(h.texture));break;case"specular":h.color&&n.specular&&n.specular.fromArray(h.color),h.texture&&(n.specularMap=s(h.texture));break;case"bump":h.texture&&(n.normalMap=s(h.texture));break;case"ambient":h.texture&&(n.lightMap=s(h.texture));break;case"shininess":h.float&&n.shininess&&(n.shininess=h.float);break;case"emission":h.color&&n.emissive&&n.emissive.fromArray(h.color),h.texture&&(n.emissiveMap=s(h.texture))}}var d=c.transparent,p=c.transparency;if(void 0===p&&d&&(p={float:1}),void 0===d&&p&&(d={opaque:"A_ONE",data:{color:[1,1,1,1]}}),d&&p)if(d.data.texture)n.transparent=!0;else{var m=d.data.color;switch(d.opaque){case"A_ONE":n.opacity=m[3]*p.float;break;case"RGB_ZERO":n.opacity=1-m[0]*p.float;break;case"A_ZERO":n.opacity=1-m[3]*p.float;break;case"RGB_ONE":n.opacity=m[0]*p.float;break;default:console.warn('THREE.ColladaLoader: Invalid opaque type "%s" of transparent tag.',d.opaque)}n.opacity<1&&(n.transparent=!0)}return void 0!==a&&void 0!==a.technique&&1===a.technique.double_sided&&(n.side=r.DoubleSide),n}function Z(e){return f(Qe.materials[e],J)}function K(e){for(var t=0;t0?a+u:a;t.inputs[h]={id:o,offset:l},t.stride=Math.max(t.stride,l+1),"TEXCOORD"===a&&(t.hasUV=!0);break;case"vcount":t.vcount=s(i.textContent);break;case"p":t.p=s(i.textContent)}}return t}function le(e){for(var t=0,n=0,r=e.length;n0&&t0&&f.setAttribute("position",new r.Float32BufferAttribute(o.array,o.stride)),a.array.length>0&&f.setAttribute("normal",new r.Float32BufferAttribute(a.array,a.stride)),l.array.length>0&&f.setAttribute("color",new r.Float32BufferAttribute(l.array,l.stride)),s.array.length>0&&f.setAttribute("uv",new r.Float32BufferAttribute(s.array,s.stride)),c.array.length>0&&f.setAttribute("uv2",new r.Float32BufferAttribute(c.array,c.stride)),u.length>0&&f.setAttribute("skinIndex",new r.Float32BufferAttribute(u,h)),d.length>0&&f.setAttribute("skinWeight",new r.Float32BufferAttribute(d,p)),i.data=f,i.type=e[0].type,i.materialKeys=m,i}function de(e,t,n,r){var i=e.p,o=e.stride,a=e.vcount;function s(e){for(var t=i[e+n]*l,o=t+l;t4)for(var v=1,y=p-2;v<=y;v++){f=u+o*v,m=u+o*(v+1);s(u+0*o),s(f),s(m)}u+=o*p}else for(h=0,d=i.length;h=t.limits.max&&(t.static=!0),t.middlePosition=(t.limits.min+t.limits.max)/2,t}function ye(e){for(var t={sid:e.getAttribute("sid"),name:e.getAttribute("name")||"",attachments:[],transforms:[]},n=0;ni.limits.max||t\n", - " * @license MIT\n", - " */\n", - "var r=n(30),i=n(7),o=n(2);function a(){return c.TYPED_ARRAY_SUPPORT?2147483647:1073741823}function s(e,t){if(a()=a())throw new RangeError("Attempt to allocate Buffer larger than maximum size: 0x"+a().toString(16)+" bytes");return 0|e}function f(e,t){if(c.isBuffer(e))return e.length;if("undefined"!=typeof ArrayBuffer&&"function"==typeof ArrayBuffer.isView&&(ArrayBuffer.isView(e)||e instanceof ArrayBuffer))return e.byteLength;"string"!=typeof e&&(e=""+e);var n=e.length;if(0===n)return 0;for(var r=!1;;)switch(t){case"ascii":case"latin1":case"binary":return n;case"utf8":case"utf-8":case void 0:return G(e).length;case"ucs2":case"ucs-2":case"utf16le":case"utf-16le":return 2*n;case"hex":return n>>>1;case"base64":return H(e).length;default:if(r)return G(e).length;t=(""+t).toLowerCase(),r=!0}}function m(e,t,n){var r=!1;if((void 0===t||t<0)&&(t=0),t>this.length)return"";if((void 0===n||n>this.length)&&(n=this.length),n<=0)return"";if((n>>>=0)<=(t>>>=0))return"";for(e||(e="utf8");;)switch(e){case"hex":return R(this,t,n);case"utf8":case"utf-8":return S(this,t,n);case"ascii":return L(this,t,n);case"latin1":case"binary":return C(this,t,n);case"base64":return T(this,t,n);case"ucs2":case"ucs-2":case"utf16le":case"utf-16le":return P(this,t,n);default:if(r)throw new TypeError("Unknown encoding: "+e);e=(e+"").toLowerCase(),r=!0}}function g(e,t,n){var r=e[t];e[t]=e[n],e[n]=r}function v(e,t,n,r,i){if(0===e.length)return-1;if("string"==typeof n?(r=n,n=0):n>2147483647?n=2147483647:n<-2147483648&&(n=-2147483648),n=+n,isNaN(n)&&(n=i?0:e.length-1),n<0&&(n=e.length+n),n>=e.length){if(i)return-1;n=e.length-1}else if(n<0){if(!i)return-1;n=0}if("string"==typeof t&&(t=c.from(t,r)),c.isBuffer(t))return 0===t.length?-1:y(e,t,n,r,i);if("number"==typeof t)return t&=255,c.TYPED_ARRAY_SUPPORT&&"function"==typeof Uint8Array.prototype.indexOf?i?Uint8Array.prototype.indexOf.call(e,t,n):Uint8Array.prototype.lastIndexOf.call(e,t,n):y(e,[t],n,r,i);throw new TypeError("val must be string, number or Buffer")}function y(e,t,n,r,i){var o,a=1,s=e.length,c=t.length;if(void 0!==r&&("ucs2"===(r=String(r).toLowerCase())||"ucs-2"===r||"utf16le"===r||"utf-16le"===r)){if(e.length<2||t.length<2)return-1;a=2,s/=2,c/=2,n/=2}function l(e,t){return 1===a?e[t]:e.readUInt16BE(t*a)}if(i){var u=-1;for(o=n;os&&(n=s-c),o=n;o>=0;o--){for(var h=!0,d=0;di&&(r=i):r=i;var o=t.length;if(o%2!=0)throw new TypeError("Invalid hex string");r>o/2&&(r=o/2);for(var a=0;a>8,i=n%256,o.push(i),o.push(r);return o}(t,e.length-n),e,n,r)}function T(e,t,n){return 0===t&&n===e.length?r.fromByteArray(e):r.fromByteArray(e.slice(t,n))}function S(e,t,n){n=Math.min(e.length,n);for(var r=[],i=t;i239?4:l>223?3:l>191?2:1;if(i+h<=n)switch(h){case 1:l<128&&(u=l);break;case 2:128==(192&(o=e[i+1]))&&(c=(31&l)<<6|63&o)>127&&(u=c);break;case 3:o=e[i+1],a=e[i+2],128==(192&o)&&128==(192&a)&&(c=(15&l)<<12|(63&o)<<6|63&a)>2047&&(c<55296||c>57343)&&(u=c);break;case 4:o=e[i+1],a=e[i+2],s=e[i+3],128==(192&o)&&128==(192&a)&&128==(192&s)&&(c=(15&l)<<18|(63&o)<<12|(63&a)<<6|63&s)>65535&&c<1114112&&(u=c)}null===u?(u=65533,h=1):u>65535&&(u-=65536,r.push(u>>>10&1023|55296),u=56320|1023&u),r.push(u),i+=h}return function(e){var t=e.length;if(t<=A)return String.fromCharCode.apply(String,e);var n="",r=0;for(;r0&&(e=this.toString("hex",0,n).match(/.{2}/g).join(" "),this.length>n&&(e+=" ... ")),""},c.prototype.compare=function(e,t,n,r,i){if(!c.isBuffer(e))throw new TypeError("Argument must be a Buffer");if(void 0===t&&(t=0),void 0===n&&(n=e?e.length:0),void 0===r&&(r=0),void 0===i&&(i=this.length),t<0||n>e.length||r<0||i>this.length)throw new RangeError("out of range index");if(r>=i&&t>=n)return 0;if(r>=i)return-1;if(t>=n)return 1;if(this===e)return 0;for(var o=(i>>>=0)-(r>>>=0),a=(n>>>=0)-(t>>>=0),s=Math.min(o,a),l=this.slice(r,i),u=e.slice(t,n),h=0;hi)&&(n=i),e.length>0&&(n<0||t<0)||t>this.length)throw new RangeError("Attempt to write outside buffer bounds");r||(r="utf8");for(var o=!1;;)switch(r){case"hex":return b(this,e,t,n);case"utf8":case"utf-8":return _(this,e,t,n);case"ascii":return x(this,e,t,n);case"latin1":case"binary":return w(this,e,t,n);case"base64":return M(this,e,t,n);case"ucs2":case"ucs-2":case"utf16le":case"utf-16le":return E(this,e,t,n);default:if(o)throw new TypeError("Unknown encoding: "+r);r=(""+r).toLowerCase(),o=!0}},c.prototype.toJSON=function(){return{type:"Buffer",data:Array.prototype.slice.call(this._arr||this,0)}};var A=4096;function L(e,t,n){var r="";n=Math.min(e.length,n);for(var i=t;ir)&&(n=r);for(var i="",o=t;on)throw new RangeError("Trying to access beyond buffer length")}function N(e,t,n,r,i,o){if(!c.isBuffer(e))throw new TypeError('"buffer" argument must be a Buffer instance');if(t>i||te.length)throw new RangeError("Index out of range")}function I(e,t,n,r){t<0&&(t=65535+t+1);for(var i=0,o=Math.min(e.length-n,2);i>>8*(r?i:1-i)}function D(e,t,n,r){t<0&&(t=4294967295+t+1);for(var i=0,o=Math.min(e.length-n,4);i>>8*(r?i:3-i)&255}function B(e,t,n,r,i,o){if(n+r>e.length)throw new RangeError("Index out of range");if(n<0)throw new RangeError("Index out of range")}function k(e,t,n,r,o){return o||B(e,0,n,4),i.write(e,t,n,r,23,4),n+4}function U(e,t,n,r,o){return o||B(e,0,n,8),i.write(e,t,n,r,52,8),n+8}c.prototype.slice=function(e,t){var n,r=this.length;if((e=~~e)<0?(e+=r)<0&&(e=0):e>r&&(e=r),(t=void 0===t?r:~~t)<0?(t+=r)<0&&(t=0):t>r&&(t=r),t0&&(i*=256);)r+=this[e+--t]*i;return r},c.prototype.readUInt8=function(e,t){return t||O(e,1,this.length),this[e]},c.prototype.readUInt16LE=function(e,t){return t||O(e,2,this.length),this[e]|this[e+1]<<8},c.prototype.readUInt16BE=function(e,t){return t||O(e,2,this.length),this[e]<<8|this[e+1]},c.prototype.readUInt32LE=function(e,t){return t||O(e,4,this.length),(this[e]|this[e+1]<<8|this[e+2]<<16)+16777216*this[e+3]},c.prototype.readUInt32BE=function(e,t){return t||O(e,4,this.length),16777216*this[e]+(this[e+1]<<16|this[e+2]<<8|this[e+3])},c.prototype.readIntLE=function(e,t,n){e|=0,t|=0,n||O(e,t,this.length);for(var r=this[e],i=1,o=0;++o=(i*=128)&&(r-=Math.pow(2,8*t)),r},c.prototype.readIntBE=function(e,t,n){e|=0,t|=0,n||O(e,t,this.length);for(var r=t,i=1,o=this[e+--r];r>0&&(i*=256);)o+=this[e+--r]*i;return o>=(i*=128)&&(o-=Math.pow(2,8*t)),o},c.prototype.readInt8=function(e,t){return t||O(e,1,this.length),128&this[e]?-1*(255-this[e]+1):this[e]},c.prototype.readInt16LE=function(e,t){t||O(e,2,this.length);var n=this[e]|this[e+1]<<8;return 32768&n?4294901760|n:n},c.prototype.readInt16BE=function(e,t){t||O(e,2,this.length);var n=this[e+1]|this[e]<<8;return 32768&n?4294901760|n:n},c.prototype.readInt32LE=function(e,t){return t||O(e,4,this.length),this[e]|this[e+1]<<8|this[e+2]<<16|this[e+3]<<24},c.prototype.readInt32BE=function(e,t){return t||O(e,4,this.length),this[e]<<24|this[e+1]<<16|this[e+2]<<8|this[e+3]},c.prototype.readFloatLE=function(e,t){return t||O(e,4,this.length),i.read(this,e,!0,23,4)},c.prototype.readFloatBE=function(e,t){return t||O(e,4,this.length),i.read(this,e,!1,23,4)},c.prototype.readDoubleLE=function(e,t){return t||O(e,8,this.length),i.read(this,e,!0,52,8)},c.prototype.readDoubleBE=function(e,t){return t||O(e,8,this.length),i.read(this,e,!1,52,8)},c.prototype.writeUIntLE=function(e,t,n,r){(e=+e,t|=0,n|=0,r)||N(this,e,t,n,Math.pow(2,8*n)-1,0);var i=1,o=0;for(this[t]=255&e;++o=0&&(o*=256);)this[t+i]=e/o&255;return t+n},c.prototype.writeUInt8=function(e,t,n){return e=+e,t|=0,n||N(this,e,t,1,255,0),c.TYPED_ARRAY_SUPPORT||(e=Math.floor(e)),this[t]=255&e,t+1},c.prototype.writeUInt16LE=function(e,t,n){return e=+e,t|=0,n||N(this,e,t,2,65535,0),c.TYPED_ARRAY_SUPPORT?(this[t]=255&e,this[t+1]=e>>>8):I(this,e,t,!0),t+2},c.prototype.writeUInt16BE=function(e,t,n){return e=+e,t|=0,n||N(this,e,t,2,65535,0),c.TYPED_ARRAY_SUPPORT?(this[t]=e>>>8,this[t+1]=255&e):I(this,e,t,!1),t+2},c.prototype.writeUInt32LE=function(e,t,n){return e=+e,t|=0,n||N(this,e,t,4,4294967295,0),c.TYPED_ARRAY_SUPPORT?(this[t+3]=e>>>24,this[t+2]=e>>>16,this[t+1]=e>>>8,this[t]=255&e):D(this,e,t,!0),t+4},c.prototype.writeUInt32BE=function(e,t,n){return e=+e,t|=0,n||N(this,e,t,4,4294967295,0),c.TYPED_ARRAY_SUPPORT?(this[t]=e>>>24,this[t+1]=e>>>16,this[t+2]=e>>>8,this[t+3]=255&e):D(this,e,t,!1),t+4},c.prototype.writeIntLE=function(e,t,n,r){if(e=+e,t|=0,!r){var i=Math.pow(2,8*n-1);N(this,e,t,n,i-1,-i)}var o=0,a=1,s=0;for(this[t]=255&e;++o>0)-s&255;return t+n},c.prototype.writeIntBE=function(e,t,n,r){if(e=+e,t|=0,!r){var i=Math.pow(2,8*n-1);N(this,e,t,n,i-1,-i)}var o=n-1,a=1,s=0;for(this[t+o]=255&e;--o>=0&&(a*=256);)e<0&&0===s&&0!==this[t+o+1]&&(s=1),this[t+o]=(e/a>>0)-s&255;return t+n},c.prototype.writeInt8=function(e,t,n){return e=+e,t|=0,n||N(this,e,t,1,127,-128),c.TYPED_ARRAY_SUPPORT||(e=Math.floor(e)),e<0&&(e=255+e+1),this[t]=255&e,t+1},c.prototype.writeInt16LE=function(e,t,n){return e=+e,t|=0,n||N(this,e,t,2,32767,-32768),c.TYPED_ARRAY_SUPPORT?(this[t]=255&e,this[t+1]=e>>>8):I(this,e,t,!0),t+2},c.prototype.writeInt16BE=function(e,t,n){return e=+e,t|=0,n||N(this,e,t,2,32767,-32768),c.TYPED_ARRAY_SUPPORT?(this[t]=e>>>8,this[t+1]=255&e):I(this,e,t,!1),t+2},c.prototype.writeInt32LE=function(e,t,n){return e=+e,t|=0,n||N(this,e,t,4,2147483647,-2147483648),c.TYPED_ARRAY_SUPPORT?(this[t]=255&e,this[t+1]=e>>>8,this[t+2]=e>>>16,this[t+3]=e>>>24):D(this,e,t,!0),t+4},c.prototype.writeInt32BE=function(e,t,n){return e=+e,t|=0,n||N(this,e,t,4,2147483647,-2147483648),e<0&&(e=4294967295+e+1),c.TYPED_ARRAY_SUPPORT?(this[t]=e>>>24,this[t+1]=e>>>16,this[t+2]=e>>>8,this[t+3]=255&e):D(this,e,t,!1),t+4},c.prototype.writeFloatLE=function(e,t,n){return k(this,e,t,!0,n)},c.prototype.writeFloatBE=function(e,t,n){return k(this,e,t,!1,n)},c.prototype.writeDoubleLE=function(e,t,n){return U(this,e,t,!0,n)},c.prototype.writeDoubleBE=function(e,t,n){return U(this,e,t,!1,n)},c.prototype.copy=function(e,t,n,r){if(n||(n=0),r||0===r||(r=this.length),t>=e.length&&(t=e.length),t||(t=0),r>0&&r=this.length)throw new RangeError("sourceStart out of bounds");if(r<0)throw new RangeError("sourceEnd out of bounds");r>this.length&&(r=this.length),e.length-t=0;--i)e[i+t]=this[i+n];else if(o<1e3||!c.TYPED_ARRAY_SUPPORT)for(i=0;i>>=0,n=void 0===n?this.length:n>>>0,e||(e=0),"number"==typeof e)for(o=t;o55295&&n<57344){if(!i){if(n>56319){(t-=3)>-1&&o.push(239,191,189);continue}if(a+1===r){(t-=3)>-1&&o.push(239,191,189);continue}i=n;continue}if(n<56320){(t-=3)>-1&&o.push(239,191,189),i=n;continue}n=65536+(i-55296<<10|n-56320)}else i&&(t-=3)>-1&&o.push(239,191,189);if(i=null,n<128){if((t-=1)<0)break;o.push(n)}else if(n<2048){if((t-=2)<0)break;o.push(n>>6|192,63&n|128)}else if(n<65536){if((t-=3)<0)break;o.push(n>>12|224,n>>6&63|128,63&n|128)}else{if(!(n<1114112))throw new Error("Invalid code point");if((t-=4)<0)break;o.push(n>>18|240,n>>12&63|128,n>>6&63|128,63&n|128)}}return o}function H(e){return r.toByteArray(function(e){if((e=function(e){return e.trim?e.trim():e.replace(/^\\s+|\\s+$/g,"")}(e).replace(F,"")).length<2)return"";for(;e.length%4!=0;)e+="=";return e}(e))}function j(e,t,n,r){for(var i=0;i=t.length||i>=e.length);++i)t[i+n]=e[i];return i}}).call(this,n(17))},function(e,t){var n;n=function(){return this}();try{n=n||new Function("return this")()}catch(e){"object"==typeof window&&(n=window)}e.exports=n},function(e,t){for(var n=t.uint8=new Array(256),r=0;r<=255;r++)n[r]=i(r);function i(e){return function(t){var n=t.reserve(1);t.buffer[n]=e}}},function(e,t,n){t.FlexDecoder=s,t.FlexEncoder=c;var r=n(1),i=2048,o=65536,a="BUFFER_SHORTAGE";function s(){if(!(this instanceof s))return new s}function c(){if(!(this instanceof c))return new c}function l(){throw new Error("method not implemented: write()")}function u(){throw new Error("method not implemented: fetch()")}function h(){return this.buffers&&this.buffers.length?(this.flush(),this.pull()):this.fetch()}function d(e){(this.buffers||(this.buffers=[])).push(e)}function p(){return(this.buffers||(this.buffers=[])).shift()}function f(e){return function(t){for(var n in e)t[n]=e[n];return t}}s.mixin=f({bufferish:r,write:function(e){var t=this.offset?r.prototype.slice.call(this.buffer,this.offset):this.buffer;this.buffer=t?e?this.bufferish.concat([t,e]):t:e,this.offset=0},fetch:u,flush:function(){for(;this.offsetthis.buffer.length)throw new Error(a);return this.offset=n,t},offset:0}),s.mixin(s.prototype),c.mixin=f({bufferish:r,write:l,fetch:function(){var e=this.start;if(e1?this.bufferish.concat(e):e[0];return e.length=0,t},read:h,reserve:function(e){var t=0|e;if(this.buffer){var n=this.buffer.length,r=0|this.offset,i=r+t;if(ithis.minBufferSize)this.flush(),this.push(e);else{var n=this.reserve(t);r.prototype.copy.call(e,this.buffer,n)}},maxBufferSize:o,minBufferSize:i,offset:0,start:0}),c.mixin(c.prototype)},function(e,t,n){t.decode=function(e,t){var n=new r(t);return n.write(e),n.read()};var r=n(21).DecodeBuffer},function(e,t,n){t.DecodeBuffer=i;var r=n(10).preset;function i(e){if(!(this instanceof i))return new i(e);if(e&&(this.options=e,e.codec)){var t=this.codec=e.codec;t.bufferish&&(this.bufferish=t.bufferish)}}n(19).FlexDecoder.mixin(i.prototype),i.prototype.codec=r,i.prototype.fetch=function(){return this.codec.decode(this)}},function(e,t,n){var r=n(7),i=n(9),o=i.Uint64BE,a=i.Int64BE;t.getReadFormat=function(e){var t=s.hasArrayBuffer&&e&&e.binarraybuffer,n=e&&e.int64;return{map:l&&e&&e.usemap?d:h,array:p,str:f,bin:t?g:m,ext:v,uint8:y,uint16:_,uint32:w,uint64:E(8,n?A:T),int8:b,int16:x,int32:M,int64:E(8,n?L:S),float32:E(4,C),float64:E(8,R)}},t.readUint8=y;var s=n(1),c=n(8),l="undefined"!=typeof Map,u=!0;function h(e,t){var n,r={},i=new Array(t),o=new Array(t),a=e.codec.decode;for(n=0;n[]))}var m=Math.log10(1/t),g=Math.pow(10,m);for(p=0;pf||8*(1-s.dot(c.object.quaternion))>f)&&(c.dispatchEvent(l),a.copy(c.object.position),s.copy(c.object.quaternion),b=!1,!0)}),this.dispose=function(){c.domElement.removeEventListener("contextmenu",ee,!1),c.domElement.removeEventListener("mousedown",q,!1),c.domElement.removeEventListener("wheel",J,!1),c.domElement.removeEventListener("touchstart",K,!1),c.domElement.removeEventListener("touchend",$,!1),c.domElement.removeEventListener("touchmove",Q,!1),document.removeEventListener("mousemove",Y,!1),document.removeEventListener("mouseup",X,!1),c.domElement.removeEventListener("keydown",Z,!1)};var c=this,l={type:"change"},u={type:"start"},h={type:"end"},d={NONE:-1,ROTATE:0,DOLLY:1,PAN:2,TOUCH_ROTATE:3,TOUCH_PAN:4,TOUCH_DOLLY_PAN:5,TOUCH_DOLLY_ROTATE:6},p=d.NONE,f=1e-6,m=new r.Spherical,g=new r.Spherical,v=1,y=new r.Vector3,b=!1,_=new r.Vector2,x=new r.Vector2,w=new r.Vector2,M=new r.Vector2,E=new r.Vector2,T=new r.Vector2,S=new r.Vector2,A=new r.Vector2,L=new r.Vector2;function C(){return Math.pow(.95,c.zoomSpeed)}function R(e){g.theta-=e}function P(e){g.phi-=e}var O,N=(O=new r.Vector3,function(e,t){O.setFromMatrixColumn(t,0),O.multiplyScalar(-e),y.add(O)}),I=function(){var e=new r.Vector3;return function(t,n){!0===c.screenSpacePanning?e.setFromMatrixColumn(n,1):(e.setFromMatrixColumn(n,0),e.crossVectors(c.object.up,e)),e.multiplyScalar(t),y.add(e)}}(),D=function(){var e=new r.Vector3;return function(t,n){var r=c.domElement;if(c.object.isPerspectiveCamera){var i=c.object.position;e.copy(i).sub(c.target);var o=e.length();o*=Math.tan(c.object.fov/2*Math.PI/180),N(2*t*o/r.clientHeight,c.object.matrix),I(2*n*o/r.clientHeight,c.object.matrix)}else c.object.isOrthographicCamera?(N(t*(c.object.right-c.object.left)/c.object.zoom/r.clientWidth,c.object.matrix),I(n*(c.object.top-c.object.bottom)/c.object.zoom/r.clientHeight,c.object.matrix)):(console.warn("WARNING: OrbitControls.js encountered an unknown camera type - pan disabled."),c.enablePan=!1)}}();function B(e){c.object.isPerspectiveCamera?v/=e:c.object.isOrthographicCamera?(c.object.zoom=Math.max(c.minZoom,Math.min(c.maxZoom,c.object.zoom*e)),c.object.updateProjectionMatrix(),b=!0):(console.warn("WARNING: OrbitControls.js encountered an unknown camera type - dolly/zoom disabled."),c.enableZoom=!1)}function k(e){c.object.isPerspectiveCamera?v*=e:c.object.isOrthographicCamera?(c.object.zoom=Math.max(c.minZoom,Math.min(c.maxZoom,c.object.zoom/e)),c.object.updateProjectionMatrix(),b=!0):(console.warn("WARNING: OrbitControls.js encountered an unknown camera type - dolly/zoom disabled."),c.enableZoom=!1)}function U(e){_.set(e.clientX,e.clientY)}function F(e){M.set(e.clientX,e.clientY)}function z(e){if(1==e.touches.length)_.set(e.touches[0].pageX,e.touches[0].pageY);else{var t=.5*(e.touches[0].pageX+e.touches[1].pageX),n=.5*(e.touches[0].pageY+e.touches[1].pageY);_.set(t,n)}}function G(e){if(1==e.touches.length)M.set(e.touches[0].pageX,e.touches[0].pageY);else{var t=.5*(e.touches[0].pageX+e.touches[1].pageX),n=.5*(e.touches[0].pageY+e.touches[1].pageY);M.set(t,n)}}function H(e){var t=e.touches[0].pageX-e.touches[1].pageX,n=e.touches[0].pageY-e.touches[1].pageY,r=Math.sqrt(t*t+n*n);S.set(0,r)}function j(e){if(1==e.touches.length)x.set(e.touches[0].pageX,e.touches[0].pageY);else{var t=.5*(e.touches[0].pageX+e.touches[1].pageX),n=.5*(e.touches[0].pageY+e.touches[1].pageY);x.set(t,n)}w.subVectors(x,_).multiplyScalar(c.rotateSpeed);var r=c.domElement;R(2*Math.PI*w.x/r.clientHeight),P(2*Math.PI*w.y/r.clientHeight),_.copy(x)}function V(e){if(1==e.touches.length)E.set(e.touches[0].pageX,e.touches[0].pageY);else{var t=.5*(e.touches[0].pageX+e.touches[1].pageX),n=.5*(e.touches[0].pageY+e.touches[1].pageY);E.set(t,n)}T.subVectors(E,M).multiplyScalar(c.panSpeed),D(T.x,T.y),M.copy(E)}function W(e){var t=e.touches[0].pageX-e.touches[1].pageX,n=e.touches[0].pageY-e.touches[1].pageY,r=Math.sqrt(t*t+n*n);A.set(0,r),L.set(0,Math.pow(A.y/S.y,c.zoomSpeed)),B(L.y),S.copy(A)}function q(e){if(!1!==c.enabled){switch(e.preventDefault(),c.domElement.focus?c.domElement.focus():window.focus(),e.button){case 0:switch(c.mouseButtons.LEFT){case r.MOUSE.ROTATE:if(e.ctrlKey||e.metaKey||e.shiftKey){if(!1===c.enablePan)return;F(e),p=d.PAN}else{if(!1===c.enableRotate)return;U(e),p=d.ROTATE}break;case r.MOUSE.PAN:if(e.ctrlKey||e.metaKey||e.shiftKey){if(!1===c.enableRotate)return;U(e),p=d.ROTATE}else{if(!1===c.enablePan)return;F(e),p=d.PAN}break;default:p=d.NONE}break;case 1:switch(c.mouseButtons.MIDDLE){case r.MOUSE.DOLLY:if(!1===c.enableZoom)return;!function(e){S.set(e.clientX,e.clientY)}(e),p=d.DOLLY;break;default:p=d.NONE}break;case 2:switch(c.mouseButtons.RIGHT){case r.MOUSE.ROTATE:if(!1===c.enableRotate)return;U(e),p=d.ROTATE;break;case r.MOUSE.PAN:if(!1===c.enablePan)return;F(e),p=d.PAN;break;default:p=d.NONE}}p!==d.NONE&&(document.addEventListener("mousemove",Y,!1),document.addEventListener("mouseup",X,!1),c.dispatchEvent(u))}}function Y(e){if(!1!==c.enabled)switch(e.preventDefault(),p){case d.ROTATE:if(!1===c.enableRotate)return;!function(e){x.set(e.clientX,e.clientY),w.subVectors(x,_).multiplyScalar(c.rotateSpeed);var t=c.domElement;R(2*Math.PI*w.x/t.clientHeight),P(2*Math.PI*w.y/t.clientHeight),_.copy(x),c.update()}(e);break;case d.DOLLY:if(!1===c.enableZoom)return;!function(e){A.set(e.clientX,e.clientY),L.subVectors(A,S),L.y>0?B(C()):L.y<0&&k(C()),S.copy(A),c.update()}(e);break;case d.PAN:if(!1===c.enablePan)return;!function(e){E.set(e.clientX,e.clientY),T.subVectors(E,M).multiplyScalar(c.panSpeed),D(T.x,T.y),M.copy(E),c.update()}(e)}}function X(e){!1!==c.enabled&&(document.removeEventListener("mousemove",Y,!1),document.removeEventListener("mouseup",X,!1),c.dispatchEvent(h),p=d.NONE)}function J(e){!1===c.enabled||!1===c.enableZoom||p!==d.NONE&&p!==d.ROTATE||(e.preventDefault(),e.stopPropagation(),c.dispatchEvent(u),function(e){e.deltaY<0?k(C()):e.deltaY>0&&B(C()),c.update()}(e),c.dispatchEvent(h))}function Z(e){!1!==c.enabled&&!1!==c.enableKeys&&!1!==c.enablePan&&function(e){var t=!1;switch(e.keyCode){case c.keys.UP:D(0,c.keyPanSpeed),t=!0;break;case c.keys.BOTTOM:D(0,-c.keyPanSpeed),t=!0;break;case c.keys.LEFT:D(c.keyPanSpeed,0),t=!0;break;case c.keys.RIGHT:D(-c.keyPanSpeed,0),t=!0}t&&(e.preventDefault(),c.update())}(e)}function K(e){if(!1!==c.enabled){switch(e.preventDefault(),e.touches.length){case 1:switch(c.touches.ONE){case r.TOUCH.ROTATE:if(!1===c.enableRotate)return;z(e),p=d.TOUCH_ROTATE;break;case r.TOUCH.PAN:if(!1===c.enablePan)return;G(e),p=d.TOUCH_PAN;break;default:p=d.NONE}break;case 2:switch(c.touches.TWO){case r.TOUCH.DOLLY_PAN:if(!1===c.enableZoom&&!1===c.enablePan)return;!function(e){c.enableZoom&&H(e),c.enablePan&&G(e)}(e),p=d.TOUCH_DOLLY_PAN;break;case r.TOUCH.DOLLY_ROTATE:if(!1===c.enableZoom&&!1===c.enableRotate)return;!function(e){c.enableZoom&&H(e),c.enableRotate&&z(e)}(e),p=d.TOUCH_DOLLY_ROTATE;break;default:p=d.NONE}break;default:p=d.NONE}p!==d.NONE&&c.dispatchEvent(u)}}function Q(e){if(!1!==c.enabled)switch(e.preventDefault(),e.stopPropagation(),p){case d.TOUCH_ROTATE:if(!1===c.enableRotate)return;j(e),c.update();break;case d.TOUCH_PAN:if(!1===c.enablePan)return;V(e),c.update();break;case d.TOUCH_DOLLY_PAN:if(!1===c.enableZoom&&!1===c.enablePan)return;!function(e){c.enableZoom&&W(e),c.enablePan&&V(e)}(e),c.update();break;case d.TOUCH_DOLLY_ROTATE:if(!1===c.enableZoom&&!1===c.enableRotate)return;!function(e){c.enableZoom&&W(e),c.enableRotate&&j(e)}(e),c.update();break;default:p=d.NONE}}function $(e){!1!==c.enabled&&(c.dispatchEvent(h),p=d.NONE)}function ee(e){!1!==c.enabled&&e.preventDefault()}c.domElement.addEventListener("contextmenu",ee,!1),c.domElement.addEventListener("mousedown",q,!1),c.domElement.addEventListener("wheel",J,!1),c.domElement.addEventListener("touchstart",K,!1),c.domElement.addEventListener("touchend",$,!1),c.domElement.addEventListener("touchmove",Q,!1),c.domElement.addEventListener("keydown",Z,!1),-1===c.domElement.tabIndex&&(c.domElement.tabIndex=0),this.update()};i.prototype=Object.create(r.EventDispatcher.prototype),i.prototype.constructor=i;var o=function(e,t){i.call(this,e,t),this.mouseButtons.LEFT=r.MOUSE.PAN,this.mouseButtons.RIGHT=r.MOUSE.ROTATE,this.touches.ONE=r.TOUCH.PAN,this.touches.TWO=r.TOUCH.DOLLY_ROTATE};(o.prototype=Object.create(r.EventDispatcher.prototype)).constructor=o},function(module,__webpack_exports__,__webpack_require__){"use strict";__webpack_require__.r(__webpack_exports__),__webpack_require__.d(__webpack_exports__,"Viewer",(function(){return Viewer})),__webpack_require__.d(__webpack_exports__,"THREE",(function(){return THREE}));var three_examples_jsm_utils_BufferGeometryUtils_js__WEBPACK_IMPORTED_MODULE_0__=__webpack_require__(24),three_examples_jsm_loaders_OBJLoader2_js__WEBPACK_IMPORTED_MODULE_1__=__webpack_require__(12),three_examples_jsm_loaders_ColladaLoader_js__WEBPACK_IMPORTED_MODULE_2__=__webpack_require__(13),three_examples_jsm_loaders_MTLLoader_js__WEBPACK_IMPORTED_MODULE_3__=__webpack_require__(4),three_examples_jsm_loaders_obj2_bridge_MtlObjBridge_js__WEBPACK_IMPORTED_MODULE_4__=__webpack_require__(25),three_examples_jsm_loaders_STLLoader_js__WEBPACK_IMPORTED_MODULE_5__=__webpack_require__(11),three_examples_jsm_controls_OrbitControls_js__WEBPACK_IMPORTED_MODULE_6__=__webpack_require__(26),THREE=__webpack_require__(0),msgpack=__webpack_require__(28),dat=__webpack_require__(44).default;function merge_geometries(e,t=!1){let n=[],r=[],i=e.matrix.clone();!function e(t,i){let o=i.clone().multiply(t.matrix);"Mesh"===t.type&&(t.geometry.applyMatrix(o),r.push(t.geometry),n.push(t.material));for(let n of t.children)e(n,o)}(e,i);let o=null;return 1==r.length?(o=r[0],t&&(o.material=n[0])):r.length>1?(o=three_examples_jsm_utils_BufferGeometryUtils_js__WEBPACK_IMPORTED_MODULE_0__.a.mergeBufferGeometries(r,!0),t&&(o.material=n)):o=new THREE.BufferGeometry,o}function handle_special_texture(e){if("_text"==e.type){let t=document.createElement("canvas");t.width=256,t.height=256;let n=t.getContext("2d");n.textAlign="center";let r=e.font_size;for(n.font=r+"px "+e.font_face;n.measureText(e.text).width>t.width;)r--,n.font=r+"px "+e.font_face;n.fillText(e.text,t.width/2,t.height/2);let i=new THREE.CanvasTexture(t);return i.uuid=e.uuid,i}return null}function handle_special_geometry(e){if("_meshfile"==e.type&&(console.warn("_meshfile is deprecated. Please use _meshfile_geometry for geometries and _meshfile_object for objects with geometry and material"),e.type="_meshfile_geometry"),"_meshfile_geometry"==e.type){if("obj"==e.format){let t=merge_geometries((new three_examples_jsm_loaders_OBJLoader2_js__WEBPACK_IMPORTED_MODULE_1__.a).parse(e.data+"\\n"));return t.uuid=e.uuid,t}if("dae"==e.format){let t=merge_geometries((new three_examples_jsm_loaders_ColladaLoader_js__WEBPACK_IMPORTED_MODULE_2__.a).parse(e.data).scene);return t.uuid=e.uuid,t}if("stl"==e.format){let t=(new three_examples_jsm_loaders_STLLoader_js__WEBPACK_IMPORTED_MODULE_5__.a).parse(e.data.buffer);return t.uuid=e.uuid,t}return console.error("Unsupported mesh type:",e),null}return null}__webpack_require__(45);class ExtensibleObjectLoader extends THREE.ObjectLoader{delegate(e,t,n,r){let i={};if(void 0===n)return i;let o=[];for(let t of n){let n=e(t);null!==n?i[n.uuid]=n:o.push(t)}return Object.assign(i,t(o,r))}parseTextures(e,t){return this.delegate(handle_special_texture,super.parseTextures,e,t)}parseGeometries(e,t){return this.delegate(handle_special_geometry,super.parseGeometries,e,t)}parseObject(e,t,n){if("_meshfile_object"==e.type){let t,n,r=new THREE.LoadingManager,i=void 0===e.url?void 0:THREE.LoaderUtils.extractUrlBase(e.url);if(r.setURLModifier(t=>void 0!==e.resources[t]?e.resources[t]:t),"obj"==e.format){let o=new three_examples_jsm_loaders_OBJLoader2_js__WEBPACK_IMPORTED_MODULE_1__.a(r);if(e.mtl_library){let t=new three_examples_jsm_loaders_MTLLoader_js__WEBPACK_IMPORTED_MODULE_3__.a(r).parse(e.mtl_library+"\\n","");console.log(t);let n=three_examples_jsm_loaders_obj2_bridge_MtlObjBridge_js__WEBPACK_IMPORTED_MODULE_4__.a.addMaterialsFromMtlLoader(t);console.log(n),o.addMaterials(n),this.onTextureLoad()}t=merge_geometries(o.parse(e.data+"\\n",i),!0),t.uuid=e.uuid,n=t.material}else if("dae"==e.format){let o=new three_examples_jsm_loaders_ColladaLoader_js__WEBPACK_IMPORTED_MODULE_2__.a(r);o.onTextureLoad=this.onTextureLoad,t=merge_geometries(o.parse(e.data,i).scene,!0),t.uuid=e.uuid,n=t.material}else{if("stl"!=e.format)return console.error("Unsupported mesh type:",e),null;t=(new three_examples_jsm_loaders_STLLoader_js__WEBPACK_IMPORTED_MODULE_5__.a).parse(e.data.buffer,i),t.uuid=e.uuid,n=t.material}let o=new THREE.Mesh(t,n);return o.uuid=e.uuid,void 0!==e.name&&(o.name=e.name),void 0!==e.matrix?(o.matrix.fromArray(e.matrix),void 0!==e.matrixAutoUpdate&&(o.matrixAutoUpdate=e.matrixAutoUpdate),o.matrixAutoUpdate&&o.matrix.decompose(o.position,o.quaternion,o.scale)):(void 0!==e.position&&o.position.fromArray(e.position),void 0!==e.rotation&&o.rotation.fromArray(e.rotation),void 0!==e.quaternion&&o.quaternion.fromArray(e.quaternion),void 0!==e.scale&&o.scale.fromArray(e.scale)),void 0!==e.castShadow&&(o.castShadow=e.castShadow),void 0!==e.receiveShadow&&(o.receiveShadow=e.receiveShadow),e.shadow&&(void 0!==e.shadow.bias&&(o.shadow.bias=e.shadow.bias),void 0!==e.shadow.radius&&(o.shadow.radius=e.shadow.radius),void 0!==e.shadow.mapSize&&o.shadow.mapSize.fromArray(e.shadow.mapSize),void 0!==e.shadow.camera&&(o.shadow.camera=this.parseObject(e.shadow.camera))),void 0!==e.visible&&(o.visible=e.visible),void 0!==e.frustumCulled&&(o.frustumCulled=e.frustumCulled),void 0!==e.renderOrder&&(o.renderOrder=e.renderOrder),void 0!==e.userjson&&(o.userjson=e.userData),void 0!==e.layers&&(o.layers.mask=e.layers),o}return super.parseObject(e,t,n)}}class SceneNode{constructor(e,t,n){this.object=e,this.folder=t,this.children={},this.controllers=[],this.on_update=n,this.create_controls();for(let e of this.object.children)this.add_child(e)}add_child(e){let t=this.folder.addFolder(e.name),n=new SceneNode(e,t,this.on_update);return this.children[e.name]=n,n}create_child(e){let t=new THREE.Group;return t.name=e,this.object.add(t),this.add_child(t)}find(e){if(0==e.length)return this;{let t=e[0],n=this.children[t];return void 0===n&&(n=this.create_child(t)),n.find(e.slice(1))}}create_controls(){for(let e of this.controllers)this.folder.remove(e);if(void 0!==this.vis_controller&&this.folder.domElement.removeChild(this.vis_controller.domElement),this.vis_controller=new dat.controllers.BooleanController(this.object,"visible"),this.vis_controller.onChange(()=>this.on_update()),this.folder.domElement.prepend(this.vis_controller.domElement),this.vis_controller.domElement.style.height="0",this.vis_controller.domElement.style.float="right",this.vis_controller.domElement.classList.add("meshcat-visibility-checkbox"),this.vis_controller.domElement.children[0].addEventListener("change",e=>{e.target.checked?this.folder.domElement.classList.remove("meshcat-hidden-scene-element"):this.folder.domElement.classList.add("meshcat-hidden-scene-element")}),this.object.isLight){let e=this.folder.add(this.object,"intensity").min(0).step(.01);if(e.onChange(()=>this.on_update()),this.controllers.push(e),void 0!==this.object.castShadow){let e=this.folder.add(this.object,"castShadow");e.onChange(()=>this.on_update()),this.controllers.push(e);let t=this.folder.add(this.object.shadow,"radius").min(0).step(.05).max(3);t.onChange(()=>this.on_update()),this.controllers.push(t)}if(void 0!==this.object.distance){let e=this.folder.add(this.object,"distance").min(0).step(.1).max(100);e.onChange(()=>this.on_update()),this.controllers.push(e)}}if(this.object.isCamera){let e=this.folder.add(this.object,"zoom").min(0).step(.1);e.onChange(()=>{this.on_update()}),this.controllers.push(e)}}set_property(e,t){"position"===e?this.object.position.set(t[0],t[1],t[2]):"quaternion"===e?this.object.quaternion.set(t[0],t[1],t[2],t[3]):"scale"===e?this.object.scale.set(t[0],t[1],t[2]):this.object[e]=t,this.vis_controller.updateDisplay(),this.controllers.forEach(e=>e.updateDisplay())}set_transform(e){let t=new THREE.Matrix4;t.fromArray(e),t.decompose(this.object.position,this.object.quaternion,this.object.scale)}set_object(e){let t=this.object.parent;this.dispose_recursive(),this.object.parent.remove(this.object),this.object=e,t.add(e),this.create_controls()}dispose_recursive(){for(let e of Object.keys(this.children))this.children[e].dispose_recursive();dispose(this.object)}delete(e){if(0==e.length)console.error("Can't delete an empty path");else{let t=this.find(e.slice(0,e.length-1)),n=e[e.length-1],r=t.children[n];void 0!==r&&(r.dispose_recursive(),t.object.remove(r.object),remove_folders(r.folder),t.folder.removeFolder(r.folder),delete t.children[n])}}}function remove_folders(e){for(let t of Object.keys(e.__folders)){let n=e.__folders[t];remove_folders(n),dat.dom.dom.unbind(window,"resize",n.__resizeHandler),e.removeFolder(n)}}function dispose(e){if(e&&(e.geometry&&e.geometry.dispose(),e.material))if(Array.isArray(e.material))for(let t of e.material)t.map&&t.map.dispose(),t.dispose();else e.material.map&&e.material.map.dispose(),e.material.dispose()}function create_default_scene(){var e=new THREE.Scene;return e.name="Scene",e.rotateX(-Math.PI/2),e}function download_data_uri(e,t){let n=document.createElement("a");n.download=e,n.href=t,document.body.appendChild(n),n.click(),document.body.removeChild(n)}function download_file(e,t,n){n=n||"text/plain";let r=new Blob([t],{type:n}),i=document.createElement("a");document.body.appendChild(i),i.download=e,i.href=window.URL.createObjectURL(r),i.onclick=function(e){let t=this;setTimeout((function(){window.URL.revokeObjectURL(t.href)}),1500)},i.click(),i.remove()}class Animator{constructor(e){this.viewer=e,this.folder=this.viewer.gui.addFolder("Animations"),this.mixer=new THREE.AnimationMixer,this.loader=new THREE.ObjectLoader,this.clock=new THREE.Clock,this.actions=[],this.playing=!1,this.time=0,this.time_scrubber=null,this.setup_capturer("png"),this.duration=0}setup_capturer(e){this.capturer=new CCapture({format:e,name:"meshcat_"+String(Date.now())}),this.capturer.format=e}play(){this.clock.start();for(let e of this.actions)e.play();this.playing=!0}record(){this.reset(),this.play(),this.recording=!0,this.capturer.start()}pause(){this.clock.stop(),this.playing=!1,this.recording&&(this.stop_capture(),this.save_capture())}stop_capture(){this.recording=!1,this.capturer.stop(),this.viewer.animate()}save_capture(){this.capturer.save(),"png"===this.capturer.format?alert("To convert the still frames into a video, extract the `.tar` file and run: \\nffmpeg -r 60 -i %07d.png \\\\\\n\\t -vcodec libx264 \\\\\\n\\t -preset slow \\\\\\n\\t -crf 18 \\\\\\n\\t output.mp4"):"jpg"===this.capturer.format&&alert("To convert the still frames into a video, extract the `.tar` file and run: \\nffmpeg -r 60 -i %07d.jpg \\\\\\n\\t -vcodec libx264 \\\\\\n\\t -preset slow \\\\\\n\\t -crf 18 \\\\\\n\\t output.mp4")}display_progress(e){this.time=e,null!==this.time_scrubber&&this.time_scrubber.updateDisplay()}seek(e){this.actions.forEach(t=>{t.time=Math.max(0,Math.min(t._clip.duration,e))}),this.mixer.update(0),this.viewer.set_dirty()}reset(){for(let e of this.actions)e.reset();this.display_progress(0),this.mixer.update(0),this.setup_capturer(this.capturer.format),this.viewer.set_dirty()}clear(){remove_folders(this.folder),this.mixer.stopAllAction(),this.actions=[],this.duration=0,this.display_progress(0),this.mixer=new THREE.AnimationMixer}load(e,t){this.clear(),this.folder.open();let n=this.folder.addFolder("default");n.open(),n.add(this,"play"),n.add(this,"pause"),n.add(this,"reset"),this.time_scrubber=n.add(this,"time",0,1e9,.001),this.time_scrubber.onChange(e=>this.seek(e)),n.add(this.mixer,"timeScale").step(.01).min(0);let r=n.addFolder("Recording");r.add(this,"record"),r.add({format:"png"},"format",["png","jpg"]).onChange(e=>{this.setup_capturer(e)}),void 0===t.play&&(t.play=!0),void 0===t.loopMode&&(t.loopMode=THREE.LoopRepeat),void 0===t.repetitions&&(t.repetitions=1),void 0===t.clampWhenFinished&&(t.clampWhenFinished=!0),this.duration=0,this.progress=0;for(let n of e){let e=this.viewer.scene_tree.find(n.path).object,r=this.loader.parseAnimations([n.clip])[0],i=this.mixer.clipAction(r,e);i.clampWhenFinished=t.clampWhenFinished,i.setLoop(t.loopMode,t.repetitions),this.actions.push(i),this.duration=Math.max(this.duration,r.duration)}this.time_scrubber.min(0),this.time_scrubber.max(this.duration),this.reset(),t.play&&this.play()}update(){if(this.playing){if(this.mixer.update(this.clock.getDelta()),this.viewer.set_dirty(),0!=this.duration){let e=this.actions.reduce((e,t)=>Math.max(e,t.time),0);this.display_progress(e)}else this.display_progress(0);if(this.actions.every(e=>e.paused)){this.pause();for(let e of this.actions)e.reset()}}}after_render(){this.recording&&this.capturer.capture(this.viewer.renderer.domElement)}}function gradient_texture(e,t){let n=[t,e];var r=new Uint8Array(6);for(let e=0;e<2;e++){let t=n[e];for(let n=0;n<1;n++){let i=3*(1*e+n);for(let e=0;e<3;e++)r[i+e]=t[e]}}var i=new THREE.DataTexture(r,1,2,THREE.RGBFormat);return i.magFilter=THREE.LinearFilter,i.encoding=THREE.LinearEncoding,i.matrixAutoUpdate=!1,i.matrix.set(.5,0,.25,0,.5,.25,0,0,1),i.needsUpdate=!0,i}class Viewer{constructor(e,t){this.dom_element=e,this.renderer=new THREE.WebGLRenderer({antialias:!0,alpha:!0}),this.renderer.shadowMap.enabled=!0,this.renderer.shadowMap.type=THREE.PCFSoftShadowMap,this.dom_element.appendChild(this.renderer.domElement),this.scene=create_default_scene(),this.create_scene_tree(),this.add_default_scene_elements(),this.set_dirty(),this.create_camera(),window.onload=e=>this.set_3d_pane_size(),window.addEventListener("resize",e=>this.set_3d_pane_size(),!1),requestAnimationFrame(()=>this.set_3d_pane_size()),(t||void 0===t)&&this.animate()}hide_background(){this.scene.background=null,this.set_dirty()}show_background(){var e=this.scene_tree.find(["Background"]).object.top_color,t=this.scene_tree.find(["Background"]).object.bottom_color;this.scene.background=gradient_texture(e,t),this.set_dirty()}set_dirty(){this.needs_render=!0}create_camera(){let e=new THREE.Matrix4;e.makeRotationX(Math.PI/2),this.set_transform(["Cameras","default","rotated"],e.toArray());let t=new THREE.PerspectiveCamera(75,1,.01,100);this.set_camera(t),this.set_object(["Cameras","default","rotated"],t),t.position.set(3,1,0)}create_default_spot_light(){var e=new THREE.SpotLight(16777215,.8);return e.position.set(1.5,1.5,2),e.castShadow=!1,e.shadow.mapSize.width=1024,e.shadow.mapSize.height=1024,e.shadow.camera.near=.5,e.shadow.camera.far=50,e.shadow.bias=-.001,e}add_default_scene_elements(){var e=this.create_default_spot_light();this.set_object(["Lights","SpotLight"],e),this.set_property(["Lights","SpotLight"],"visible",!1);var t=new THREE.PointLight(16777215,.4);t.position.set(1.5,1.5,2),t.castShadow=!1,t.distance=10,t.shadow.mapSize.width=1024,t.shadow.mapSize.height=1024,t.shadow.camera.near=.5,t.shadow.camera.far=10,t.shadow.bias=-.001,this.set_object(["Lights","PointLightNegativeX"],t);var n=new THREE.PointLight(16777215,.4);n.position.set(-1.5,-1.5,2),n.castShadow=!1,n.distance=10,n.shadow.mapSize.width=1024,n.shadow.mapSize.height=1024,n.shadow.camera.near=.5,n.shadow.camera.far=10,n.shadow.bias=-.001,this.set_object(["Lights","PointLightPositiveX"],n);var r=new THREE.AmbientLight(16777215,.3);r.intensity=.6,this.set_object(["Lights","AmbientLight"],r);var i=new THREE.DirectionalLight(16777215,.4);i.position.set(-10,-10,0),this.set_object(["Lights","FillLight"],i);var o=new THREE.GridHelper(20,40);o.rotateX(Math.PI/2),this.set_object(["Grid"],o);var a=new THREE.AxesHelper(.5);this.set_object(["Axes"],a)}create_scene_tree(){this.gui&&this.gui.destroy(),this.gui=new dat.GUI({autoPlace:!1}),this.dom_element.parentElement.appendChild(this.gui.domElement),this.gui.domElement.style.position="absolute",this.gui.domElement.style.right=0,this.gui.domElement.style.top=0;let e=this.gui.addFolder("Scene");e.open(),this.scene_tree=new SceneNode(this.scene,e,()=>this.set_dirty());let t=this.gui.addFolder("Save / Load / Capture");t.add(this,"save_scene"),t.add(this,"load_scene"),t.add(this,"save_image"),this.animator=new Animator(this),this.gui.close(),this.set_property(["Background"],"top_color",[135,206,250]),this.set_property(["Background"],"bottom_color",[25,25,112]),this.scene_tree.find(["Background"]).on_update=()=>{this.scene_tree.find(["Background"]).object.visible?this.show_background():this.hide_background()},this.show_background()}set_3d_pane_size(e,t){void 0===e&&(e=this.dom_element.offsetWidth),void 0===t&&(t=window.innerHeight),"OrthographicCamera"==this.camera.type?this.camera.right=this.camera.left+e*(this.camera.top-this.camera.bottom)/t:this.camera.aspect=e/t,this.camera.updateProjectionMatrix(),this.renderer.setSize(e,t),this.set_dirty()}render(){this.controls.update(),this.camera.updateProjectionMatrix(),this.renderer.render(this.scene,this.camera),this.animator.after_render(),this.needs_render=!1}animate(){requestAnimationFrame(()=>this.animate()),this.animator.update(),this.needs_render&&this.render()}capture_image(){return this.render(),this.renderer.domElement.toDataURL()}save_image(){download_data_uri("meshcat.png",this.capture_image())}set_camera(e){this.camera=e,this.controls=new three_examples_jsm_controls_OrbitControls_js__WEBPACK_IMPORTED_MODULE_6__.a(e,this.dom_element),this.controls.enableKeys=!1,this.controls.screenSpacePanning=!0,this.controls.addEventListener("start",()=>{this.set_dirty()}),this.controls.addEventListener("change",()=>{this.set_dirty()})}set_camera_from_json(e){(new ExtensibleObjectLoader).parse(e,e=>{this.set_camera(e)})}set_transform(e,t){this.scene_tree.find(e).set_transform(t)}set_object(e,t){this.scene_tree.find(e.concat([""])).set_object(t)}set_object_from_json(e,t){let n=new ExtensibleObjectLoader;n.onTextureLoad=()=>{this.set_dirty()},n.parse(t,t=>{void 0!==t.geometry&&"BufferGeometry"==t.geometry.type?void 0!==t.geometry.attributes.normal&&0!==t.geometry.attributes.normal.count||t.geometry.computeVertexNormals():t.type.includes("Camera")&&(this.set_camera(t),this.set_3d_pane_size()),t.castShadow=!0,t.receiveShadow=!0,this.set_object(e,t),this.set_dirty()})}delete_path(e){0==e.length?console.error("Deleting the entire scene is not implemented"):this.scene_tree.delete(e)}set_property(e,t,n){this.scene_tree.find(e).set_property(t,n),"Background"===e[0]&&this.scene_tree.find(e).on_update()}set_animation(e,t){t=t||{},this.animator.load(e,t)}set_control(name,callback,value,min,max,step){let handler={};if(void 0!==value){handler[name]=value;let controller=this.gui.add(handler,name,min,max,step);controller.onChange(eval(callback))}else handler[name]=eval(callback),this.gui.add(handler,name)}handle_command(e){if("set_transform"==e.type){let t=split_path(e.path);this.set_transform(t,e.matrix)}else if("delete"==e.type){let t=split_path(e.path);this.delete_path(t)}else if("set_object"==e.type){let t=split_path(e.path);this.set_object_from_json(t,e.object)}else if("set_property"==e.type){let t=split_path(e.path);this.set_property(t,e.property,e.value)}else"set_animation"==e.type?(e.animations.forEach(e=>{e.path=split_path(e.path)}),this.set_animation(e.animations,e.options)):"set_control"==e.type&&this.set_control(e.name,e.callback,e.value,e.min,e.max,e.step);this.set_dirty()}handle_command_bytearray(e){let t=msgpack.decode(e);this.handle_command(t)}handle_command_message(e){this.handle_command_bytearray(new Uint8Array(e.data))}connect(e){void 0===e&&(e=`ws://${location.host}`),"https:"==location.protocol&&(e=e.replace("ws:","wss:")),console.log(e),this.connection=new WebSocket(e),console.log("connection:",this.connection),this.connection.binaryType="arraybuffer",this.connection.onmessage=e=>this.handle_command_message(e),this.connection.onclose=function(e){console.log("onclose:",e)}}save_scene(){download_file("scene.json",JSON.stringify(this.scene.toJSON()))}load_scene_from_json(e){let t=new ExtensibleObjectLoader;t.onTextureLoad=()=>{this.set_dirty()},this.scene_tree.dispose_recursive(),this.scene=t.parse(e),this.show_background(),this.create_scene_tree();let n=this.scene_tree.find(["Cameras","default","rotated",""]);n.object.isCamera?this.set_camera(n.object):this.create_camera()}handle_load_file(e){let t=e.files[0];if(!t)return;let n=new FileReader,r=this;n.onload=function(e){let t=this.result,n=JSON.parse(t);r.load_scene_from_json(n)},n.readAsText(t)}load_scene(){let e=document.createElement("input");e.type="file",document.body.appendChild(e);let t=this;e.addEventListener("change",(function(){console.log(this,t),t.handle_load_file(this)}),!1),e.click(),e.remove()}}function split_path(e){return e.split("/").filter(e=>e.length>0)}let style=document.createElement("style");style.appendChild(document.createTextNode("")),document.head.appendChild(style),style.sheet.insertRule("\\n .meshcat-visibility-checkbox > input {\\n float: right;\\n }"),style.sheet.insertRule("\\n .meshcat-hidden-scene-element li .meshcat-visibility-checkbox {\\n opacity: 0.25;\\n pointer-events: none;\\n }"),style.sheet.insertRule("\\n .meshcat-visibility-checkbox > input[type=checkbox] {\\n height: 16px;\\n width: 16px;\\n display:inline-block;\\n padding: 0 0 0 0px;\\n }")},function(e,t,n){t.encode=n(14).encode,t.decode=n(20).decode,t.Encoder=n(40).Encoder,t.Decoder=n(41).Decoder,t.createCodec=n(42).createCodec,t.codec=n(43).codec},function(e,t,n){(function(t){function n(e){return e&&e.isBuffer&&e}e.exports=n(void 0!==t&&t)||n(this.Buffer)||n("undefined"!=typeof window&&window.Buffer)||this.Buffer}).call(this,n(16).Buffer)},function(e,t,n){"use strict";t.byteLength=function(e){var t=l(e),n=t[0],r=t[1];return 3*(n+r)/4-r},t.toByteArray=function(e){var t,n,r=l(e),a=r[0],s=r[1],c=new o(function(e,t,n){return 3*(t+n)/4-n}(0,a,s)),u=0,h=s>0?a-4:a;for(n=0;n>16&255,c[u++]=t>>8&255,c[u++]=255&t;2===s&&(t=i[e.charCodeAt(n)]<<2|i[e.charCodeAt(n+1)]>>4,c[u++]=255&t);1===s&&(t=i[e.charCodeAt(n)]<<10|i[e.charCodeAt(n+1)]<<4|i[e.charCodeAt(n+2)]>>2,c[u++]=t>>8&255,c[u++]=255&t);return c},t.fromByteArray=function(e){for(var t,n=e.length,i=n%3,o=[],a=0,s=n-i;as?s:a+16383));1===i?(t=e[n-1],o.push(r[t>>2]+r[t<<4&63]+"==")):2===i&&(t=(e[n-2]<<8)+e[n-1],o.push(r[t>>10]+r[t>>4&63]+r[t<<2&63]+"="));return o.join("")};for(var r=[],i=[],o="undefined"!=typeof Uint8Array?Uint8Array:Array,a="ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/",s=0,c=a.length;s0)throw new Error("Invalid string. Length must be a multiple of 4");var n=e.indexOf("=");return-1===n&&(n=t),[n,n===t?0:4-n%4]}function u(e,t,n){for(var i,o,a=[],s=t;s>18&63]+r[o>>12&63]+r[o>>6&63]+r[63&o]);return a.join("")}i["-".charCodeAt(0)]=62,i["_".charCodeAt(0)]=63},function(e,t,n){var r=n(1);function i(e){return new Array(e)}(t=e.exports=i(0)).alloc=i,t.concat=r.concat,t.from=function(e){if(!r.isBuffer(e)&&r.isView(e))e=r.Uint8Array.from(e);else if(r.isArrayBuffer(e))e=new Uint8Array(e);else{if("string"==typeof e)return r.from.call(t,e);if("number"==typeof e)throw new TypeError('"value" argument must not be a number')}return Array.prototype.slice.call(e)}},function(e,t,n){var r=n(1),i=r.global;function o(e){return new i(e)}(t=e.exports=r.hasBuffer?o(0):[]).alloc=r.hasBuffer&&i.alloc||o,t.concat=r.concat,t.from=function(e){if(!r.isBuffer(e)&&r.isView(e))e=r.Uint8Array.from(e);else if(r.isArrayBuffer(e))e=new Uint8Array(e);else{if("string"==typeof e)return r.from.call(t,e);if("number"==typeof e)throw new TypeError('"value" argument must not be a number')}return i.from&&1!==i.from.length?i.from(e):new i(e)}},function(e,t,n){var r=n(1);function i(e){return new Uint8Array(e)}(t=e.exports=r.hasArrayBuffer?i(0):[]).alloc=i,t.concat=r.concat,t.from=function(e){if(r.isView(e)){var n=e.byteOffset,i=e.byteLength;(e=e.buffer).byteLength!==i&&(e.slice?e=e.slice(n,n+i):(e=new Uint8Array(e)).byteLength!==i&&(e=Array.prototype.slice.call(e,n,n+i)))}else{if("string"==typeof e)return r.from.call(t,e);if("number"==typeof e)throw new TypeError('"value" argument must not be a number')}return new Uint8Array(e)}},function(e,t){t.copy=function(e,t,n,r){var i;n||(n=0);r||0===r||(r=this.length);t||(t=0);var o=r-n;if(e===this&&n=0;i--)e[i+t]=this[i+n];else for(i=0;i=65536?(o-=65536,i+=String.fromCharCode(55296+(o>>>10),56320+(1023&o))):i+=String.fromCharCode(o));return i},t.write=function(e,t){var n=t||(t|=0),r=e.length,i=0,o=0;for(;o>>6,this[n++]=128|63&i):i<55296||i>57343?(this[n++]=224|i>>>12,this[n++]=128|i>>>6&63,this[n++]=128|63&i):(i=65536+(i-55296<<10|e.charCodeAt(o++)-56320),this[n++]=240|i>>>18,this[n++]=128|i>>>12&63,this[n++]=128|i>>>6&63,this[n++]=128|63&i);return n-t}},function(e,t,n){t.setExtPackers=function(e){e.addExtPacker(14,Error,[h,c]),e.addExtPacker(1,EvalError,[h,c]),e.addExtPacker(2,RangeError,[h,c]),e.addExtPacker(3,ReferenceError,[h,c]),e.addExtPacker(4,SyntaxError,[h,c]),e.addExtPacker(5,TypeError,[h,c]),e.addExtPacker(6,URIError,[h,c]),e.addExtPacker(10,RegExp,[u,c]),e.addExtPacker(11,Boolean,[l,c]),e.addExtPacker(12,String,[l,c]),e.addExtPacker(13,Date,[Number,c]),e.addExtPacker(15,Number,[l,c]),"undefined"!=typeof Uint8Array&&(e.addExtPacker(17,Int8Array,a),e.addExtPacker(18,Uint8Array,a),e.addExtPacker(19,Int16Array,a),e.addExtPacker(20,Uint16Array,a),e.addExtPacker(21,Int32Array,a),e.addExtPacker(22,Uint32Array,a),e.addExtPacker(23,Float32Array,a),"undefined"!=typeof Float64Array&&e.addExtPacker(24,Float64Array,a),"undefined"!=typeof Uint8ClampedArray&&e.addExtPacker(25,Uint8ClampedArray,a),e.addExtPacker(26,ArrayBuffer,a),e.addExtPacker(29,DataView,a));i.hasBuffer&&e.addExtPacker(27,o,i.from)};var r,i=n(1),o=i.global,a=i.Uint8Array.from,s={name:1,message:1,stack:1,columnNumber:1,fileName:1,lineNumber:1};function c(e){return r||(r=n(14).encode),r(e)}function l(e){return e.valueOf()}function u(e){(e=RegExp.prototype.toString.call(e).split("/")).shift();var t=[e.pop()];return t.unshift(e.join("/")),t}function h(e){var t={};for(var n in s)t[n]=e[n];return t}},function(e,t,n){var r=n(2),i=n(9),o=i.Uint64BE,a=i.Int64BE,s=n(1),c=n(8),l=n(37),u=n(18).uint8,h=n(6).ExtBuffer,d="undefined"!=typeof Uint8Array,p="undefined"!=typeof Map,f=[];f[1]=212,f[2]=213,f[4]=214,f[8]=215,f[16]=216,t.getWriteType=function(e){var t=l.getWriteToken(e),n=e&&e.useraw,i=d&&e&&e.binarraybuffer,m=i?s.isArrayBuffer:s.isBuffer,g=i?function(e,t){x(e,new Uint8Array(t))}:x,v=p&&e&&e.usemap?function(e,n){if(!(n instanceof Map))return w(e,n);var r=n.size;t[r<16?128+r:r<=65535?222:223](e,r);var i=e.codec.encode;n.forEach((function(t,n,r){i(e,n),i(e,t)}))}:w;return{boolean:function(e,n){t[n?195:194](e,n)},function:_,number:function(e,n){var r,i=0|n;if(n!==i)return void t[r=203](e,n);r=-32<=i&&i<=127?255&i:0<=i?i<=255?204:i<=65535?205:206:-128<=i?208:-32768<=i?209:210;t[r](e,i)},object:n?function(e,n){if(m(n))return function(e,n){var r=n.length;t[r<32?160+r:r<=65535?218:219](e,r),e.send(n)}(e,n);b(e,n)}:b,string:(y=n?function(e){return e<32?1:e<=65535?3:5}:function(e){return e<32?1:e<=255?2:e<=65535?3:5},function(e,n){var r=n.length,i=5+3*r;e.offset=e.reserve(i);var o=e.buffer,a=y(r),s=e.offset+a;r=c.write.call(o,n,s);var l=y(r);if(a!==l){var u=s+l-a,h=s+r;c.copy.call(o,o,u,s,h)}t[1===l?160+r:l<=3?215+l:219](e,r),e.offset+=r}),symbol:_,undefined:_};var y;function b(e,n){if(null===n)return _(e,n);if(m(n))return g(e,n);if(r(n))return function(e,n){var r=n.length;t[r<16?144+r:r<=65535?220:221](e,r);for(var i=e.codec.encode,o=0;o>>8,i[r]=n}}function m(e){return function(t,n){var r=t.reserve(5),i=t.buffer;i[r++]=e,i[r++]=n>>>24,i[r++]=n>>>16,i[r++]=n>>>8,i[r]=n}}function g(e,t,n,r){return function(i,o){var a=i.reserve(t+1);i.buffer[a++]=e,n.call(i.buffer,o,a,r)}}function v(e,t){new o(this,t,e)}function y(e,t){new a(this,t,e)}function b(e,t){r.write(this,e,t,!1,23,4)}function _(e,t){r.write(this,e,t,!1,52,8)}t.getWriteToken=function(e){return e&&e.uint8array?((t=d())[202]=g(202,4,b),t[203]=g(203,8,_),t):u||c.hasBuffer&&e&&e.safe?function(){var e=s.slice();return e[196]=g(196,1,l.prototype.writeUInt8),e[197]=g(197,2,l.prototype.writeUInt16BE),e[198]=g(198,4,l.prototype.writeUInt32BE),e[199]=g(199,1,l.prototype.writeUInt8),e[200]=g(200,2,l.prototype.writeUInt16BE),e[201]=g(201,4,l.prototype.writeUInt32BE),e[202]=g(202,4,l.prototype.writeFloatBE),e[203]=g(203,8,l.prototype.writeDoubleBE),e[204]=g(204,1,l.prototype.writeUInt8),e[205]=g(205,2,l.prototype.writeUInt16BE),e[206]=g(206,4,l.prototype.writeUInt32BE),e[207]=g(207,8,v),e[208]=g(208,1,l.prototype.writeInt8),e[209]=g(209,2,l.prototype.writeInt16BE),e[210]=g(210,4,l.prototype.writeInt32BE),e[211]=g(211,8,y),e[217]=g(217,1,l.prototype.writeUInt8),e[218]=g(218,2,l.prototype.writeUInt16BE),e[219]=g(219,4,l.prototype.writeUInt32BE),e[220]=g(220,2,l.prototype.writeUInt16BE),e[221]=g(221,4,l.prototype.writeUInt32BE),e[222]=g(222,2,l.prototype.writeUInt16BE),e[223]=g(223,4,l.prototype.writeUInt32BE),e}():d();var t}},function(e,t,n){t.setExtUnpackers=function(e){e.addExtUnpacker(14,[s,l(Error)]),e.addExtUnpacker(1,[s,l(EvalError)]),e.addExtUnpacker(2,[s,l(RangeError)]),e.addExtUnpacker(3,[s,l(ReferenceError)]),e.addExtUnpacker(4,[s,l(SyntaxError)]),e.addExtUnpacker(5,[s,l(TypeError)]),e.addExtUnpacker(6,[s,l(URIError)]),e.addExtUnpacker(10,[s,c]),e.addExtUnpacker(11,[s,u(Boolean)]),e.addExtUnpacker(12,[s,u(String)]),e.addExtUnpacker(13,[s,u(Date)]),e.addExtUnpacker(15,[s,u(Number)]),"undefined"!=typeof Uint8Array&&(e.addExtUnpacker(17,u(Int8Array)),e.addExtUnpacker(18,u(Uint8Array)),e.addExtUnpacker(19,[h,u(Int16Array)]),e.addExtUnpacker(20,[h,u(Uint16Array)]),e.addExtUnpacker(21,[h,u(Int32Array)]),e.addExtUnpacker(22,[h,u(Uint32Array)]),e.addExtUnpacker(23,[h,u(Float32Array)]),"undefined"!=typeof Float64Array&&e.addExtUnpacker(24,[h,u(Float64Array)]),"undefined"!=typeof Uint8ClampedArray&&e.addExtUnpacker(25,u(Uint8ClampedArray)),e.addExtUnpacker(26,h),e.addExtUnpacker(29,[h,u(DataView)]));i.hasBuffer&&e.addExtUnpacker(27,u(o))};var r,i=n(1),o=i.global,a={name:1,message:1,stack:1,columnNumber:1,fileName:1,lineNumber:1};function s(e){return r||(r=n(20).decode),r(e)}function c(e){return RegExp.apply(null,e)}function l(e){return function(t){var n=new e;for(var r in a)n[r]=t[r];return n}}function u(e){return function(t){return new e(t)}}function h(e){return new Uint8Array(e).buffer}},function(e,t,n){var r=n(22);function i(e){var t,n=new Array(256);for(t=0;t<=127;t++)n[t]=o(t);for(t=128;t<=143;t++)n[t]=s(t-128,e.map);for(t=144;t<=159;t++)n[t]=s(t-144,e.array);for(t=160;t<=191;t++)n[t]=s(t-160,e.str);for(n[192]=o(null),n[193]=null,n[194]=o(!1),n[195]=o(!0),n[196]=a(e.uint8,e.bin),n[197]=a(e.uint16,e.bin),n[198]=a(e.uint32,e.bin),n[199]=a(e.uint8,e.ext),n[200]=a(e.uint16,e.ext),n[201]=a(e.uint32,e.ext),n[202]=e.float32,n[203]=e.float64,n[204]=e.uint8,n[205]=e.uint16,n[206]=e.uint32,n[207]=e.uint64,n[208]=e.int8,n[209]=e.int16,n[210]=e.int32,n[211]=e.int64,n[212]=s(1,e.ext),n[213]=s(2,e.ext),n[214]=s(4,e.ext),n[215]=s(8,e.ext),n[216]=s(16,e.ext),n[217]=a(e.uint8,e.str),n[218]=a(e.uint16,e.str),n[219]=a(e.uint32,e.str),n[220]=a(e.uint16,e.array),n[221]=a(e.uint32,e.array),n[222]=a(e.uint16,e.map),n[223]=a(e.uint32,e.map),t=224;t<=255;t++)n[t]=o(t-256);return n}function o(e){return function(){return e}}function a(e,t){return function(n){var r=e(n);return t(n,r)}}function s(e,t){return function(n){return t(n,e)}}t.getReadToken=function(e){var t=r.getReadFormat(e);return e&&e.useraw?function(e){var t,n=i(e).slice();for(n[217]=n[196],n[218]=n[197],n[219]=n[198],t=160;t<=191;t++)n[t]=s(t-160,e.bin);return n}(t):i(t)}},function(e,t,n){t.Encoder=o;var r=n(23),i=n(15).EncodeBuffer;function o(e){if(!(this instanceof o))return new o(e);i.call(this,e)}o.prototype=new i,r.mixin(o.prototype),o.prototype.encode=function(e){this.write(e),this.emit("data",this.read())},o.prototype.end=function(e){arguments.length&&this.encode(e),this.flush(),this.emit("end")}},function(e,t,n){t.Decoder=o;var r=n(23),i=n(21).DecodeBuffer;function o(e){if(!(this instanceof o))return new o(e);i.call(this,e)}o.prototype=new i,r.mixin(o.prototype),o.prototype.decode=function(e){arguments.length&&this.write(e),this.flush()},o.prototype.push=function(e){this.emit("data",e)},o.prototype.end=function(e){this.decode(e),this.emit("end")}},function(e,t,n){n(10),n(5),t.createCodec=n(3).createCodec},function(e,t,n){n(10),n(5),t.codec={preset:n(3).preset}},function(e,t,n){"use strict";function r(e,t){var n=e.__state.conversionName.toString(),r=Math.round(e.r),i=Math.round(e.g),o=Math.round(e.b),a=e.a,s=Math.round(e.h),c=e.s.toFixed(1),l=e.v.toFixed(1);if(t||"THREE_CHAR_HEX"===n||"SIX_CHAR_HEX"===n){for(var u=e.hex.toString(16);u.length<6;)u="0"+u;return"#"+u}return"CSS_RGB"===n?"rgb("+r+","+i+","+o+")":"CSS_RGBA"===n?"rgba("+r+","+i+","+o+","+a+")":"HEX"===n?"0x"+e.hex.toString(16):"RGB_ARRAY"===n?"["+r+","+i+","+o+"]":"RGBA_ARRAY"===n?"["+r+","+i+","+o+","+a+"]":"RGB_OBJ"===n?"{r:"+r+",g:"+i+",b:"+o+"}":"RGBA_OBJ"===n?"{r:"+r+",g:"+i+",b:"+o+",a:"+a+"}":"HSV_OBJ"===n?"{h:"+s+",s:"+c+",v:"+l+"}":"HSVA_OBJ"===n?"{h:"+s+",s:"+c+",v:"+l+",a:"+a+"}":"unknown format"}n.r(t),n.d(t,"color",(function(){return ue})),n.d(t,"controllers",(function(){return he})),n.d(t,"dom",(function(){return de})),n.d(t,"gui",(function(){return pe})),n.d(t,"GUI",(function(){return fe}));var i=Array.prototype.forEach,o=Array.prototype.slice,a={BREAK:{},extend:function(e){return this.each(o.call(arguments,1),(function(t){(this.isObject(t)?Object.keys(t):[]).forEach(function(n){this.isUndefined(t[n])||(e[n]=t[n])}.bind(this))}),this),e},defaults:function(e){return this.each(o.call(arguments,1),(function(t){(this.isObject(t)?Object.keys(t):[]).forEach(function(n){this.isUndefined(e[n])&&(e[n]=t[n])}.bind(this))}),this),e},compose:function(){var e=o.call(arguments);return function(){for(var t=o.call(arguments),n=e.length-1;n>=0;n--)t=[e[n].apply(this,t)];return t[0]}},each:function(e,t,n){if(e)if(i&&e.forEach&&e.forEach===i)e.forEach(t,n);else if(e.length===e.length+0){var r,o=void 0;for(o=0,r=e.length;o1?a.toArray(arguments):arguments[0];return a.each(s,(function(t){if(t.litmus(e))return a.each(t.conversions,(function(t,n){if(c=t.read(e),!1===l&&!1!==c)return l=c,c.conversionName=n,c.conversion=t,a.BREAK})),a.BREAK})),l},h=void 0,d={hsv_to_rgb:function(e,t,n){var r=Math.floor(e/60)%6,i=e/60-Math.floor(e/60),o=n*(1-t),a=n*(1-i*t),s=n*(1-(1-i)*t),c=[[n,s,o],[a,n,o],[o,n,s],[o,a,n],[s,o,n],[n,o,a]][r];return{r:255*c[0],g:255*c[1],b:255*c[2]}},rgb_to_hsv:function(e,t,n){var r=Math.min(e,t,n),i=Math.max(e,t,n),o=i-r,a=void 0;return 0===i?{h:NaN,s:0,v:0}:(a=e===i?(t-n)/o:t===i?2+(n-e)/o:4+(e-t)/o,(a/=6)<0&&(a+=1),{h:360*a,s:o/i,v:i/255})},rgb_to_hex:function(e,t,n){var r=this.hex_with_component(0,2,e);return r=this.hex_with_component(r,1,t),r=this.hex_with_component(r,0,n)},component_from_hex:function(e,t){return e>>8*t&255},hex_with_component:function(e,t,n){return n<<(h=8*t)|e&~(255<-1?t.length-t.indexOf(".")-1:0}var P=function(e){function t(e,n,r){f(this,t);var i=y(this,(t.__proto__||Object.getPrototypeOf(t)).call(this,e,n)),o=r||{};return i.__min=o.min,i.__max=o.max,i.__step=o.step,a.isUndefined(i.__step)?0===i.initialValue?i.__impliedStep=1:i.__impliedStep=Math.pow(10,Math.floor(Math.log(Math.abs(i.initialValue))/Math.LN10))/10:i.__impliedStep=i.__step,i.__precision=R(i.__impliedStep),i}return v(t,e),m(t,[{key:"setValue",value:function(e){var n=e;return void 0!==this.__min&&nthis.__max&&(n=this.__max),void 0!==this.__step&&n%this.__step!=0&&(n=Math.round(n/this.__step)*this.__step),g(t.prototype.__proto__||Object.getPrototypeOf(t.prototype),"setValue",this).call(this,n)}},{key:"min",value:function(e){return this.__min=e,this}},{key:"max",value:function(e){return this.__max=e,this}},{key:"step",value:function(e){return this.__step=e,this.__impliedStep=e,this.__precision=R(e),this}}]),t}(w);var O=function(e){function t(e,n,r){f(this,t);var i=y(this,(t.__proto__||Object.getPrototypeOf(t)).call(this,e,n,r));i.__truncationSuspended=!1;var o=i,s=void 0;function c(){o.__onFinishChange&&o.__onFinishChange.call(o,o.getValue())}function l(e){var t=s-e.clientY;o.setValue(o.getValue()+t*o.__impliedStep),s=e.clientY}function u(){S.unbind(window,"mousemove",l),S.unbind(window,"mouseup",u),c()}return i.__input=document.createElement("input"),i.__input.setAttribute("type","text"),S.bind(i.__input,"change",(function(){var e=parseFloat(o.__input.value);a.isNaN(e)||o.setValue(e)})),S.bind(i.__input,"blur",(function(){c()})),S.bind(i.__input,"mousedown",(function(e){S.bind(window,"mousemove",l),S.bind(window,"mouseup",u),s=e.clientY})),S.bind(i.__input,"keydown",(function(e){13===e.keyCode&&(o.__truncationSuspended=!0,this.blur(),o.__truncationSuspended=!1,c())})),i.updateDisplay(),i.domElement.appendChild(i.__input),i}return v(t,e),m(t,[{key:"updateDisplay",value:function(){var e,n,r;return this.__input.value=this.__truncationSuspended?this.getValue():(e=this.getValue(),n=this.__precision,r=Math.pow(10,n),Math.round(e*r)/r),g(t.prototype.__proto__||Object.getPrototypeOf(t.prototype),"updateDisplay",this).call(this)}}]),t}(P);function N(e,t,n,r,i){return r+(e-t)/(n-t)*(i-r)}var I=function(e){function t(e,n,r,i,o){f(this,t);var a=y(this,(t.__proto__||Object.getPrototypeOf(t)).call(this,e,n,{min:r,max:i,step:o})),s=a;function c(e){e.preventDefault();var t=s.__background.getBoundingClientRect();return s.setValue(N(e.clientX,t.left,t.right,s.__min,s.__max)),!1}function l(){S.unbind(window,"mousemove",c),S.unbind(window,"mouseup",l),s.__onFinishChange&&s.__onFinishChange.call(s,s.getValue())}function u(e){var t=e.touches[0].clientX,n=s.__background.getBoundingClientRect();s.setValue(N(t,n.left,n.right,s.__min,s.__max))}function h(){S.unbind(window,"touchmove",u),S.unbind(window,"touchend",h),s.__onFinishChange&&s.__onFinishChange.call(s,s.getValue())}return a.__background=document.createElement("div"),a.__foreground=document.createElement("div"),S.bind(a.__background,"mousedown",(function(e){document.activeElement.blur(),S.bind(window,"mousemove",c),S.bind(window,"mouseup",l),c(e)})),S.bind(a.__background,"touchstart",(function(e){if(1!==e.touches.length)return;S.bind(window,"touchmove",u),S.bind(window,"touchend",h),u(e)})),S.addClass(a.__background,"slider"),S.addClass(a.__foreground,"slider-fg"),a.updateDisplay(),a.__background.appendChild(a.__foreground),a.domElement.appendChild(a.__background),a}return v(t,e),m(t,[{key:"updateDisplay",value:function(){var e=(this.getValue()-this.__min)/(this.__max-this.__min);return this.__foreground.style.width=100*e+"%",g(t.prototype.__proto__||Object.getPrototypeOf(t.prototype),"updateDisplay",this).call(this)}}]),t}(P),D=function(e){function t(e,n,r){f(this,t);var i=y(this,(t.__proto__||Object.getPrototypeOf(t)).call(this,e,n)),o=i;return i.__button=document.createElement("div"),i.__button.innerHTML=void 0===r?"Fire":r,S.bind(i.__button,"click",(function(e){return e.preventDefault(),o.fire(),!1})),S.addClass(i.__button,"button"),i.domElement.appendChild(i.__button),i}return v(t,e),m(t,[{key:"fire",value:function(){this.__onChange&&this.__onChange.call(this),this.getValue().call(this.object),this.__onFinishChange&&this.__onFinishChange.call(this,this.getValue())}}]),t}(w),B=function(e){function t(e,n){f(this,t);var r=y(this,(t.__proto__||Object.getPrototypeOf(t)).call(this,e,n));r.__color=new b(r.getValue()),r.__temp=new b(0);var i=r;r.domElement=document.createElement("div"),S.makeSelectable(r.domElement,!1),r.__selector=document.createElement("div"),r.__selector.className="selector",r.__saturation_field=document.createElement("div"),r.__saturation_field.className="saturation-field",r.__field_knob=document.createElement("div"),r.__field_knob.className="field-knob",r.__field_knob_border="2px solid ",r.__hue_knob=document.createElement("div"),r.__hue_knob.className="hue-knob",r.__hue_field=document.createElement("div"),r.__hue_field.className="hue-field",r.__input=document.createElement("input"),r.__input.type="text",r.__input_textShadow="0 1px 1px ",S.bind(r.__input,"keydown",(function(e){13===e.keyCode&&p.call(this)})),S.bind(r.__input,"blur",p),S.bind(r.__selector,"mousedown",(function(){S.addClass(this,"drag").bind(window,"mouseup",(function(){S.removeClass(i.__selector,"drag")}))})),S.bind(r.__selector,"touchstart",(function(){S.addClass(this,"drag").bind(window,"touchend",(function(){S.removeClass(i.__selector,"drag")}))}));var o,s=document.createElement("div");function c(e){g(e),S.bind(window,"mousemove",g),S.bind(window,"touchmove",g),S.bind(window,"mouseup",h),S.bind(window,"touchend",h)}function l(e){v(e),S.bind(window,"mousemove",v),S.bind(window,"touchmove",v),S.bind(window,"mouseup",d),S.bind(window,"touchend",d)}function h(){S.unbind(window,"mousemove",g),S.unbind(window,"touchmove",g),S.unbind(window,"mouseup",h),S.unbind(window,"touchend",h),m()}function d(){S.unbind(window,"mousemove",v),S.unbind(window,"touchmove",v),S.unbind(window,"mouseup",d),S.unbind(window,"touchend",d),m()}function p(){var e=u(this.value);!1!==e?(i.__color.__state=e,i.setValue(i.__color.toOriginal())):this.value=i.__color.toString()}function m(){i.__onFinishChange&&i.__onFinishChange.call(i,i.__color.toOriginal())}function g(e){-1===e.type.indexOf("touch")&&e.preventDefault();var t=i.__saturation_field.getBoundingClientRect(),n=e.touches&&e.touches[0]||e,r=n.clientX,o=n.clientY,a=(r-t.left)/(t.right-t.left),s=1-(o-t.top)/(t.bottom-t.top);return s>1?s=1:s<0&&(s=0),a>1?a=1:a<0&&(a=0),i.__color.v=s,i.__color.s=a,i.setValue(i.__color.toOriginal()),!1}function v(e){-1===e.type.indexOf("touch")&&e.preventDefault();var t=i.__hue_field.getBoundingClientRect(),n=1-((e.touches&&e.touches[0]||e).clientY-t.top)/(t.bottom-t.top);return n>1?n=1:n<0&&(n=0),i.__color.h=360*n,i.setValue(i.__color.toOriginal()),!1}return a.extend(r.__selector.style,{width:"122px",height:"102px",padding:"3px",backgroundColor:"#222",boxShadow:"0px 1px 3px rgba(0,0,0,0.3)"}),a.extend(r.__field_knob.style,{position:"absolute",width:"12px",height:"12px",border:r.__field_knob_border+(r.__color.v<.5?"#fff":"#000"),boxShadow:"0px 1px 3px rgba(0,0,0,0.5)",borderRadius:"12px",zIndex:1}),a.extend(r.__hue_knob.style,{position:"absolute",width:"15px",height:"2px",borderRight:"4px solid #fff",zIndex:1}),a.extend(r.__saturation_field.style,{width:"100px",height:"100px",border:"1px solid #555",marginRight:"3px",display:"inline-block",cursor:"pointer"}),a.extend(s.style,{width:"100%",height:"100%",background:"none"}),U(s,"top","rgba(0,0,0,0)","#000"),a.extend(r.__hue_field.style,{width:"15px",height:"100px",border:"1px solid #555",cursor:"ns-resize",position:"absolute",top:"3px",right:"3px"}),(o=r.__hue_field).style.background="",o.style.cssText+="background: -moz-linear-gradient(top, #ff0000 0%, #ff00ff 17%, #0000ff 34%, #00ffff 50%, #00ff00 67%, #ffff00 84%, #ff0000 100%);",o.style.cssText+="background: -webkit-linear-gradient(top, #ff0000 0%,#ff00ff 17%,#0000ff 34%,#00ffff 50%,#00ff00 67%,#ffff00 84%,#ff0000 100%);",o.style.cssText+="background: -o-linear-gradient(top, #ff0000 0%,#ff00ff 17%,#0000ff 34%,#00ffff 50%,#00ff00 67%,#ffff00 84%,#ff0000 100%);",o.style.cssText+="background: -ms-linear-gradient(top, #ff0000 0%,#ff00ff 17%,#0000ff 34%,#00ffff 50%,#00ff00 67%,#ffff00 84%,#ff0000 100%);",o.style.cssText+="background: linear-gradient(top, #ff0000 0%,#ff00ff 17%,#0000ff 34%,#00ffff 50%,#00ff00 67%,#ffff00 84%,#ff0000 100%);",a.extend(r.__input.style,{outline:"none",textAlign:"center",color:"#fff",border:0,fontWeight:"bold",textShadow:r.__input_textShadow+"rgba(0,0,0,0.7)"}),S.bind(r.__saturation_field,"mousedown",c),S.bind(r.__saturation_field,"touchstart",c),S.bind(r.__field_knob,"mousedown",c),S.bind(r.__field_knob,"touchstart",c),S.bind(r.__hue_field,"mousedown",l),S.bind(r.__hue_field,"touchstart",l),r.__saturation_field.appendChild(s),r.__selector.appendChild(r.__field_knob),r.__selector.appendChild(r.__saturation_field),r.__selector.appendChild(r.__hue_field),r.__hue_field.appendChild(r.__hue_knob),r.domElement.appendChild(r.__input),r.domElement.appendChild(r.__selector),r.updateDisplay(),r}return v(t,e),m(t,[{key:"updateDisplay",value:function(){var e=u(this.getValue());if(!1!==e){var t=!1;a.each(b.COMPONENTS,(function(n){if(!a.isUndefined(e[n])&&!a.isUndefined(this.__color.__state[n])&&e[n]!==this.__color.__state[n])return t=!0,{}}),this),t&&a.extend(this.__color.__state,e)}a.extend(this.__temp.__state,this.__color.__state),this.__temp.a=1;var n=this.__color.v<.5||this.__color.s>.5?255:0,r=255-n;a.extend(this.__field_knob.style,{marginLeft:100*this.__color.s-7+"px",marginTop:100*(1-this.__color.v)-7+"px",backgroundColor:this.__temp.toHexString(),border:this.__field_knob_border+"rgb("+n+","+n+","+n+")"}),this.__hue_knob.style.marginTop=100*(1-this.__color.h/360)+"px",this.__temp.s=1,this.__temp.v=1,U(this.__saturation_field,"left","#fff",this.__temp.toHexString()),this.__input.value=this.__color.toString(),a.extend(this.__input.style,{backgroundColor:this.__color.toHexString(),color:"rgb("+n+","+n+","+n+")",textShadow:this.__input_textShadow+"rgba("+r+","+r+","+r+",.7)"})}}]),t}(w),k=["-moz-","-o-","-webkit-","-ms-",""];function U(e,t,n,r){e.style.background="",a.each(k,(function(i){e.style.cssText+="background: "+i+"linear-gradient("+t+", "+n+" 0%, "+r+" 100%); "}))}var F=function(e,t){var n=t||document,r=document.createElement("style");r.type="text/css",r.innerHTML=e;var i=n.getElementsByTagName("head")[0];try{i.appendChild(r)}catch(e){}},z='
\\n\\n Here\\'s the new load parameter for your GUI\\'s constructor:\\n\\n \\n\\n
\\n\\n Automatically save\\n values to localStorage on exit.\\n\\n
The values saved to localStorage will\\n override those passed to dat.GUI\\'s constructor. This makes it\\n easier to work incrementally, but localStorage is fragile,\\n and your friends may not see the same values you do.\\n\\n
\\n\\n
\\n\\n
',G=function(e,t){var n=e[t];return a.isArray(arguments[2])||a.isObject(arguments[2])?new L(e,t,arguments[2]):a.isNumber(n)?a.isNumber(arguments[2])&&a.isNumber(arguments[3])?a.isNumber(arguments[4])?new I(e,t,arguments[2],arguments[3],arguments[4]):new I(e,t,arguments[2],arguments[3]):a.isNumber(arguments[4])?new O(e,t,{min:arguments[2],max:arguments[3],step:arguments[4]}):new O(e,t,{min:arguments[2],max:arguments[3]}):a.isString(n)?new C(e,t):a.isFunction(n)?new D(e,t,""):a.isBoolean(n)?new A(e,t):null};var H=window.requestAnimationFrame||window.webkitRequestAnimationFrame||window.mozRequestAnimationFrame||window.oRequestAnimationFrame||window.msRequestAnimationFrame||function(e){setTimeout(e,1e3/60)},j=function(){function e(){f(this,e),this.backgroundElement=document.createElement("div"),a.extend(this.backgroundElement.style,{backgroundColor:"rgba(0,0,0,0.8)",top:0,left:0,display:"none",zIndex:"1000",opacity:0,WebkitTransition:"opacity 0.2s linear",transition:"opacity 0.2s linear"}),S.makeFullscreen(this.backgroundElement),this.backgroundElement.style.position="fixed",this.domElement=document.createElement("div"),a.extend(this.domElement.style,{position:"fixed",display:"none",zIndex:"1001",opacity:0,WebkitTransition:"-webkit-transform 0.2s ease-out, opacity 0.2s linear",transition:"transform 0.2s ease-out, opacity 0.2s linear"}),document.body.appendChild(this.backgroundElement),document.body.appendChild(this.domElement);var t=this;S.bind(this.backgroundElement,"click",(function(){t.hide()}))}return m(e,[{key:"show",value:function(){var e=this;this.backgroundElement.style.display="block",this.domElement.style.display="block",this.domElement.style.opacity=0,this.domElement.style.webkitTransform="scale(1.1)",this.layout(),a.defer((function(){e.backgroundElement.style.opacity=1,e.domElement.style.opacity=1,e.domElement.style.webkitTransform="scale(1)"}))}},{key:"hide",value:function(){var e=this,t=function t(){e.domElement.style.display="none",e.backgroundElement.style.display="none",S.unbind(e.domElement,"webkitTransitionEnd",t),S.unbind(e.domElement,"transitionend",t),S.unbind(e.domElement,"oTransitionEnd",t)};S.bind(this.domElement,"webkitTransitionEnd",t),S.bind(this.domElement,"transitionend",t),S.bind(this.domElement,"oTransitionEnd",t),this.backgroundElement.style.opacity=0,this.domElement.style.opacity=0,this.domElement.style.webkitTransform="scale(1.1)"}},{key:"layout",value:function(){this.domElement.style.left=window.innerWidth/2-S.getWidth(this.domElement)/2+"px",this.domElement.style.top=window.innerHeight/2-S.getHeight(this.domElement)/2+"px"}}]),e}();F(function(e){if(e&&"undefined"!=typeof window){var t=document.createElement("style");return t.setAttribute("type","text/css"),t.innerHTML=e,document.head.appendChild(t),e}}(".dg ul{list-style:none;margin:0;padding:0;width:100%;clear:both}.dg.ac{position:fixed;top:0;left:0;right:0;height:0;z-index:0}.dg:not(.ac) .main{overflow:hidden}.dg.main{-webkit-transition:opacity .1s linear;-o-transition:opacity .1s linear;-moz-transition:opacity .1s linear;transition:opacity .1s linear}.dg.main.taller-than-window{overflow-y:auto}.dg.main.taller-than-window .close-button{opacity:1;margin-top:-1px;border-top:1px solid #2c2c2c}.dg.main ul.closed .close-button{opacity:1 !important}.dg.main:hover .close-button,.dg.main .close-button.drag{opacity:1}.dg.main .close-button{-webkit-transition:opacity .1s linear;-o-transition:opacity .1s linear;-moz-transition:opacity .1s linear;transition:opacity .1s linear;border:0;line-height:19px;height:20px;cursor:pointer;text-align:center;background-color:#000}.dg.main .close-button.close-top{position:relative}.dg.main .close-button.close-bottom{position:absolute}.dg.main .close-button:hover{background-color:#111}.dg.a{float:right;margin-right:15px;overflow-y:visible}.dg.a.has-save>ul.close-top{margin-top:0}.dg.a.has-save>ul.close-bottom{margin-top:27px}.dg.a.has-save>ul.closed{margin-top:0}.dg.a .save-row{top:0;z-index:1002}.dg.a .save-row.close-top{position:relative}.dg.a .save-row.close-bottom{position:fixed}.dg li{-webkit-transition:height .1s ease-out;-o-transition:height .1s ease-out;-moz-transition:height .1s ease-out;transition:height .1s ease-out;-webkit-transition:overflow .1s linear;-o-transition:overflow .1s linear;-moz-transition:overflow .1s linear;transition:overflow .1s linear}.dg li:not(.folder){cursor:auto;height:27px;line-height:27px;padding:0 4px 0 5px}.dg li.folder{padding:0;border-left:4px solid rgba(0,0,0,0)}.dg li.title{cursor:pointer;margin-left:-4px}.dg .closed li:not(.title),.dg .closed ul li,.dg .closed ul li>*{height:0;overflow:hidden;border:0}.dg .cr{clear:both;padding-left:3px;height:27px;overflow:hidden}.dg .property-name{cursor:default;float:left;clear:left;width:40%;overflow:hidden;text-overflow:ellipsis}.dg .c{float:left;width:60%;position:relative}.dg .c input[type=text]{border:0;margin-top:4px;padding:3px;width:100%;float:right}.dg .has-slider input[type=text]{width:30%;margin-left:0}.dg .slider{float:left;width:66%;margin-left:-5px;margin-right:0;height:19px;margin-top:4px}.dg .slider-fg{height:100%}.dg .c input[type=checkbox]{margin-top:7px}.dg .c select{margin-top:5px}.dg .cr.function,.dg .cr.function .property-name,.dg .cr.function *,.dg .cr.boolean,.dg .cr.boolean *{cursor:pointer}.dg .cr.color{overflow:visible}.dg .selector{display:none;position:absolute;margin-left:-9px;margin-top:23px;z-index:10}.dg .c:hover .selector,.dg .selector.drag{display:block}.dg li.save-row{padding:0}.dg li.save-row .button{display:inline-block;padding:0px 6px}.dg.dialogue{background-color:#222;width:460px;padding:15px;font-size:13px;line-height:15px}#dg-new-constructor{padding:10px;color:#222;font-family:Monaco, monospace;font-size:10px;border:0;resize:none;box-shadow:inset 1px 1px 1px #888;word-wrap:break-word;margin:12px 0;display:block;width:440px;overflow-y:scroll;height:100px;position:relative}#dg-local-explain{display:none;font-size:11px;line-height:17px;border-radius:3px;background-color:#333;padding:8px;margin-top:10px}#dg-local-explain code{font-size:10px}#dat-gui-save-locally{display:none}.dg{color:#eee;font:11px 'Lucida Grande', sans-serif;text-shadow:0 -1px 0 #111}.dg.main::-webkit-scrollbar{width:5px;background:#1a1a1a}.dg.main::-webkit-scrollbar-corner{height:0;display:none}.dg.main::-webkit-scrollbar-thumb{border-radius:5px;background:#676767}.dg li:not(.folder){background:#1a1a1a;border-bottom:1px solid #2c2c2c}.dg li.save-row{line-height:25px;background:#dad5cb;border:0}.dg li.save-row select{margin-left:5px;width:108px}.dg li.save-row .button{margin-left:5px;margin-top:1px;border-radius:2px;font-size:9px;line-height:7px;padding:4px 4px 5px 4px;background:#c5bdad;color:#fff;text-shadow:0 1px 0 #b0a58f;box-shadow:0 -1px 0 #b0a58f;cursor:pointer}.dg li.save-row .button.gears{background:#c5bdad url(data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAsAAAANCAYAAAB/9ZQ7AAAAGXRFWHRTb2Z0d2FyZQBBZG9iZSBJbWFnZVJlYWR5ccllPAAAAQJJREFUeNpiYKAU/P//PwGIC/ApCABiBSAW+I8AClAcgKxQ4T9hoMAEUrxx2QSGN6+egDX+/vWT4e7N82AMYoPAx/evwWoYoSYbACX2s7KxCxzcsezDh3evFoDEBYTEEqycggWAzA9AuUSQQgeYPa9fPv6/YWm/Acx5IPb7ty/fw+QZblw67vDs8R0YHyQhgObx+yAJkBqmG5dPPDh1aPOGR/eugW0G4vlIoTIfyFcA+QekhhHJhPdQxbiAIguMBTQZrPD7108M6roWYDFQiIAAv6Aow/1bFwXgis+f2LUAynwoIaNcz8XNx3Dl7MEJUDGQpx9gtQ8YCueB+D26OECAAQDadt7e46D42QAAAABJRU5ErkJggg==) 2px 1px no-repeat;height:7px;width:8px}.dg li.save-row .button:hover{background-color:#bab19e;box-shadow:0 -1px 0 #b0a58f}.dg li.folder{border-bottom:0}.dg li.title{padding-left:16px;background:#000 url(data:image/gif;base64,R0lGODlhBQAFAJEAAP////Pz8////////yH5BAEAAAIALAAAAAAFAAUAAAIIlI+hKgFxoCgAOw==) 6px 10px no-repeat;cursor:pointer;border-bottom:1px solid rgba(255,255,255,0.2)}.dg .closed li.title{background-image:url(data:image/gif;base64,R0lGODlhBQAFAJEAAP////Pz8////////yH5BAEAAAIALAAAAAAFAAUAAAIIlGIWqMCbWAEAOw==)}.dg .cr.boolean{border-left:3px solid #806787}.dg .cr.color{border-left:3px solid}.dg .cr.function{border-left:3px solid #e61d5f}.dg .cr.number{border-left:3px solid #2FA1D6}.dg .cr.number input[type=text]{color:#2FA1D6}.dg .cr.string{border-left:3px solid #1ed36f}.dg .cr.string input[type=text]{color:#1ed36f}.dg .cr.function:hover,.dg .cr.boolean:hover{background:#111}.dg .c input[type=text]{background:#303030;outline:none}.dg .c input[type=text]:hover{background:#3c3c3c}.dg .c input[type=text]:focus{background:#494949;color:#fff}.dg .c .slider{background:#303030;cursor:ew-resize}.dg .c .slider-fg{background:#2FA1D6;max-width:100%}.dg .c .slider:hover{background:#3c3c3c}.dg .c .slider:hover .slider-fg{background:#44abda}\\n"));var V="Default",W=function(){try{return!!window.localStorage}catch(e){return!1}}(),q=void 0,Y=!0,X=void 0,J=!1,Z=[],K=function e(t){var n=this,r=t||{};this.domElement=document.createElement("div"),this.__ul=document.createElement("ul"),this.domElement.appendChild(this.__ul),S.addClass(this.domElement,"dg"),this.__folders={},this.__controllers=[],this.__rememberedObjects=[],this.__rememberedObjectIndecesToControllers=[],this.__listening=[],r=a.defaults(r,{closeOnTop:!1,autoPlace:!0,width:e.DEFAULT_WIDTH}),r=a.defaults(r,{resizable:r.autoPlace,hideable:r.autoPlace}),a.isUndefined(r.load)?r.load={preset:V}:r.preset&&(r.load.preset=r.preset),a.isUndefined(r.parent)&&r.hideable&&Z.push(this),r.resizable=a.isUndefined(r.parent)&&r.resizable,r.autoPlace&&a.isUndefined(r.scrollable)&&(r.scrollable=!0);var i,o=W&&"true"===localStorage.getItem(re(this,"isLocal")),s=void 0,c=void 0;if(Object.defineProperties(this,{parent:{get:function(){return r.parent}},scrollable:{get:function(){return r.scrollable}},autoPlace:{get:function(){return r.autoPlace}},closeOnTop:{get:function(){return r.closeOnTop}},preset:{get:function(){return n.parent?n.getRoot().preset:r.load.preset},set:function(e){n.parent?n.getRoot().preset=e:r.load.preset=e,function(e){for(var t=0;t1){var r=n.__li.nextElementSibling;return n.remove(),ne(e,n.object,n.property,{before:r,factoryArgs:[a.toArray(arguments)]})}if(a.isArray(t)||a.isObject(t)){var i=n.__li.nextElementSibling;return n.remove(),ne(e,n.object,n.property,{before:i,factoryArgs:[t]})}},name:function(e){return n.__li.firstElementChild.firstElementChild.innerHTML=e,n},listen:function(){return n.__gui.listen(n),n},remove:function(){return n.__gui.remove(n),n}}),n instanceof I){var r=new O(n.object,n.property,{min:n.__min,max:n.__max,step:n.__step});a.each(["updateDisplay","onChange","onFinishChange","step","min","max"],(function(e){var t=n[e],i=r[e];n[e]=r[e]=function(){var e=Array.prototype.slice.call(arguments);return i.apply(r,e),t.apply(n,e)}})),S.addClass(t,"has-slider"),n.domElement.insertBefore(r.domElement,n.domElement.firstElementChild)}else if(n instanceof O){var i=function(t){if(a.isNumber(n.__min)&&a.isNumber(n.__max)){var r=n.__li.firstElementChild.firstElementChild.innerHTML,i=n.__gui.__listening.indexOf(n)>-1;n.remove();var o=ne(e,n.object,n.property,{before:n.__li.nextElementSibling,factoryArgs:[n.__min,n.__max,n.__step]});return o.name(r),i&&o.listen(),o}return t};n.min=a.compose(i,n.min),n.max=a.compose(i,n.max)}else n instanceof A?(S.bind(t,"click",(function(){S.fakeEvent(n.__checkbox,"click")})),S.bind(n.__checkbox,"click",(function(e){e.stopPropagation()}))):n instanceof D?(S.bind(t,"click",(function(){S.fakeEvent(n.__button,"click")})),S.bind(t,"mouseover",(function(){S.addClass(n.__button,"hover")})),S.bind(t,"mouseout",(function(){S.removeClass(n.__button,"hover")}))):n instanceof B&&(S.addClass(t,"color"),n.updateDisplay=a.compose((function(e){return t.style.borderLeftColor=n.__color.toString(),e}),n.updateDisplay),n.updateDisplay());n.setValue=a.compose((function(t){return e.getRoot().__preset_select&&n.isModified()&&ee(e.getRoot(),!0),t}),n.setValue)}(e,l,i),e.__controllers.push(i),i}function re(e,t){return document.location.href+"."+t}function ie(e,t,n){var r=document.createElement("option");r.innerHTML=t,r.value=t,e.__preset_select.appendChild(r),n&&(e.__preset_select.selectedIndex=e.__preset_select.length-1)}function oe(e,t){t.style.display=e.useLocalStorage?"block":"none"}function ae(e){var t=e.__save_row=document.createElement("li");S.addClass(e.domElement,"has-save"),e.__ul.insertBefore(t,e.__ul.firstChild),S.addClass(t,"save-row");var n=document.createElement("span");n.innerHTML=" ",S.addClass(n,"button gears");var r=document.createElement("span");r.innerHTML="Save",S.addClass(r,"button"),S.addClass(r,"save");var i=document.createElement("span");i.innerHTML="New",S.addClass(i,"button"),S.addClass(i,"save-as");var o=document.createElement("span");o.innerHTML="Revert",S.addClass(o,"button"),S.addClass(o,"revert");var s=e.__preset_select=document.createElement("select");if(e.load&&e.load.remembered?a.each(e.load.remembered,(function(t,n){ie(e,n,n===e.preset)})):ie(e,V,!1),S.bind(s,"change",(function(){for(var t=0;t0&&(e.preset=this.preset,e.remembered||(e.remembered={}),e.remembered[this.preset]=le(this)),e.folders={},a.each(this.__folders,(function(t,n){e.folders[n]=t.getSaveObject()})),e},save:function(){this.load.remembered||(this.load.remembered={}),this.load.remembered[this.preset]=le(this),ee(this,!1),this.saveToLocalStorageIfPossible()},saveAs:function(e){this.load.remembered||(this.load.remembered={},this.load.remembered[V]=le(this,!0)),this.load.remembered[e]=le(this),this.preset=e,ie(this,e,!0),this.saveToLocalStorageIfPossible()},revert:function(e){a.each(this.__controllers,(function(t){this.getRoot().load.remembered?te(e||this.getRoot(),t):t.setValue(t.initialValue),t.__onFinishChange&&t.__onFinishChange.call(t,t.getValue())}),this),a.each(this.__folders,(function(e){e.revert(e)})),e||ee(this.getRoot(),!1)},listen:function(e){var t=0===this.__listening.length;this.__listening.push(e),t&&function e(t){0!==t.length&&H.call(window,(function(){e(t)}));a.each(t,(function(e){e.updateDisplay()}))}(this.__listening)},updateDisplay:function(){a.each(this.__controllers,(function(e){e.updateDisplay()})),a.each(this.__folders,(function(e){e.updateDisplay()}))}});var ue={Color:b,math:d,interpret:u},he={Controller:w,BooleanController:A,OptionController:L,StringController:C,NumberController:P,NumberControllerBox:O,NumberControllerSlider:I,FunctionController:D,ColorController:B},de={dom:S},pe={GUI:K},fe=K,me={color:ue,controllers:he,dom:de,gui:pe,GUI:fe};t.default=me},function(e,t,n){(function(e,r){var i;!function(){if(void 0!==e.exports)var o=n(47),a=n(48),s=n(49);var c={function:!0,object:!0};function l(e){return e&&e.Object===Object?e:null}parseFloat,parseInt;var u=c[typeof t]&&t&&!t.nodeType?t:void 0,h=c[typeof e]&&e&&!e.nodeType?e:void 0,d=(h&&h.exports,l(u&&h&&"object"==typeof r&&r)),p=l(c[typeof self]&&self),f=l(c[typeof window]&&window),m=l(c[typeof this]&&this);d||f!==(m&&m.window)&&f||p||m||Function("return this")();function g(e){return String("0000000"+e).slice(-7)}"gc"in window||(window.gc=function(){}),HTMLCanvasElement.prototype.toBlob||Object.defineProperty(HTMLCanvasElement.prototype,"toBlob",{value:function(e,t,n){for(var r=atob(this.toDataURL(t,n).split(",")[1]),i=r.length,o=new Uint8Array(i),a=0;a=l.frameLimit||l.timeLimit&&e>=l.timeLimit)&&(G(),V());var t=new Date(null);t.setSeconds(e),l.motionBlurFrames>2?y.textContent="CCapture "+l.format+" | "+d+" frames ("+p+" inter) | "+t.toISOString().substr(11,8):y.textContent="CCapture "+l.format+" | "+d+" frames | "+t.toISOString().substr(11,8)}(),W("Frame: "+d+" "+p);for(var a=0;a=u[a].triggerTime&&(H(u[a].callback),u.splice(a,1));for(a=0;a=h[a].triggerTime&&(H(h[a].callback),h[a].triggerTime+=h[a].time);f.forEach((function(e){H(e,n-v)})),f=[]}function V(e){e||(e=function(e){return a(e,c.filename+c.extension,c.mimeType),!1}),c.save(e)}function W(e){t&&console.log(e)}return{start:function(){!function(){function e(){return this._hooked||(this._hooked=!0,this._hookedTime=this.currentTime||0,this.pause(),z.push(this)),this._hookedTime+l.startTime}W("Capturer start"),r=window.Date.now(),n=r+l.startTime,o=window.performance.now(),i=o+l.startTime,window.Date.prototype.getTime=function(){return n},window.Date.now=function(){return n},window.setTimeout=function(e,t){var r={callback:e,time:t,triggerTime:n+t};return u.push(r),W("Timeout set to "+r.time),r},window.clearTimeout=function(e){for(var t=0;t2?(function(e){A.width===e.width&&A.height===e.height||(A.width=e.width,A.height=e.height,b=new Uint16Array(A.height*A.width*4),L.fillStyle="#0",L.fillRect(0,0,A.width,A.height))}(e),function(e){L.drawImage(e,0,0),S=L.getImageData(0,0,A.width,A.height);for(var t=0;t=.5*l.motionBlurFrames?function(){for(var e=S.data,t=0;t0&&this.frames.length/this.settings.framerate>=this.settings.autoSaveTime?this.save(function(e){this.filename=this.baseFilename+"-part-"+g(this.part),a(e,this.filename+this.extension,this.mimeType),this.dispose(),this.part++,this.filename=this.baseFilename+"-part-"+g(this.part),this.step()}.bind(this)):this.step()},w.prototype.save=function(e){this.videoWriter.complete().then(e)},w.prototype.dispose=function(e){this.frames=[]},M.prototype=Object.create(y.prototype),M.prototype.start=function(){this.encoder.start(this.settings)},M.prototype.add=function(e){this.encoder.add(e)},M.prototype.save=function(e){this.callback=e,this.encoder.end()},M.prototype.safeToProceed=function(){return this.encoder.safeToProceed()},E.prototype=Object.create(y.prototype),E.prototype.add=function(e){this.stream||(this.stream=e.captureStream(this.framerate),this.mediaRecorder=new MediaRecorder(this.stream),this.mediaRecorder.start(),this.mediaRecorder.ondataavailable=function(e){this.chunks.push(e.data)}.bind(this)),this.step()},E.prototype.save=function(e){this.mediaRecorder.onstop=function(t){var n=new Blob(this.chunks,{type:"video/webm"});this.chunks=[],e(n)}.bind(this),this.mediaRecorder.stop()},T.prototype=Object.create(y.prototype),T.prototype.add=function(e){this.sizeSet||(this.encoder.setOption("width",e.width),this.encoder.setOption("height",e.height),this.sizeSet=!0),this.canvas.width=e.width,this.canvas.height=e.height,this.ctx.drawImage(e,0,0),this.encoder.addFrame(this.ctx,{copy:!0,delay:this.settings.step}),this.step()},T.prototype.save=function(e){this.callback=e,this.encoder.render()},(f||p||{}).CCapture=S,void 0===(i=function(){return S}.call(t,n,t,e))||(e.exports=i)}()}).call(this,n(46)(e),n(17))},function(e,t){e.exports=function(e){return e.webpackPolyfill||(e.deprecate=function(){},e.paths=[],e.children||(e.children=[]),Object.defineProperty(e,"loaded",{enumerable:!0,get:function(){return e.l}}),Object.defineProperty(e,"id",{enumerable:!0,get:function(){return e.i}}),e.webpackPolyfill=1),e}},function(e,t,n){!function(){"use strict";var e=["A","B","C","D","E","F","G","H","I","J","K","L","M","N","O","P","Q","R","S","T","U","V","W","X","Y","Z","a","b","c","d","e","f","g","h","i","j","k","l","m","n","o","p","q","r","s","t","u","v","w","x","y","z","0","1","2","3","4","5","6","7","8","9","+","/"];function t(e){var t,n=new Uint8Array(e);for(t=0;t>18&63]+e[o>>12&63]+e[o>>6&63]+e[63&o];switch(s.length%4){case 1:s+="=";break;case 2:s+="=="}return s}}(),function(){"use strict";var e,t=window.utils;e=[{field:"fileName",length:100},{field:"fileMode",length:8},{field:"uid",length:8},{field:"gid",length:8},{field:"fileSize",length:12},{field:"mtime",length:12},{field:"checksum",length:8},{field:"type",length:1},{field:"linkName",length:100},{field:"ustar",length:8},{field:"owner",length:32},{field:"group",length:32},{field:"majorNumber",length:8},{field:"minorNumber",length:8},{field:"filenamePrefix",length:155},{field:"padding",length:12}],window.header={},window.header.structure=e,window.header.format=function(n,r){var i=t.clean(512),o=0;return e.forEach((function(e){var t,r,a=n[e.field]||"";for(t=0,r=a.length;tr&&(t.push({blocks:o,length:n}),o=[],n=0),o.push(e),n+=e.headerLength+e.inputLength})),t.push({blocks:o,length:n}),t.forEach((function(t){var n=new Uint8Array(t.length),r=0;t.blocks.forEach((function(e){n.set(e.header,r),r+=e.headerLength,n.set(e.input,r),r+=e.inputLength})),e.push(n)})),e.push(new Uint8Array(2*i)),new Blob(e,{type:"octet/stream"})},o.prototype.clear=function(){this.written=0,this.out=r.clean(t)},void 0!==e.exports?e.exports=o:window.Tar=o}()},function(e,t,n){void 0!==e.exports&&(e.exports=function(e,t,n){var r,i,o,a=window,s="application/octet-stream",c=n||s,l=e,u=document,h=u.createElement("a"),d=function(e){return String(e)},p=a.Blob||a.MozBlob||a.WebKitBlob||d,f=a.MSBlobBuilder||a.WebKitBlobBuilder||a.BlobBuilder,m=t||"download";if("true"===String(this)&&(c=(l=[l,c])[0],l=l[1]),String(l).match(/^data\\:[\\w+\\-]+\\/[\\w+\\-]+[,;]/))return navigator.msSaveBlob?navigator.msSaveBlob(function(e){var t=e.split(/[:;,]/),n=t[1],r=("base64"==t[2]?atob:decodeURIComponent)(t.pop()),i=r.length,o=0,a=new Uint8Array(i);for(;o0&&this._events[e].length>n&&(this._events[e].warned=!0,console.error("(node) warning: possible EventEmitter memory leak detected. %d listeners added. Use emitter.setMaxListeners() to increase limit.",this._events[e].length),"function"==typeof console.trace&&console.trace()),this},r.prototype.on=r.prototype.addListener,r.prototype.once=function(e,t){if(!i(t))throw TypeError("listener must be a function");var n=!1;function r(){this.removeListener(e,r),n||(n=!0,t.apply(this,arguments))}return r.listener=t,this.on(e,r),this},r.prototype.removeListener=function(e,t){var n,r,a,s;if(!i(t))throw TypeError("listener must be a function");if(!this._events||!this._events[e])return this;if(a=(n=this._events[e]).length,r=-1,n===t||i(n.listener)&&n.listener===t)delete this._events[e],this._events.removeListener&&this.emit("removeListener",e,t);else if(o(n)){for(s=a;s-- >0;)if(n[s]===t||n[s].listener&&n[s].listener===t){r=s;break}if(r<0)return this;1===n.length?(n.length=0,delete this._events[e]):n.splice(r,1),this._events.removeListener&&this.emit("removeListener",e,t)}return this},r.prototype.removeAllListeners=function(e){var t,n;if(!this._events)return this;if(!this._events.removeListener)return 0===arguments.length?this._events={}:this._events[e]&&delete this._events[e],this;if(0===arguments.length){for(t in this._events)"removeListener"!==t&&this.removeAllListeners(t);return this.removeAllListeners("removeListener"),this._events={},this}if(i(n=this._events[e]))this.removeListener(e,n);else if(n)for(;n.length;)this.removeListener(e,n[n.length-1]);return delete this._events[e],this},r.prototype.listeners=function(e){return this._events&&this._events[e]?i(this._events[e])?[this._events[e]]:this._events[e].slice():[]},r.prototype.listenerCount=function(e){if(this._events){var t=this._events[e];if(i(t))return 1;if(t)return t.length}return 0},r.listenerCount=function(e,t){return e.listenerCount(t)}},{}],2:[function(e,t,n){var r=e("./TypedNeuQuant.js"),i=e("./LZWEncoder.js");function o(){this.page=-1,this.pages=[],this.newPage()}o.pageSize=4096,o.charMap={};for(var a=0;a<256;a++)o.charMap[a]=String.fromCharCode(a);function s(e,t){this.width=~~e,this.height=~~t,this.transparent=null,this.transIndex=0,this.repeat=-1,this.delay=0,this.image=null,this.pixels=null,this.indexedPixels=null,this.colorDepth=null,this.colorTab=null,this.neuQuant=null,this.usedEntry=new Array,this.palSize=7,this.dispose=-1,this.firstFrame=!0,this.sample=10,this.dither=!1,this.globalPalette=!1,this.out=new o}o.prototype.newPage=function(){this.pages[++this.page]=new Uint8Array(o.pageSize),this.cursor=0},o.prototype.getData=function(){for(var e="",t=0;t=o.pageSize&&this.newPage(),this.pages[this.page][this.cursor++]=e},o.prototype.writeUTFBytes=function(e){for(var t=e.length,n=0;n=0&&(this.dispose=e)},s.prototype.setRepeat=function(e){this.repeat=e},s.prototype.setTransparent=function(e){this.transparent=e},s.prototype.addFrame=function(e){this.image=e,this.colorTab=this.globalPalette&&this.globalPalette.slice?this.globalPalette:null,this.getImagePixels(),this.analyzePixels(),!0===this.globalPalette&&(this.globalPalette=this.colorTab),this.firstFrame&&(this.writeLSD(),this.writePalette(),this.repeat>=0&&this.writeNetscapeExt()),this.writeGraphicCtrlExt(),this.writeImageDesc(),this.firstFrame||this.globalPalette||this.writePalette(),this.writePixels(),this.firstFrame=!1},s.prototype.finish=function(){this.out.writeByte(59)},s.prototype.setQuality=function(e){e<1&&(e=1),this.sample=e},s.prototype.setDither=function(e){!0===e&&(e="FloydSteinberg"),this.dither=e},s.prototype.setGlobalPalette=function(e){this.globalPalette=e},s.prototype.getGlobalPalette=function(){return this.globalPalette&&this.globalPalette.slice&&this.globalPalette.slice(0)||this.globalPalette},s.prototype.writeHeader=function(){this.out.writeUTFBytes("GIF89a")},s.prototype.analyzePixels=function(){this.colorTab||(this.neuQuant=new r(this.pixels,this.sample),this.neuQuant.buildColormap(),this.colorTab=this.neuQuant.getColormap()),this.dither?this.ditherPixels(this.dither.replace("-serpentine",""),null!==this.dither.match(/-serpentine/)):this.indexPixels(),this.pixels=null,this.colorDepth=8,this.palSize=7,null!==this.transparent&&(this.transIndex=this.findClosest(this.transparent,!0))},s.prototype.indexPixels=function(e){var t=this.pixels.length/3;this.indexedPixels=new Uint8Array(t);for(var n=0,r=0;r=0&&x+u=0&&w+l>16,(65280&e)>>8,255&e,t)},s.prototype.findClosestRGB=function(e,t,n,r){if(null===this.colorTab)return-1;if(this.neuQuant&&!r)return this.neuQuant.lookupRGB(e,t,n);for(var i=0,o=16777216,a=this.colorTab.length,s=0,c=0;s=0&&(t=7&this.dispose),t<<=2,this.out.writeByte(0|t|e),this.writeShort(this.delay),this.out.writeByte(this.transIndex),this.out.writeByte(0)},s.prototype.writeImageDesc=function(){this.out.writeByte(44),this.writeShort(0),this.writeShort(0),this.writeShort(this.width),this.writeShort(this.height),this.firstFrame||this.globalPalette?this.out.writeByte(0):this.out.writeByte(128|this.palSize)},s.prototype.writeLSD=function(){this.writeShort(this.width),this.writeShort(this.height),this.out.writeByte(240|this.palSize),this.out.writeByte(0),this.out.writeByte(0)},s.prototype.writeNetscapeExt=function(){this.out.writeByte(33),this.out.writeByte(255),this.out.writeByte(11),this.out.writeUTFBytes("NETSCAPE2.0"),this.out.writeByte(3),this.out.writeByte(1),this.writeShort(this.repeat),this.out.writeByte(0)},s.prototype.writePalette=function(){this.out.writeBytes(this.colorTab);for(var e=768-this.colorTab.length,t=0;t>8&255)},s.prototype.writePixels=function(){new i(this.width,this.height,this.indexedPixels,this.colorDepth).encode(this.out)},s.prototype.stream=function(){return this.out},t.exports=s},{"./LZWEncoder.js":3,"./TypedNeuQuant.js":4}],3:[function(e,t,n){var r=-1,i=12,o=5003,a=[0,1,3,7,15,31,63,127,255,511,1023,2047,4095,8191,16383,32767,65535];t.exports=function(e,t,n,s){var c,l,u,h,d,p,f=Math.max(2,s),m=new Uint8Array(256),g=new Int32Array(o),v=new Int32Array(o),y=0,b=0,_=!1;function x(e,t){m[l++]=e,l>=254&&E(t)}function w(e){M(o),b=d+2,_=!0,A(d,e)}function M(e){for(var t=0;t0&&(e.writeByte(l),e.writeBytes(m,0,l),l=0)}function T(e){return(1<0?c|=e<=8;)x(255&c,t),c>>=8,y-=8;if((b>u||_)&&(_?(u=T(n_bits=h),_=!1):(++n_bits,u=n_bits==i?1<0;)x(255&c,t),c>>=8,y-=8;E(t)}}this.encode=function(n){n.writeByte(f),remaining=e*t,curPixel=0,function(e,t){var n,a,s,c,f,m,y;for(h=e,_=!1,n_bits=h,u=T(n_bits),p=1+(d=1<=0){f=m-s,0===s&&(f=1);do{if((s-=f)<0&&(s+=m),g[s]===n){c=v[s];continue e}}while(g[s]>=0)}A(c,t),c=a,b<1<>u,d=c<>3)*(1<l;)c=A[p++],hl&&((s=n[d--])[0]-=c*(s[0]-r)/y,s[1]-=c*(s[1]-o)/y,s[2]-=c*(s[2]-a)/y)}function R(e,t,r){var o,c,p,f,m,g=~(1<<31),v=g,y=-1,b=y;for(o=0;o>s-a))>u,S[o]-=m,T[o]+=m<>3),e=0;e>p;for(S<=1&&(S=0),n=0;n=u&&(P-=u),0===y&&(y=1),++n%y==0)for(E-=E/h,(S=(T-=T/m)>>p)<=1&&(S=0),l=0;l>=a,n[e][1]>>=a,n[e][2]>>=a,n[e][3]=e}(),function(){var e,t,r,a,s,c,l=0,u=0;for(e=0;e>1,t=l+1;t>1,t=l+1;t<256;t++)E[t]=o}()},this.getColormap=function(){for(var e=[],t=[],r=0;r=0;)u=c?u=i:(u++,s<0&&(s=-s),(o=a[0]-e)<0&&(o=-o),(s+=o)=0&&((s=t-(a=n[h])[1])>=c?h=-1:(h--,s<0&&(s=-s),(o=a[0]-e)<0&&(o=-o),(s+=o)t;0<=t?++e:--e)n.push(null);return n}.call(this),t=this.spawnWorkers(),!0===this.options.globalPalette)this.renderNextFrame();else for(e=0,n=t;0<=n?en;0<=n?++e:--e)this.renderNextFrame();return this.emit("start"),this.emit("progress",0)},r.prototype.abort=function(){for(var e;null!=(e=this.activeWorkers.shift());)this.log("killing active worker"),e.terminate();return this.running=!1,this.emit("abort")},r.prototype.spawnWorkers=function(){var e,t,n,r;return e=Math.min(this.options.workers,this.frames.length),function(){n=[];for(var r=t=this.freeWorkers.length;t<=e?re;t<=e?r++:r--)n.push(r);return n}.apply(this).forEach((r=this,function(e){var t;return r.log("spawning worker "+e),(t=new Worker(r.options.workerScript)).onmessage=function(e){return r.activeWorkers.splice(r.activeWorkers.indexOf(t),1),r.freeWorkers.push(t),r.frameFinished(e.data)},r.freeWorkers.push(t)})),e},r.prototype.frameFinished=function(e){var t,n;if(this.log("frame "+e.index+" finished - "+this.activeWorkers.length+" active"),this.finishedFrames++,this.emit("progress",this.finishedFrames/this.frames.length),this.imageParts[e.index]=e,!0===this.options.globalPalette&&(this.options.globalPalette=e.globalPalette,this.log("global palette analyzed"),this.frames.length>2))for(t=1,n=this.freeWorkers.length;1<=n?tn;1<=n?++t:--t)this.renderNextFrame();return a.call(this.imageParts,null)>=0?this.renderNextFrame():this.finishRendering()},r.prototype.finishRendering=function(){var e,t,n,r,i,o,a,s,c,l,u,h,d,p,f,m;for(s=0,i=0,c=(p=this.imageParts).length;i=this.frames.length))return e=this.frames[this.nextFrame++],n=this.freeWorkers.shift(),t=this.getTask(e),this.log("starting frame "+(t.index+1)+" of "+this.frames.length),this.activeWorkers.push(n),n.postMessage(t)},r.prototype.getContextData=function(e){return e.getImageData(0,0,this.options.width,this.options.height).data},r.prototype.getImageData=function(e){var t;return null==this._canvas&&(this._canvas=document.createElement("canvas"),this._canvas.width=this.options.width,this._canvas.height=this.options.height),(t=this._canvas.getContext("2d")).setFill=this.options.background,t.fillRect(0,0,this.options.width,this.options.height),t.drawImage(e,0,0),this.getContextData(t)},r.prototype.getTask=function(e){var t,n;if(n={index:t=this.frames.indexOf(e),last:t===this.frames.length-1,delay:e.delay,dispose:e.dispose,transparent:e.transparent,width:this.options.width,height:this.options.height,quality:this.options.quality,dither:this.options.dither,globalPalette:this.options.globalPalette,repeat:this.options.repeat,canTransfer:"chrome"===i.name},null!=e.data)n.data=e.data;else if(null!=e.context)n.data=this.getContextData(e.context);else{if(null==e.image)throw new Error("Invalid frame");n.data=this.getImageData(e.image)}return n},r.prototype.log=function(){var e;if(e=1<=arguments.length?s.call(arguments,0):[],this.options.debug)return console.log.apply(console,e)},r}(r)},{"./GIFEncoder.js":2,"./browser.coffee":5,"./gif.worker.coffee":7,events:1}],7:[function(e,t,n){var r,i;r=e("./GIFEncoder.js"),i=function(e){var t,n,i,o;return t=new r(e.width,e.height),0===e.index?t.writeHeader():t.firstFrame=!1,t.setTransparent(e.transparent),t.setDispose(e.dispose),t.setRepeat(e.repeat),t.setDelay(e.delay),t.setQuality(e.quality),t.setDither(e.dither),t.setGlobalPalette(e.globalPalette),t.addFrame(e.data),e.last&&t.finish(),!0===e.globalPalette&&(e.globalPalette=t.getGlobalPalette()),i=t.stream(),e.data=i.pages,e.cursor=i.cursor,e.pageSize=i.constructor.pageSize,e.canTransfer?(o=function(){var t,r,i,o;for(o=[],t=0,r=(i=e.data).length;t{var __webpack_modules__={583:(e,t,n)=>{var i;e=n.nmd(e),function(){if(void 0!==e.exports)var r=n(617),s=n(549),a=n(468);var o={function:!0,object:!0};function l(e){return e&&e.Object===Object?e:null}parseFloat,parseInt;var c=o[typeof t]&&t&&!t.nodeType?t:void 0,h=o.object&&e&&!e.nodeType?e:void 0,u=(h&&h.exports,l(c&&h&&"object"==typeof n.g&&n.g)),d=l(o[typeof self]&&self),p=l(o[typeof window]&&window),f=l(o[typeof this]&&this);function m(e){return String("0000000"+e).slice(-7)}u||p!==(f&&f.window)&&p||d||f||Function("return this")(),"gc"in window||(window.gc=function(){}),HTMLCanvasElement.prototype.toBlob||Object.defineProperty(HTMLCanvasElement.prototype,"toBlob",{value:function(e,t,n){for(var i=atob(this.toDataURL(t,n).split(",")[1]),r=i.length,s=new Uint8Array(r),a=0;a=c.frameLimit||c.timeLimit&&e>=c.timeLimit)&&(H(),W());var t=new Date(null);t.setSeconds(e),c.motionBlurFrames>2?y.textContent="CCapture "+c.format+" | "+d+" frames ("+p+" inter) | "+t.toISOString().substr(11,8):y.textContent="CCapture "+c.format+" | "+d+" frames | "+t.toISOString().substr(11,8)}(),j("Frame: "+d+" "+p);for(var s=0;s=h[s].triggerTime&&(G(h[s].callback),h.splice(s,1));for(s=0;s=u[s].triggerTime&&(G(u[s].callback),u[s].triggerTime+=u[s].time);f.forEach((function(e){G(e,n-g)})),f=[]}function W(e){e||(e=function(e){return s(e,l.filename+l.extension,l.mimeType),!1}),l.save(e)}function j(e){t&&console.log(e)}return{start:function(){!function(){function e(){return this._hooked||(this._hooked=!0,this._hookedTime=this.currentTime||0,this.pause(),z.push(this)),this._hookedTime+c.startTime}j("Capturer start"),i=window.Date.now(),n=i+c.startTime,a=window.performance.now(),r=a+c.startTime,window.Date.prototype.getTime=function(){return n},window.Date.now=function(){return n},window.setTimeout=function(e,t){var i={callback:e,time:t,triggerTime:n+t};return h.push(i),j("Timeout set to "+i.time),i},window.clearTimeout=function(e){for(var t=0;t2?(function(e){A.width===e.width&&A.height===e.height||(A.width=e.width,A.height=e.height,E=new Uint16Array(A.height*A.width*4),L.fillStyle="#0",L.fillRect(0,0,A.width,A.height))}(e),function(e){L.drawImage(e,0,0),S=L.getImageData(0,0,A.width,A.height);for(var t=0;t=.5*c.motionBlurFrames?function(){for(var e=S.data,t=0;t0&&this.frames.length/this.settings.framerate>=this.settings.autoSaveTime?this.save(function(e){this.filename=this.baseFilename+"-part-"+m(this.part),s(e,this.filename+this.extension,this.mimeType),this.dispose(),this.part++,this.filename=this.baseFilename+"-part-"+m(this.part),this.step()}.bind(this)):this.step()},b.prototype.save=function(e){this.videoWriter.complete().then(e)},b.prototype.dispose=function(e){this.frames=[]},w.prototype=Object.create(v.prototype),w.prototype.start=function(){this.encoder.start(this.settings)},w.prototype.add=function(e){this.encoder.add(e)},w.prototype.save=function(e){this.callback=e,this.encoder.end()},w.prototype.safeToProceed=function(){return this.encoder.safeToProceed()},M.prototype=Object.create(v.prototype),M.prototype.add=function(e){this.stream||(this.stream=e.captureStream(this.framerate),this.mediaRecorder=new MediaRecorder(this.stream),this.mediaRecorder.start(),this.mediaRecorder.ondataavailable=function(e){this.chunks.push(e.data)}.bind(this)),this.step()},M.prototype.save=function(e){this.mediaRecorder.onstop=function(t){var n=new Blob(this.chunks,{type:"video/webm"});this.chunks=[],e(n)}.bind(this),this.mediaRecorder.stop()},T.prototype=Object.create(v.prototype),T.prototype.add=function(e){this.sizeSet||(this.encoder.setOption("width",e.width),this.encoder.setOption("height",e.height),this.sizeSet=!0),this.canvas.width=e.width,this.canvas.height=e.height,this.ctx.drawImage(e,0,0),this.encoder.addFrame(this.ctx,{copy:!0,delay:this.settings.step}),this.step()},T.prototype.save=function(e){this.callback=e,this.encoder.render()},(p||d||{}).CCapture=E,void 0===(i=function(){return E}.call(t,n,t,e))||(e.exports=i)}()},549:e=>{void 0!==e.exports&&(e.exports=function(e,t,n){var i,r,s,a=window,o="application/octet-stream",l=n||o,c=e,h=document,u=h.createElement("a"),d=function(e){return String(e)},p=a.Blob||a.MozBlob||a.WebKitBlob||d,f=a.MSBlobBuilder||a.WebKitBlobBuilder||a.BlobBuilder,m=t||"download";if("true"===String(this)&&(l=(c=[c,l])[0],c=c[1]),String(c).match(/^data\\:[\\w+\\-]+\\/[\\w+\\-]+[,;]/))return navigator.msSaveBlob?navigator.msSaveBlob(function(e){for(var t=e.split(/[:;,]/),n=t[1],i=("base64"==t[2]?atob:decodeURIComponent)(t.pop()),r=i.length,s=0,a=new Uint8Array(r);s{e.exports=function e(t,n,i){function r(a,o){if(!n[a]){if(!t[a]){if(s)return s(a,!0);var l=new Error("Cannot find module '"+a+"'");throw l.code="MODULE_NOT_FOUND",l}var c=n[a]={exports:{}};t[a][0].call(c.exports,(function(e){return r(t[a][1][e]||e)}),c,c.exports,e,t,n,i)}return n[a].exports}for(var s=void 0,a=0;a0&&this._events[e].length>n&&(this._events[e].warned=!0,console.error("(node) warning: possible EventEmitter memory leak detected. %d listeners added. Use emitter.setMaxListeners() to increase limit.",this._events[e].length),"function"==typeof console.trace&&console.trace()),this},i.prototype.on=i.prototype.addListener,i.prototype.once=function(e,t){if(!r(t))throw TypeError("listener must be a function");var n=!1;function i(){this.removeListener(e,i),n||(n=!0,t.apply(this,arguments))}return i.listener=t,this.on(e,i),this},i.prototype.removeListener=function(e,t){var n,i,a,o;if(!r(t))throw TypeError("listener must be a function");if(!this._events||!this._events[e])return this;if(a=(n=this._events[e]).length,i=-1,n===t||r(n.listener)&&n.listener===t)delete this._events[e],this._events.removeListener&&this.emit("removeListener",e,t);else if(s(n)){for(o=a;o-- >0;)if(n[o]===t||n[o].listener&&n[o].listener===t){i=o;break}if(i<0)return this;1===n.length?(n.length=0,delete this._events[e]):n.splice(i,1),this._events.removeListener&&this.emit("removeListener",e,t)}return this},i.prototype.removeAllListeners=function(e){var t,n;if(!this._events)return this;if(!this._events.removeListener)return 0===arguments.length?this._events={}:this._events[e]&&delete this._events[e],this;if(0===arguments.length){for(t in this._events)"removeListener"!==t&&this.removeAllListeners(t);return this.removeAllListeners("removeListener"),this._events={},this}if(r(n=this._events[e]))this.removeListener(e,n);else if(n)for(;n.length;)this.removeListener(e,n[n.length-1]);return delete this._events[e],this},i.prototype.listeners=function(e){return this._events&&this._events[e]?r(this._events[e])?[this._events[e]]:this._events[e].slice():[]},i.prototype.listenerCount=function(e){if(this._events){var t=this._events[e];if(r(t))return 1;if(t)return t.length}return 0},i.listenerCount=function(e,t){return e.listenerCount(t)}},{}],2:[function(e,t,n){var i=e("./TypedNeuQuant.js"),r=e("./LZWEncoder.js");function s(){this.page=-1,this.pages=[],this.newPage()}s.pageSize=4096,s.charMap={};for(var a=0;a<256;a++)s.charMap[a]=String.fromCharCode(a);function o(e,t){this.width=~~e,this.height=~~t,this.transparent=null,this.transIndex=0,this.repeat=-1,this.delay=0,this.image=null,this.pixels=null,this.indexedPixels=null,this.colorDepth=null,this.colorTab=null,this.neuQuant=null,this.usedEntry=new Array,this.palSize=7,this.dispose=-1,this.firstFrame=!0,this.sample=10,this.dither=!1,this.globalPalette=!1,this.out=new s}s.prototype.newPage=function(){this.pages[++this.page]=new Uint8Array(s.pageSize),this.cursor=0},s.prototype.getData=function(){for(var e="",t=0;t=s.pageSize&&this.newPage(),this.pages[this.page][this.cursor++]=e},s.prototype.writeUTFBytes=function(e){for(var t=e.length,n=0;n=0&&(this.dispose=e)},o.prototype.setRepeat=function(e){this.repeat=e},o.prototype.setTransparent=function(e){this.transparent=e},o.prototype.addFrame=function(e){this.image=e,this.colorTab=this.globalPalette&&this.globalPalette.slice?this.globalPalette:null,this.getImagePixels(),this.analyzePixels(),!0===this.globalPalette&&(this.globalPalette=this.colorTab),this.firstFrame&&(this.writeLSD(),this.writePalette(),this.repeat>=0&&this.writeNetscapeExt()),this.writeGraphicCtrlExt(),this.writeImageDesc(),this.firstFrame||this.globalPalette||this.writePalette(),this.writePixels(),this.firstFrame=!1},o.prototype.finish=function(){this.out.writeByte(59)},o.prototype.setQuality=function(e){e<1&&(e=1),this.sample=e},o.prototype.setDither=function(e){!0===e&&(e="FloydSteinberg"),this.dither=e},o.prototype.setGlobalPalette=function(e){this.globalPalette=e},o.prototype.getGlobalPalette=function(){return this.globalPalette&&this.globalPalette.slice&&this.globalPalette.slice(0)||this.globalPalette},o.prototype.writeHeader=function(){this.out.writeUTFBytes("GIF89a")},o.prototype.analyzePixels=function(){this.colorTab||(this.neuQuant=new i(this.pixels,this.sample),this.neuQuant.buildColormap(),this.colorTab=this.neuQuant.getColormap()),this.dither?this.ditherPixels(this.dither.replace("-serpentine",""),null!==this.dither.match(/-serpentine/)):this.indexPixels(),this.pixels=null,this.colorDepth=8,this.palSize=7,null!==this.transparent&&(this.transIndex=this.findClosest(this.transparent,!0))},o.prototype.indexPixels=function(e){var t=this.pixels.length/3;this.indexedPixels=new Uint8Array(t);for(var n=0,i=0;i=0&&b+h=0&&w+c>16,(65280&e)>>8,255&e,t)},o.prototype.findClosestRGB=function(e,t,n,i){if(null===this.colorTab)return-1;if(this.neuQuant&&!i)return this.neuQuant.lookupRGB(e,t,n);for(var r=0,s=16777216,a=this.colorTab.length,o=0,l=0;o=0&&(t=7&this.dispose),t<<=2,this.out.writeByte(0|t|e),this.writeShort(this.delay),this.out.writeByte(this.transIndex),this.out.writeByte(0)},o.prototype.writeImageDesc=function(){this.out.writeByte(44),this.writeShort(0),this.writeShort(0),this.writeShort(this.width),this.writeShort(this.height),this.firstFrame||this.globalPalette?this.out.writeByte(0):this.out.writeByte(128|this.palSize)},o.prototype.writeLSD=function(){this.writeShort(this.width),this.writeShort(this.height),this.out.writeByte(240|this.palSize),this.out.writeByte(0),this.out.writeByte(0)},o.prototype.writeNetscapeExt=function(){this.out.writeByte(33),this.out.writeByte(255),this.out.writeByte(11),this.out.writeUTFBytes("NETSCAPE2.0"),this.out.writeByte(3),this.out.writeByte(1),this.writeShort(this.repeat),this.out.writeByte(0)},o.prototype.writePalette=function(){this.out.writeBytes(this.colorTab);for(var e=768-this.colorTab.length,t=0;t>8&255)},o.prototype.writePixels=function(){new r(this.width,this.height,this.indexedPixels,this.colorDepth).encode(this.out)},o.prototype.stream=function(){return this.out},t.exports=o},{"./LZWEncoder.js":3,"./TypedNeuQuant.js":4}],3:[function(e,t,n){var i=5003,r=[0,1,3,7,15,31,63,127,255,511,1023,2047,4095,8191,16383,32767,65535];t.exports=function(e,t,n,s){var a,o,l,c,h,u,d=Math.max(2,s),p=new Uint8Array(256),f=new Int32Array(i),m=new Int32Array(i),g=0,v=0,y=!1;function _(e,t){p[o++]=e,o>=254&&w(t)}function x(e){b(i),v=h+2,y=!0,E(h,e)}function b(e){for(var t=0;t0&&(e.writeByte(o),e.writeBytes(p,0,o),o=0)}function M(e){return(1<0?a|=e<=8;)_(255&a,t),a>>=8,g-=8;if((v>l||y)&&(y?(l=M(n_bits=c),y=!1):(++n_bits,l=12==n_bits?4096:M(n_bits))),e==u){for(;g>0;)_(255&a,t),a>>=8,g-=8;w(t)}}this.encode=function(n){n.writeByte(d),remaining=e*t,curPixel=0,function(e,t){var n,r,s,a,d,p;for(c=e,y=!1,n_bits=c,l=M(n_bits),u=1+(h=1<=0){d=5003-s,0===s&&(d=1);do{if((s-=d)<0&&(s+=5003),f[s]===n){a=m[s];continue e}}while(f[s]>=0)}E(a,t),a=r,v<4096?(m[s]=v++,f[s]=n):x(t)}else a=m[s];E(a,t),E(u,t)}(d+1,n),n.writeByte(0)}}},{}],4:[function(e,t,n){var i=256,r=1024,s=1<<18;t.exports=function(e,t){var n,a,o,l,c;function h(e,t,i,s,a){n[t][0]-=e*(n[t][0]-i)/r,n[t][1]-=e*(n[t][1]-s)/r,n[t][2]-=e*(n[t][2]-a)/r}function u(e,t,r,a,o){for(var l,h,u=Math.abs(t-e),d=Math.min(t+e,i),p=t+1,f=t-1,m=1;pu;)h=c[m++],pu&&((l=n[f--])[0]-=h*(l[0]-r)/s,l[1]-=h*(l[1]-a)/s,l[2]-=h*(l[2]-o)/s)}function d(e,t,r){var s,a,c,h,u,d=~(1<<31),p=d,f=-1,m=f;for(s=0;s>12))>10,l[s]-=u,o[s]+=u<<10;return l[f]+=64,o[f]-=65536,m}this.buildColormap=function(){(function(){var e,t;for(n=[],a=new Int32Array(256),o=new Int32Array(i),l=new Int32Array(i),c=new Int32Array(32),e=0;e>6;for(_<=1&&(_=0),n=0;n<_;n++)c[n]=v*(256*(_*_-n*n)/(_*_));p<1509?(t=1,i=3):i=p%499!=0?1497:p%491!=0?1473:p%487!=0?1461:1509;var x=0;for(n=0;n=p&&(x-=p),0===g&&(g=1),++n%g==0)for(v-=v/f,(_=(y-=y/30)>>6)<=1&&(_=0),l=0;l<_;l++)c[l]=v*(256*(_*_-l*l)/(_*_))}(),function(){for(var e=0;e>=4,n[e][1]>>=4,n[e][2]>>=4,n[e][3]=e}(),function(){var e,t,r,s,o,l,c=0,h=0;for(e=0;e>1,t=c+1;t>1,t=c+1;t<256;t++)a[t]=255}()},this.getColormap=function(){for(var e=[],t=[],r=0;r=0;)u=c?u=i:(u++,l<0&&(l=-l),(s=o[0]-e)<0&&(s=-s),(l+=s)=0&&((l=t-(o=n[d])[1])>=c?d=-1:(d--,l<0&&(l=-l),(s=o[0]-e)<0&&(s=-s),(l+=s)t;0<=t?++e:--e)n.push(null);return n}.call(this),t=this.spawnWorkers(),!0===this.options.globalPalette)this.renderNextFrame();else for(e=0,n=t;0<=n?en;0<=n?++e:--e)this.renderNextFrame();return this.emit("start"),this.emit("progress",0)},i.prototype.abort=function(){for(var e;null!=(e=this.activeWorkers.shift());)this.log("killing active worker"),e.terminate();return this.running=!1,this.emit("abort")},i.prototype.spawnWorkers=function(){var e,t,n,i;return e=Math.min(this.options.workers,this.frames.length),function(){n=[];for(var i=t=this.freeWorkers.length;t<=e?ie;t<=e?i++:i--)n.push(i);return n}.apply(this).forEach((i=this,function(e){var t;return i.log("spawning worker "+e),(t=new Worker(i.options.workerScript)).onmessage=function(e){return i.activeWorkers.splice(i.activeWorkers.indexOf(t),1),i.freeWorkers.push(t),i.frameFinished(e.data)},i.freeWorkers.push(t)})),e},i.prototype.frameFinished=function(e){var t,n;if(this.log("frame "+e.index+" finished - "+this.activeWorkers.length+" active"),this.finishedFrames++,this.emit("progress",this.finishedFrames/this.frames.length),this.imageParts[e.index]=e,!0===this.options.globalPalette&&(this.options.globalPalette=e.globalPalette,this.log("global palette analyzed"),this.frames.length>2))for(t=1,n=this.freeWorkers.length;1<=n?tn;1<=n?++t:--t)this.renderNextFrame();return a.call(this.imageParts,null)>=0?this.renderNextFrame():this.finishRendering()},i.prototype.finishRendering=function(){var e,t,n,i,r,s,a,o,l,c,h,u,d,p,f,m;for(o=0,r=0,l=(p=this.imageParts).length;r=this.frames.length))return e=this.frames[this.nextFrame++],n=this.freeWorkers.shift(),t=this.getTask(e),this.log("starting frame "+(t.index+1)+" of "+this.frames.length),this.activeWorkers.push(n),n.postMessage(t)},i.prototype.getContextData=function(e){return e.getImageData(0,0,this.options.width,this.options.height).data},i.prototype.getImageData=function(e){var t;return null==this._canvas&&(this._canvas=document.createElement("canvas"),this._canvas.width=this.options.width,this._canvas.height=this.options.height),(t=this._canvas.getContext("2d")).setFill=this.options.background,t.fillRect(0,0,this.options.width,this.options.height),t.drawImage(e,0,0),this.getContextData(t)},i.prototype.getTask=function(e){var t,n;if(n={index:t=this.frames.indexOf(e),last:t===this.frames.length-1,delay:e.delay,dispose:e.dispose,transparent:e.transparent,width:this.options.width,height:this.options.height,quality:this.options.quality,dither:this.options.dither,globalPalette:this.options.globalPalette,repeat:this.options.repeat,canTransfer:"chrome"===r.name},null!=e.data)n.data=e.data;else if(null!=e.context)n.data=this.getContextData(e.context);else{if(null==e.image)throw new Error("Invalid frame");n.data=this.getImageData(e.image)}return n},i.prototype.log=function(){var e;if(e=1<=arguments.length?o.call(arguments,0):[],this.options.debug)return console.log.apply(console,e)},i}(i)},{"./GIFEncoder.js":2,"./browser.coffee":5,"./gif.worker.coffee":7,events:1}],7:[function(e,t,n){var i,r;i=e("./GIFEncoder.js"),r=function(e){var t,n,r,s;return t=new i(e.width,e.height),0===e.index?t.writeHeader():t.firstFrame=!1,t.setTransparent(e.transparent),t.setDispose(e.dispose),t.setRepeat(e.repeat),t.setDelay(e.delay),t.setQuality(e.quality),t.setDither(e.dither),t.setGlobalPalette(e.globalPalette),t.addFrame(e.data),e.last&&t.finish(),!0===e.globalPalette&&(e.globalPalette=t.getGlobalPalette()),r=t.stream(),e.data=r.pages,e.cursor=r.cursor,e.pageSize=r.constructor.pageSize,e.canTransfer?(s=function(){var t,i,r,s;for(s=[],t=0,i=(r=e.data).length;t{!function(){"use strict";var e=["A","B","C","D","E","F","G","H","I","J","K","L","M","N","O","P","Q","R","S","T","U","V","W","X","Y","Z","a","b","c","d","e","f","g","h","i","j","k","l","m","n","o","p","q","r","s","t","u","v","w","x","y","z","0","1","2","3","4","5","6","7","8","9","+","/"];function t(e){var t,n=new Uint8Array(e);for(t=0;t>18&63]+e[s>>12&63]+e[s>>6&63]+e[63&s];switch(o.length%4){case 1:o+="=";break;case 2:o+="=="}return o}}(),function(){"use strict";var e,t=window.utils;e=[{field:"fileName",length:100},{field:"fileMode",length:8},{field:"uid",length:8},{field:"gid",length:8},{field:"fileSize",length:12},{field:"mtime",length:12},{field:"checksum",length:8},{field:"type",length:1},{field:"linkName",length:100},{field:"ustar",length:8},{field:"owner",length:32},{field:"group",length:32},{field:"majorNumber",length:8},{field:"minorNumber",length:8},{field:"filenamePrefix",length:155},{field:"padding",length:12}],window.header={},window.header.structure=e,window.header.format=function(n,i){var r=t.clean(512),s=0;return e.forEach((function(e){var t,i,a=n[e.field]||"";for(t=0,i=a.length;ti&&(t.push({blocks:r,length:n}),r=[],n=0),r.push(e),n+=e.headerLength+e.inputLength})),t.push({blocks:r,length:n}),t.forEach((function(t){var n=new Uint8Array(t.length),i=0;t.blocks.forEach((function(e){n.set(e.header,i),i+=e.headerLength,n.set(e.input,i),i+=e.inputLength})),e.push(n)})),e.push(new Uint8Array(1024)),new Blob(e,{type:"octet/stream"})},s.prototype.clear=function(){this.written=0,this.out=i.clean(t)},void 0!==e.exports?e.exports=s:window.Tar=s}()},376:(e,t,n)=>{"use strict";function i(e,t){var n=e.__state.conversionName.toString(),i=Math.round(e.r),r=Math.round(e.g),s=Math.round(e.b),a=e.a,o=Math.round(e.h),l=e.s.toFixed(1),c=e.v.toFixed(1);if(t||"THREE_CHAR_HEX"===n||"SIX_CHAR_HEX"===n){for(var h=e.hex.toString(16);h.length<6;)h="0"+h;return"#"+h}return"CSS_RGB"===n?"rgb("+i+","+r+","+s+")":"CSS_RGBA"===n?"rgba("+i+","+r+","+s+","+a+")":"HEX"===n?"0x"+e.hex.toString(16):"RGB_ARRAY"===n?"["+i+","+r+","+s+"]":"RGBA_ARRAY"===n?"["+i+","+r+","+s+","+a+"]":"RGB_OBJ"===n?"{r:"+i+",g:"+r+",b:"+s+"}":"RGBA_OBJ"===n?"{r:"+i+",g:"+r+",b:"+s+",a:"+a+"}":"HSV_OBJ"===n?"{h:"+o+",s:"+l+",v:"+c+"}":"HSVA_OBJ"===n?"{h:"+o+",s:"+l+",v:"+c+",a:"+a+"}":"unknown format"}n.d(t,{ZP:()=>he});var r=Array.prototype.forEach,s=Array.prototype.slice,a={BREAK:{},extend:function(e){return this.each(s.call(arguments,1),(function(t){(this.isObject(t)?Object.keys(t):[]).forEach(function(n){this.isUndefined(t[n])||(e[n]=t[n])}.bind(this))}),this),e},defaults:function(e){return this.each(s.call(arguments,1),(function(t){(this.isObject(t)?Object.keys(t):[]).forEach(function(n){this.isUndefined(e[n])&&(e[n]=t[n])}.bind(this))}),this),e},compose:function(){var e=s.call(arguments);return function(){for(var t=s.call(arguments),n=e.length-1;n>=0;n--)t=[e[n].apply(this,t)];return t[0]}},each:function(e,t,n){if(e)if(r&&e.forEach&&e.forEach===r)e.forEach(t,n);else if(e.length===e.length+0){var i,s=void 0;for(s=0,i=e.length;s1?a.toArray(arguments):arguments[0];return a.each(o,(function(t){if(t.litmus(e))return a.each(t.conversions,(function(t,n){if(l=t.read(e),!1===c&&!1!==l)return c=l,l.conversionName=n,l.conversion=t,a.BREAK})),a.BREAK})),c},u=void 0,d={hsv_to_rgb:function(e,t,n){var i=Math.floor(e/60)%6,r=e/60-Math.floor(e/60),s=n*(1-t),a=n*(1-r*t),o=n*(1-(1-r)*t),l=[[n,o,s],[a,n,s],[s,n,o],[s,a,n],[o,s,n],[n,s,a]][i];return{r:255*l[0],g:255*l[1],b:255*l[2]}},rgb_to_hsv:function(e,t,n){var i=Math.min(e,t,n),r=Math.max(e,t,n),s=r-i,a=void 0;return 0===r?{h:NaN,s:0,v:0}:(a=e===r?(t-n)/s:t===r?2+(n-e)/s:4+(e-t)/s,(a/=6)<0&&(a+=1),{h:360*a,s:s/r,v:r/255})},rgb_to_hex:function(e,t,n){var i=this.hex_with_component(0,2,e);return i=this.hex_with_component(i,1,t),this.hex_with_component(i,0,n)},component_from_hex:function(e,t){return e>>8*t&255},hex_with_component:function(e,t,n){return n<<(u=8*t)|e&~(255<-1?t.length-t.indexOf(".")-1:0}var P=function(e){function t(e,n,i){f(this,t);var r=y(this,(t.__proto__||Object.getPrototypeOf(t)).call(this,e,n)),s=i||{};return r.__min=s.min,r.__max=s.max,r.__step=s.step,a.isUndefined(r.__step)?0===r.initialValue?r.__impliedStep=1:r.__impliedStep=Math.pow(10,Math.floor(Math.log(Math.abs(r.initialValue))/Math.LN10))/10:r.__impliedStep=r.__step,r.__precision=R(r.__impliedStep),r}return v(t,e),m(t,[{key:"setValue",value:function(e){var n=e;return void 0!==this.__min&&nthis.__max&&(n=this.__max),void 0!==this.__step&&n%this.__step!=0&&(n=Math.round(n/this.__step)*this.__step),g(t.prototype.__proto__||Object.getPrototypeOf(t.prototype),"setValue",this).call(this,n)}},{key:"min",value:function(e){return this.__min=e,this}},{key:"max",value:function(e){return this.__max=e,this}},{key:"step",value:function(e){return this.__step=e,this.__impliedStep=e,this.__precision=R(e),this}}]),t}(w),k=function(e){function t(e,n,i){f(this,t);var r=y(this,(t.__proto__||Object.getPrototypeOf(t)).call(this,e,n,i));r.__truncationSuspended=!1;var s=r,o=void 0;function l(){s.__onFinishChange&&s.__onFinishChange.call(s,s.getValue())}function c(e){var t=o-e.clientY;s.setValue(s.getValue()+t*s.__impliedStep),o=e.clientY}function h(){S.unbind(window,"mousemove",c),S.unbind(window,"mouseup",h),l()}return r.__input=document.createElement("input"),r.__input.setAttribute("type","text"),S.bind(r.__input,"change",(function(){var e=parseFloat(s.__input.value);a.isNaN(e)||s.setValue(e)})),S.bind(r.__input,"blur",(function(){l()})),S.bind(r.__input,"mousedown",(function(e){S.bind(window,"mousemove",c),S.bind(window,"mouseup",h),o=e.clientY})),S.bind(r.__input,"keydown",(function(e){13===e.keyCode&&(s.__truncationSuspended=!0,this.blur(),s.__truncationSuspended=!1,l())})),r.updateDisplay(),r.domElement.appendChild(r.__input),r}return v(t,e),m(t,[{key:"updateDisplay",value:function(){var e,n,i;return this.__input.value=this.__truncationSuspended?this.getValue():(e=this.getValue(),n=this.__precision,i=Math.pow(10,n),Math.round(e*i)/i),g(t.prototype.__proto__||Object.getPrototypeOf(t.prototype),"updateDisplay",this).call(this)}}]),t}(P);function N(e,t,n,i,r){return i+(e-t)/(n-t)*(r-i)}var I=function(e){function t(e,n,i,r,s){f(this,t);var a=y(this,(t.__proto__||Object.getPrototypeOf(t)).call(this,e,n,{min:i,max:r,step:s})),o=a;function l(e){e.preventDefault();var t=o.__background.getBoundingClientRect();return o.setValue(N(e.clientX,t.left,t.right,o.__min,o.__max)),!1}function c(){S.unbind(window,"mousemove",l),S.unbind(window,"mouseup",c),o.__onFinishChange&&o.__onFinishChange.call(o,o.getValue())}function h(e){var t=e.touches[0].clientX,n=o.__background.getBoundingClientRect();o.setValue(N(t,n.left,n.right,o.__min,o.__max))}function u(){S.unbind(window,"touchmove",h),S.unbind(window,"touchend",u),o.__onFinishChange&&o.__onFinishChange.call(o,o.getValue())}return a.__background=document.createElement("div"),a.__foreground=document.createElement("div"),S.bind(a.__background,"mousedown",(function(e){document.activeElement.blur(),S.bind(window,"mousemove",l),S.bind(window,"mouseup",c),l(e)})),S.bind(a.__background,"touchstart",(function(e){1===e.touches.length&&(S.bind(window,"touchmove",h),S.bind(window,"touchend",u),h(e))})),S.addClass(a.__background,"slider"),S.addClass(a.__foreground,"slider-fg"),a.updateDisplay(),a.__background.appendChild(a.__foreground),a.domElement.appendChild(a.__background),a}return v(t,e),m(t,[{key:"updateDisplay",value:function(){var e=(this.getValue()-this.__min)/(this.__max-this.__min);return this.__foreground.style.width=100*e+"%",g(t.prototype.__proto__||Object.getPrototypeOf(t.prototype),"updateDisplay",this).call(this)}}]),t}(P),D=function(e){function t(e,n,i){f(this,t);var r=y(this,(t.__proto__||Object.getPrototypeOf(t)).call(this,e,n)),s=r;return r.__button=document.createElement("div"),r.__button.innerHTML=void 0===i?"Fire":i,S.bind(r.__button,"click",(function(e){return e.preventDefault(),s.fire(),!1})),S.addClass(r.__button,"button"),r.domElement.appendChild(r.__button),r}return v(t,e),m(t,[{key:"fire",value:function(){this.__onChange&&this.__onChange.call(this),this.getValue().call(this.object),this.__onFinishChange&&this.__onFinishChange.call(this,this.getValue())}}]),t}(w),O=function(e){function t(e,n){f(this,t);var i=y(this,(t.__proto__||Object.getPrototypeOf(t)).call(this,e,n));i.__color=new _(i.getValue()),i.__temp=new _(0);var r=i;i.domElement=document.createElement("div"),S.makeSelectable(i.domElement,!1),i.__selector=document.createElement("div"),i.__selector.className="selector",i.__saturation_field=document.createElement("div"),i.__saturation_field.className="saturation-field",i.__field_knob=document.createElement("div"),i.__field_knob.className="field-knob",i.__field_knob_border="2px solid ",i.__hue_knob=document.createElement("div"),i.__hue_knob.className="hue-knob",i.__hue_field=document.createElement("div"),i.__hue_field.className="hue-field",i.__input=document.createElement("input"),i.__input.type="text",i.__input_textShadow="0 1px 1px ",S.bind(i.__input,"keydown",(function(e){13===e.keyCode&&p.call(this)})),S.bind(i.__input,"blur",p),S.bind(i.__selector,"mousedown",(function(){S.addClass(this,"drag").bind(window,"mouseup",(function(){S.removeClass(r.__selector,"drag")}))})),S.bind(i.__selector,"touchstart",(function(){S.addClass(this,"drag").bind(window,"touchend",(function(){S.removeClass(r.__selector,"drag")}))}));var s,o=document.createElement("div");function l(e){g(e),S.bind(window,"mousemove",g),S.bind(window,"touchmove",g),S.bind(window,"mouseup",u),S.bind(window,"touchend",u)}function c(e){v(e),S.bind(window,"mousemove",v),S.bind(window,"touchmove",v),S.bind(window,"mouseup",d),S.bind(window,"touchend",d)}function u(){S.unbind(window,"mousemove",g),S.unbind(window,"touchmove",g),S.unbind(window,"mouseup",u),S.unbind(window,"touchend",u),m()}function d(){S.unbind(window,"mousemove",v),S.unbind(window,"touchmove",v),S.unbind(window,"mouseup",d),S.unbind(window,"touchend",d),m()}function p(){var e=h(this.value);!1!==e?(r.__color.__state=e,r.setValue(r.__color.toOriginal())):this.value=r.__color.toString()}function m(){r.__onFinishChange&&r.__onFinishChange.call(r,r.__color.toOriginal())}function g(e){-1===e.type.indexOf("touch")&&e.preventDefault();var t=r.__saturation_field.getBoundingClientRect(),n=e.touches&&e.touches[0]||e,i=n.clientX,s=n.clientY,a=(i-t.left)/(t.right-t.left),o=1-(s-t.top)/(t.bottom-t.top);return o>1?o=1:o<0&&(o=0),a>1?a=1:a<0&&(a=0),r.__color.v=o,r.__color.s=a,r.setValue(r.__color.toOriginal()),!1}function v(e){-1===e.type.indexOf("touch")&&e.preventDefault();var t=r.__hue_field.getBoundingClientRect(),n=1-((e.touches&&e.touches[0]||e).clientY-t.top)/(t.bottom-t.top);return n>1?n=1:n<0&&(n=0),r.__color.h=360*n,r.setValue(r.__color.toOriginal()),!1}return a.extend(i.__selector.style,{width:"122px",height:"102px",padding:"3px",backgroundColor:"#222",boxShadow:"0px 1px 3px rgba(0,0,0,0.3)"}),a.extend(i.__field_knob.style,{position:"absolute",width:"12px",height:"12px",border:i.__field_knob_border+(i.__color.v<.5?"#fff":"#000"),boxShadow:"0px 1px 3px rgba(0,0,0,0.5)",borderRadius:"12px",zIndex:1}),a.extend(i.__hue_knob.style,{position:"absolute",width:"15px",height:"2px",borderRight:"4px solid #fff",zIndex:1}),a.extend(i.__saturation_field.style,{width:"100px",height:"100px",border:"1px solid #555",marginRight:"3px",display:"inline-block",cursor:"pointer"}),a.extend(o.style,{width:"100%",height:"100%",background:"none"}),F(o,"top","rgba(0,0,0,0)","#000"),a.extend(i.__hue_field.style,{width:"15px",height:"100px",border:"1px solid #555",cursor:"ns-resize",position:"absolute",top:"3px",right:"3px"}),(s=i.__hue_field).style.background="",s.style.cssText+="background: -moz-linear-gradient(top, #ff0000 0%, #ff00ff 17%, #0000ff 34%, #00ffff 50%, #00ff00 67%, #ffff00 84%, #ff0000 100%);",s.style.cssText+="background: -webkit-linear-gradient(top, #ff0000 0%,#ff00ff 17%,#0000ff 34%,#00ffff 50%,#00ff00 67%,#ffff00 84%,#ff0000 100%);",s.style.cssText+="background: -o-linear-gradient(top, #ff0000 0%,#ff00ff 17%,#0000ff 34%,#00ffff 50%,#00ff00 67%,#ffff00 84%,#ff0000 100%);",s.style.cssText+="background: -ms-linear-gradient(top, #ff0000 0%,#ff00ff 17%,#0000ff 34%,#00ffff 50%,#00ff00 67%,#ffff00 84%,#ff0000 100%);",s.style.cssText+="background: linear-gradient(top, #ff0000 0%,#ff00ff 17%,#0000ff 34%,#00ffff 50%,#00ff00 67%,#ffff00 84%,#ff0000 100%);",a.extend(i.__input.style,{outline:"none",textAlign:"center",color:"#fff",border:0,fontWeight:"bold",textShadow:i.__input_textShadow+"rgba(0,0,0,0.7)"}),S.bind(i.__saturation_field,"mousedown",l),S.bind(i.__saturation_field,"touchstart",l),S.bind(i.__field_knob,"mousedown",l),S.bind(i.__field_knob,"touchstart",l),S.bind(i.__hue_field,"mousedown",c),S.bind(i.__hue_field,"touchstart",c),i.__saturation_field.appendChild(o),i.__selector.appendChild(i.__field_knob),i.__selector.appendChild(i.__saturation_field),i.__selector.appendChild(i.__hue_field),i.__hue_field.appendChild(i.__hue_knob),i.domElement.appendChild(i.__input),i.domElement.appendChild(i.__selector),i.updateDisplay(),i}return v(t,e),m(t,[{key:"updateDisplay",value:function(){var e=h(this.getValue());if(!1!==e){var t=!1;a.each(_.COMPONENTS,(function(n){if(!a.isUndefined(e[n])&&!a.isUndefined(this.__color.__state[n])&&e[n]!==this.__color.__state[n])return t=!0,{}}),this),t&&a.extend(this.__color.__state,e)}a.extend(this.__temp.__state,this.__color.__state),this.__temp.a=1;var n=this.__color.v<.5||this.__color.s>.5?255:0,i=255-n;a.extend(this.__field_knob.style,{marginLeft:100*this.__color.s-7+"px",marginTop:100*(1-this.__color.v)-7+"px",backgroundColor:this.__temp.toHexString(),border:this.__field_knob_border+"rgb("+n+","+n+","+n+")"}),this.__hue_knob.style.marginTop=100*(1-this.__color.h/360)+"px",this.__temp.s=1,this.__temp.v=1,F(this.__saturation_field,"left","#fff",this.__temp.toHexString()),this.__input.value=this.__color.toString(),a.extend(this.__input.style,{backgroundColor:this.__color.toHexString(),color:"rgb("+n+","+n+","+n+")",textShadow:this.__input_textShadow+"rgba("+i+","+i+","+i+",.7)"})}}]),t}(w),B=["-moz-","-o-","-webkit-","-ms-",""];function F(e,t,n,i){e.style.background="",a.each(B,(function(r){e.style.cssText+="background: "+r+"linear-gradient("+t+", "+n+" 0%, "+i+" 100%); "}))}var U='
\\n\\n Here\\'s the new load parameter for your GUI\\'s constructor:\\n\\n \\n\\n
\\n\\n Automatically save\\n values to localStorage on exit.\\n\\n
The values saved to localStorage will\\n override those passed to dat.GUI\\'s constructor. This makes it\\n easier to work incrementally, but localStorage is fragile,\\n and your friends may not see the same values you do.\\n\\n
\\n\\n
\\n\\n
',z=function(e,t){var n=e[t];return a.isArray(arguments[2])||a.isObject(arguments[2])?new L(e,t,arguments[2]):a.isNumber(n)?a.isNumber(arguments[2])&&a.isNumber(arguments[3])?a.isNumber(arguments[4])?new I(e,t,arguments[2],arguments[3],arguments[4]):new I(e,t,arguments[2],arguments[3]):a.isNumber(arguments[4])?new k(e,t,{min:arguments[2],max:arguments[3],step:arguments[4]}):new k(e,t,{min:arguments[2],max:arguments[3]}):a.isString(n)?new C(e,t):a.isFunction(n)?new D(e,t,""):a.isBoolean(n)?new A(e,t):null},H=window.requestAnimationFrame||window.webkitRequestAnimationFrame||window.mozRequestAnimationFrame||window.oRequestAnimationFrame||window.msRequestAnimationFrame||function(e){setTimeout(e,1e3/60)},G=function(){function e(){f(this,e),this.backgroundElement=document.createElement("div"),a.extend(this.backgroundElement.style,{backgroundColor:"rgba(0,0,0,0.8)",top:0,left:0,display:"none",zIndex:"1000",opacity:0,WebkitTransition:"opacity 0.2s linear",transition:"opacity 0.2s linear"}),S.makeFullscreen(this.backgroundElement),this.backgroundElement.style.position="fixed",this.domElement=document.createElement("div"),a.extend(this.domElement.style,{position:"fixed",display:"none",zIndex:"1001",opacity:0,WebkitTransition:"-webkit-transform 0.2s ease-out, opacity 0.2s linear",transition:"transform 0.2s ease-out, opacity 0.2s linear"}),document.body.appendChild(this.backgroundElement),document.body.appendChild(this.domElement);var t=this;S.bind(this.backgroundElement,"click",(function(){t.hide()}))}return m(e,[{key:"show",value:function(){var e=this;this.backgroundElement.style.display="block",this.domElement.style.display="block",this.domElement.style.opacity=0,this.domElement.style.webkitTransform="scale(1.1)",this.layout(),a.defer((function(){e.backgroundElement.style.opacity=1,e.domElement.style.opacity=1,e.domElement.style.webkitTransform="scale(1)"}))}},{key:"hide",value:function(){var e=this,t=function t(){e.domElement.style.display="none",e.backgroundElement.style.display="none",S.unbind(e.domElement,"webkitTransitionEnd",t),S.unbind(e.domElement,"transitionend",t),S.unbind(e.domElement,"oTransitionEnd",t)};S.bind(this.domElement,"webkitTransitionEnd",t),S.bind(this.domElement,"transitionend",t),S.bind(this.domElement,"oTransitionEnd",t),this.backgroundElement.style.opacity=0,this.domElement.style.opacity=0,this.domElement.style.webkitTransform="scale(1.1)"}},{key:"layout",value:function(){this.domElement.style.left=window.innerWidth/2-S.getWidth(this.domElement)/2+"px",this.domElement.style.top=window.innerHeight/2-S.getHeight(this.domElement)/2+"px"}}]),e}();!function(e,t){var n=t||document,i=document.createElement("style");i.type="text/css",i.innerHTML=e;var r=n.getElementsByTagName("head")[0];try{r.appendChild(i)}catch(e){}}(function(e){if("undefined"!=typeof window){var t=document.createElement("style");return t.setAttribute("type","text/css"),t.innerHTML=e,document.head.appendChild(t),e}}(".dg ul{list-style:none;margin:0;padding:0;width:100%;clear:both}.dg.ac{position:fixed;top:0;left:0;right:0;height:0;z-index:0}.dg:not(.ac) .main{overflow:hidden}.dg.main{-webkit-transition:opacity .1s linear;-o-transition:opacity .1s linear;-moz-transition:opacity .1s linear;transition:opacity .1s linear}.dg.main.taller-than-window{overflow-y:auto}.dg.main.taller-than-window .close-button{opacity:1;margin-top:-1px;border-top:1px solid #2c2c2c}.dg.main ul.closed .close-button{opacity:1 !important}.dg.main:hover .close-button,.dg.main .close-button.drag{opacity:1}.dg.main .close-button{-webkit-transition:opacity .1s linear;-o-transition:opacity .1s linear;-moz-transition:opacity .1s linear;transition:opacity .1s linear;border:0;line-height:19px;height:20px;cursor:pointer;text-align:center;background-color:#000}.dg.main .close-button.close-top{position:relative}.dg.main .close-button.close-bottom{position:absolute}.dg.main .close-button:hover{background-color:#111}.dg.a{float:right;margin-right:15px;overflow-y:visible}.dg.a.has-save>ul.close-top{margin-top:0}.dg.a.has-save>ul.close-bottom{margin-top:27px}.dg.a.has-save>ul.closed{margin-top:0}.dg.a .save-row{top:0;z-index:1002}.dg.a .save-row.close-top{position:relative}.dg.a .save-row.close-bottom{position:fixed}.dg li{-webkit-transition:height .1s ease-out;-o-transition:height .1s ease-out;-moz-transition:height .1s ease-out;transition:height .1s ease-out;-webkit-transition:overflow .1s linear;-o-transition:overflow .1s linear;-moz-transition:overflow .1s linear;transition:overflow .1s linear}.dg li:not(.folder){cursor:auto;height:27px;line-height:27px;padding:0 4px 0 5px}.dg li.folder{padding:0;border-left:4px solid rgba(0,0,0,0)}.dg li.title{cursor:pointer;margin-left:-4px}.dg .closed li:not(.title),.dg .closed ul li,.dg .closed ul li>*{height:0;overflow:hidden;border:0}.dg .cr{clear:both;padding-left:3px;height:27px;overflow:hidden}.dg .property-name{cursor:default;float:left;clear:left;width:40%;overflow:hidden;text-overflow:ellipsis}.dg .c{float:left;width:60%;position:relative}.dg .c input[type=text]{border:0;margin-top:4px;padding:3px;width:100%;float:right}.dg .has-slider input[type=text]{width:30%;margin-left:0}.dg .slider{float:left;width:66%;margin-left:-5px;margin-right:0;height:19px;margin-top:4px}.dg .slider-fg{height:100%}.dg .c input[type=checkbox]{margin-top:7px}.dg .c select{margin-top:5px}.dg .cr.function,.dg .cr.function .property-name,.dg .cr.function *,.dg .cr.boolean,.dg .cr.boolean *{cursor:pointer}.dg .cr.color{overflow:visible}.dg .selector{display:none;position:absolute;margin-left:-9px;margin-top:23px;z-index:10}.dg .c:hover .selector,.dg .selector.drag{display:block}.dg li.save-row{padding:0}.dg li.save-row .button{display:inline-block;padding:0px 6px}.dg.dialogue{background-color:#222;width:460px;padding:15px;font-size:13px;line-height:15px}#dg-new-constructor{padding:10px;color:#222;font-family:Monaco, monospace;font-size:10px;border:0;resize:none;box-shadow:inset 1px 1px 1px #888;word-wrap:break-word;margin:12px 0;display:block;width:440px;overflow-y:scroll;height:100px;position:relative}#dg-local-explain{display:none;font-size:11px;line-height:17px;border-radius:3px;background-color:#333;padding:8px;margin-top:10px}#dg-local-explain code{font-size:10px}#dat-gui-save-locally{display:none}.dg{color:#eee;font:11px 'Lucida Grande', sans-serif;text-shadow:0 -1px 0 #111}.dg.main::-webkit-scrollbar{width:5px;background:#1a1a1a}.dg.main::-webkit-scrollbar-corner{height:0;display:none}.dg.main::-webkit-scrollbar-thumb{border-radius:5px;background:#676767}.dg li:not(.folder){background:#1a1a1a;border-bottom:1px solid #2c2c2c}.dg li.save-row{line-height:25px;background:#dad5cb;border:0}.dg li.save-row select{margin-left:5px;width:108px}.dg li.save-row .button{margin-left:5px;margin-top:1px;border-radius:2px;font-size:9px;line-height:7px;padding:4px 4px 5px 4px;background:#c5bdad;color:#fff;text-shadow:0 1px 0 #b0a58f;box-shadow:0 -1px 0 #b0a58f;cursor:pointer}.dg li.save-row .button.gears{background:#c5bdad url(data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAsAAAANCAYAAAB/9ZQ7AAAAGXRFWHRTb2Z0d2FyZQBBZG9iZSBJbWFnZVJlYWR5ccllPAAAAQJJREFUeNpiYKAU/P//PwGIC/ApCABiBSAW+I8AClAcgKxQ4T9hoMAEUrxx2QSGN6+egDX+/vWT4e7N82AMYoPAx/evwWoYoSYbACX2s7KxCxzcsezDh3evFoDEBYTEEqycggWAzA9AuUSQQgeYPa9fPv6/YWm/Acx5IPb7ty/fw+QZblw67vDs8R0YHyQhgObx+yAJkBqmG5dPPDh1aPOGR/eugW0G4vlIoTIfyFcA+QekhhHJhPdQxbiAIguMBTQZrPD7108M6roWYDFQiIAAv6Aow/1bFwXgis+f2LUAynwoIaNcz8XNx3Dl7MEJUDGQpx9gtQ8YCueB+D26OECAAQDadt7e46D42QAAAABJRU5ErkJggg==) 2px 1px no-repeat;height:7px;width:8px}.dg li.save-row .button:hover{background-color:#bab19e;box-shadow:0 -1px 0 #b0a58f}.dg li.folder{border-bottom:0}.dg li.title{padding-left:16px;background:#000 url(data:image/gif;base64,R0lGODlhBQAFAJEAAP////Pz8////////yH5BAEAAAIALAAAAAAFAAUAAAIIlI+hKgFxoCgAOw==) 6px 10px no-repeat;cursor:pointer;border-bottom:1px solid rgba(255,255,255,0.2)}.dg .closed li.title{background-image:url(data:image/gif;base64,R0lGODlhBQAFAJEAAP////Pz8////////yH5BAEAAAIALAAAAAAFAAUAAAIIlGIWqMCbWAEAOw==)}.dg .cr.boolean{border-left:3px solid #806787}.dg .cr.color{border-left:3px solid}.dg .cr.function{border-left:3px solid #e61d5f}.dg .cr.number{border-left:3px solid #2FA1D6}.dg .cr.number input[type=text]{color:#2FA1D6}.dg .cr.string{border-left:3px solid #1ed36f}.dg .cr.string input[type=text]{color:#1ed36f}.dg .cr.function:hover,.dg .cr.boolean:hover{background:#111}.dg .c input[type=text]{background:#303030;outline:none}.dg .c input[type=text]:hover{background:#3c3c3c}.dg .c input[type=text]:focus{background:#494949;color:#fff}.dg .c .slider{background:#303030;cursor:ew-resize}.dg .c .slider-fg{background:#2FA1D6;max-width:100%}.dg .c .slider:hover{background:#3c3c3c}.dg .c .slider:hover .slider-fg{background:#44abda}\\n"));var V="Default",W=function(){try{return!!window.localStorage}catch(e){return!1}}(),j=void 0,q=!0,X=void 0,Y=!1,J=[],Z=function e(t){var n=this,i=t||{};this.domElement=document.createElement("div"),this.__ul=document.createElement("ul"),this.domElement.appendChild(this.__ul),S.addClass(this.domElement,"dg"),this.__folders={},this.__controllers=[],this.__rememberedObjects=[],this.__rememberedObjectIndecesToControllers=[],this.__listening=[],i=a.defaults(i,{closeOnTop:!1,autoPlace:!0,width:e.DEFAULT_WIDTH}),i=a.defaults(i,{resizable:i.autoPlace,hideable:i.autoPlace}),a.isUndefined(i.load)?i.load={preset:V}:i.preset&&(i.load.preset=i.preset),a.isUndefined(i.parent)&&i.hideable&&J.push(this),i.resizable=a.isUndefined(i.parent)&&i.resizable,i.autoPlace&&a.isUndefined(i.scrollable)&&(i.scrollable=!0);var r,s=W&&"true"===localStorage.getItem(ne(0,"isLocal")),o=void 0,l=void 0;if(Object.defineProperties(this,{parent:{get:function(){return i.parent}},scrollable:{get:function(){return i.scrollable}},autoPlace:{get:function(){return i.autoPlace}},closeOnTop:{get:function(){return i.closeOnTop}},preset:{get:function(){return n.parent?n.getRoot().preset:i.load.preset},set:function(e){n.parent?n.getRoot().preset=e:i.load.preset=e,function(e){for(var t=0;t1){var i=n.__li.nextElementSibling;return n.remove(),te(e,n.object,n.property,{before:i,factoryArgs:[a.toArray(arguments)]})}if(a.isArray(t)||a.isObject(t)){var r=n.__li.nextElementSibling;return n.remove(),te(e,n.object,n.property,{before:r,factoryArgs:[t]})}},name:function(e){return n.__li.firstElementChild.firstElementChild.innerHTML=e,n},listen:function(){return n.__gui.listen(n),n},remove:function(){return n.__gui.remove(n),n}}),n instanceof I){var i=new k(n.object,n.property,{min:n.__min,max:n.__max,step:n.__step});a.each(["updateDisplay","onChange","onFinishChange","step","min","max"],(function(e){var t=n[e],r=i[e];n[e]=i[e]=function(){var e=Array.prototype.slice.call(arguments);return r.apply(i,e),t.apply(n,e)}})),S.addClass(t,"has-slider"),n.domElement.insertBefore(i.domElement,n.domElement.firstElementChild)}else if(n instanceof k){var r=function(t){if(a.isNumber(n.__min)&&a.isNumber(n.__max)){var i=n.__li.firstElementChild.firstElementChild.innerHTML,r=n.__gui.__listening.indexOf(n)>-1;n.remove();var s=te(e,n.object,n.property,{before:n.__li.nextElementSibling,factoryArgs:[n.__min,n.__max,n.__step]});return s.name(i),r&&s.listen(),s}return t};n.min=a.compose(r,n.min),n.max=a.compose(r,n.max)}else n instanceof A?(S.bind(t,"click",(function(){S.fakeEvent(n.__checkbox,"click")})),S.bind(n.__checkbox,"click",(function(e){e.stopPropagation()}))):n instanceof D?(S.bind(t,"click",(function(){S.fakeEvent(n.__button,"click")})),S.bind(t,"mouseover",(function(){S.addClass(n.__button,"hover")})),S.bind(t,"mouseout",(function(){S.removeClass(n.__button,"hover")}))):n instanceof O&&(S.addClass(t,"color"),n.updateDisplay=a.compose((function(e){return t.style.borderLeftColor=n.__color.toString(),e}),n.updateDisplay),n.updateDisplay());n.setValue=a.compose((function(t){return e.getRoot().__preset_select&&n.isModified()&&$(e.getRoot(),!0),t}),n.setValue)}(e,c,r),e.__controllers.push(r),r}function ne(e,t){return document.location.href+"."+t}function ie(e,t,n){var i=document.createElement("option");i.innerHTML=t,i.value=t,e.__preset_select.appendChild(i),n&&(e.__preset_select.selectedIndex=e.__preset_select.length-1)}function re(e,t){t.style.display=e.useLocalStorage?"block":"none"}function se(e){var t=e.__save_row=document.createElement("li");S.addClass(e.domElement,"has-save"),e.__ul.insertBefore(t,e.__ul.firstChild),S.addClass(t,"save-row");var n=document.createElement("span");n.innerHTML=" ",S.addClass(n,"button gears");var i=document.createElement("span");i.innerHTML="Save",S.addClass(i,"button"),S.addClass(i,"save");var r=document.createElement("span");r.innerHTML="New",S.addClass(r,"button"),S.addClass(r,"save-as");var s=document.createElement("span");s.innerHTML="Revert",S.addClass(s,"button"),S.addClass(s,"revert");var o=e.__preset_select=document.createElement("select");if(e.load&&e.load.remembered?a.each(e.load.remembered,(function(t,n){ie(e,n,n===e.preset)})):ie(e,V,!1),S.bind(o,"change",(function(){for(var t=0;t0&&(e.preset=this.preset,e.remembered||(e.remembered={}),e.remembered[this.preset]=le(this)),e.folders={},a.each(this.__folders,(function(t,n){e.folders[n]=t.getSaveObject()})),e},save:function(){this.load.remembered||(this.load.remembered={}),this.load.remembered[this.preset]=le(this),$(this,!1),this.saveToLocalStorageIfPossible()},saveAs:function(e){this.load.remembered||(this.load.remembered={},this.load.remembered.Default=le(this,!0)),this.load.remembered[e]=le(this),this.preset=e,ie(this,e,!0),this.saveToLocalStorageIfPossible()},revert:function(e){a.each(this.__controllers,(function(t){this.getRoot().load.remembered?ee(e||this.getRoot(),t):t.setValue(t.initialValue),t.__onFinishChange&&t.__onFinishChange.call(t,t.getValue())}),this),a.each(this.__folders,(function(e){e.revert(e)})),e||$(this.getRoot(),!1)},listen:function(e){var t=0===this.__listening.length;this.__listening.push(e),t&&ce(this.__listening)},updateDisplay:function(){a.each(this.__controllers,(function(e){e.updateDisplay()})),a.each(this.__folders,(function(e){e.updateDisplay()}))}});const he={color:{Color:_,math:d,interpret:h},controllers:{Controller:w,BooleanController:A,OptionController:L,StringController:C,NumberController:P,NumberControllerBox:k,NumberControllerSlider:I,FunctionController:D,ColorController:O},dom:{dom:S},gui:{GUI:Z},GUI:Z}},258:e=>{!function(t){e.exports=t;var n={on:function(e,t){return s(this,e).push(t),this},once:function(e,t){var n=this;return i.originalListener=t,s(n,e).push(i),n;function i(){r.call(n,e,i),t.apply(this,arguments)}},off:r,emit:function(e,t){var n=this,i=s(n,e,!0);if(!i)return!1;var r=arguments.length;if(1===r)i.forEach(o);else if(2===r)i.forEach(l);else{var a=Array.prototype.slice.call(arguments,1);i.forEach(c)}return!!i.length;function o(e){e.call(n)}function l(e){e.call(n,t)}function c(e){e.apply(n,a)}}};function i(e){for(var t in n)e[t]=n[t];return e}function r(e,t){var n,i=this;if(arguments.length){if(t){if(n=s(i,e,!0)){if(!(n=n.filter(a)).length)return r.call(i,e);i.listeners[e]=n}}else if((n=i.listeners)&&(delete n[e],!Object.keys(n).length))return r.call(i)}else delete i.listeners;return i;function a(e){return e!==t&&e.originalListener!==t}}function s(e,t,n){if(!n||e.listeners){var i=e.listeners||(e.listeners={});return i[t]||(i[t]=[])}}i(t.prototype),t.mixin=i}((function e(){if(!(this instanceof e))return new e}))},645:(e,t)=>{t.read=function(e,t,n,i,r){var s,a,o=8*r-i-1,l=(1<>1,h=-7,u=n?r-1:0,d=n?-1:1,p=e[t+u];for(u+=d,s=p&(1<<-h)-1,p>>=-h,h+=o;h>0;s=256*s+e[t+u],u+=d,h-=8);for(a=s&(1<<-h)-1,s>>=-h,h+=i;h>0;a=256*a+e[t+u],u+=d,h-=8);if(0===s)s=1-c;else{if(s===l)return a?NaN:1/0*(p?-1:1);a+=Math.pow(2,i),s-=c}return(p?-1:1)*a*Math.pow(2,s-i)},t.write=function(e,t,n,i,r,s){var a,o,l,c=8*s-r-1,h=(1<>1,d=23===r?Math.pow(2,-24)-Math.pow(2,-77):0,p=i?0:s-1,f=i?1:-1,m=t<0||0===t&&1/t<0?1:0;for(t=Math.abs(t),isNaN(t)||t===1/0?(o=isNaN(t)?1:0,a=h):(a=Math.floor(Math.log(t)/Math.LN2),t*(l=Math.pow(2,-a))<1&&(a--,l*=2),(t+=a+u>=1?d/l:d*Math.pow(2,1-u))*l>=2&&(a++,l/=2),a+u>=h?(o=0,a=h):a+u>=1?(o=(t*l-1)*Math.pow(2,r),a+=u):(o=t*Math.pow(2,u-1)*Math.pow(2,r),a=0));r>=8;e[n+p]=255&o,p+=f,o/=256,r-=8);for(a=a<0;e[n+p]=255&a,p+=f,a/=256,c-=8);e[n+p-f]|=128*m}},166:function(e,t){!function(e){var t,n="undefined",i=n!==typeof Buffer&&Buffer,r=n!==typeof Uint8Array&&Uint8Array,s=n!==typeof ArrayBuffer&&ArrayBuffer,a=[0,0,0,0,0,0,0,0],o=Array.isArray||function(e){return!!e&&"[object Array]"==Object.prototype.toString.call(e)},l=4294967296;function c(o,c,x){var b=c?0:4,w=c?4:0,M=c?0:3,T=c?1:2,E=c?2:1,S=c?3:0,A=c?g:y,L=c?v:_,C=k.prototype,R="is"+o,P="_"+R;return C.buffer=void 0,C.offset=0,C[P]=!0,C.toNumber=N,C.toString=function(e){var t=this.buffer,n=this.offset,i=D(t,n+b),r=D(t,n+w),s="",a=!x&&2147483648&i;for(a&&(i=~i,r=l-r),e=e||10;;){var o=i%e*l+r;if(i=Math.floor(i/e),r=Math.floor(o/e),s=(o%e).toString(e)+s,!i&&!r)break}return a&&(s="-"+s),s},C.toJSON=N,C.toArray=h,i&&(C.toBuffer=u),r&&(C.toArrayBuffer=d),k[R]=function(e){return!(!e||!e[P])},e[o]=k,k;function k(e,i,o,c){return this instanceof k?function(e,i,o,c,h){r&&s&&(i instanceof s&&(i=new r(i)),c instanceof s&&(c=new r(c))),i||o||c||t?(p(i,o)||(h=o,c=i,o=0,i=new(t||Array)(8)),e.buffer=i,e.offset=o|=0,n!==typeof c&&("string"==typeof c?function(e,t,n,i){var r=0,s=n.length,a=0,o=0;"-"===n[0]&&r++;for(var c=r;r=0))break;o=o*i+h,a=a*i+Math.floor(o/l),o%=l}c&&(a=~a,o?o=l-o:a++),I(e,t+b,a),I(e,t+w,o)}(i,o,c,h||10):p(c,h)?f(i,o,c,h):"number"==typeof h?(I(i,o+b,c),I(i,o+w,h)):c>0?A(i,o,c):c<0?L(i,o,c):f(i,o,a,0))):e.buffer=m(a,0)}(this,e,i,o,c):new k(e,i,o,c)}function N(){var e=this.buffer,t=this.offset,n=D(e,t+b),i=D(e,t+w);return x||(n|=0),n?n*l+i:i}function I(e,t,n){e[t+S]=255&n,n>>=8,e[t+E]=255&n,n>>=8,e[t+T]=255&n,n>>=8,e[t+M]=255&n}function D(e,t){return 16777216*e[t+M]+(e[t+T]<<16)+(e[t+E]<<8)+e[t+S]}}function h(e){var n=this.buffer,i=this.offset;return t=null,!1!==e&&0===i&&8===n.length&&o(n)?n:m(n,i)}function u(e){var n=this.buffer,r=this.offset;if(t=i,!1!==e&&0===r&&8===n.length&&Buffer.isBuffer(n))return n;var s=new i(8);return f(s,0,n,r),s}function d(e){var n=this.buffer,i=this.offset,a=n.buffer;if(t=r,!1!==e&&0===i&&a instanceof s&&8===a.byteLength)return a;var o=new r(8);return f(o,0,n,i),o.buffer}function p(e,t){var n=e&&e.length;return t|=0,n&&t+8<=n&&"string"!=typeof e[t]}function f(e,t,n,i){t|=0,i|=0;for(var r=0;r<8;r++)e[t++]=255&n[i++]}function m(e,t){return Array.prototype.slice.call(e,t,t+8)}function g(e,t,n){for(var i=t+8;i>t;)e[--i]=255&n,n/=256}function v(e,t,n){var i=t+8;for(n++;i>t;)e[--i]=255&-n^255,n/=256}function y(e,t,n){for(var i=t+8;t{var t={}.toString;e.exports=Array.isArray||function(e){return"[object Array]"==t.call(e)}},374:(e,t,n)=>{t.encode=n(764).encode,t.decode=n(299).decode,t.Encoder=n(883).Encoder,t.Decoder=n(441).Decoder,t.createCodec=n(832).createCodec,t.codec=n(766).codec},679:function(e){function t(e){return e&&e.isBuffer&&e}e.exports=t("undefined"!=typeof Buffer&&Buffer)||t(this.Buffer)||t("undefined"!=typeof window&&window.Buffer)||this.Buffer},947:(e,t)=>{t.copy=function(e,t,n,i){var r;n||(n=0),i||0===i||(i=this.length),t||(t=0);var s=i-n;if(e===this&&n=0;r--)e[r+t]=this[r+n];else for(r=0;r=65536?(a-=65536,s+=String.fromCharCode(55296+(a>>>10),56320+(1023&a))):s+=String.fromCharCode(a));return s},t.write=function(e,t){for(var n=this,i=t||(t|=0),r=e.length,s=0,a=0;a>>6,n[i++]=128|63&s):s<55296||s>57343?(n[i++]=224|s>>>12,n[i++]=128|s>>>6&63,n[i++]=128|63&s):(s=65536+(s-55296<<10|e.charCodeAt(a++)-56320),n[i++]=240|s>>>18,n[i++]=128|s>>>12&63,n[i++]=128|s>>>6&63,n[i++]=128|63&s);return i-t}},683:(e,t,n)=>{var i=n(895),r=e.exports=s(0);function s(e){return new Array(e)}r.alloc=s,r.concat=i.concat,r.from=function(e){if(!i.isBuffer(e)&&i.isView(e))e=i.Uint8Array.from(e);else if(i.isArrayBuffer(e))e=new Uint8Array(e);else{if("string"==typeof e)return i.from.call(r,e);if("number"==typeof e)throw new TypeError('"value" argument must not be a number')}return Array.prototype.slice.call(e)}},580:(e,t,n)=>{var i=n(895),r=i.global,s=e.exports=i.hasBuffer?a(0):[];function a(e){return new r(e)}s.alloc=i.hasBuffer&&r.alloc||a,s.concat=i.concat,s.from=function(e){if(!i.isBuffer(e)&&i.isView(e))e=i.Uint8Array.from(e);else if(i.isArrayBuffer(e))e=new Uint8Array(e);else{if("string"==typeof e)return i.from.call(s,e);if("number"==typeof e)throw new TypeError('"value" argument must not be a number')}return r.from&&1!==r.from.length?r.from(e):new r(e)}},190:(e,t,n)=>{var i=n(947);t.copy=l,t.slice=c,t.toString=function(e,t,n){var s=!a&&r.isBuffer(this)?this.toString:i.toString;return s.apply(this,arguments)},t.write=("write",function(){return(this.write||i.write).apply(this,arguments)});var r=n(895),s=r.global,a=r.hasBuffer&&"TYPED_ARRAY_SUPPORT"in s,o=a&&!s.TYPED_ARRAY_SUPPORT;function l(e,t,n,s){var a=r.isBuffer(this),l=r.isBuffer(e);if(a&&l)return this.copy(e,t,n,s);if(o||a||l||!r.isView(this)||!r.isView(e))return i.copy.call(this,e,t,n,s);var h=n||null!=s?c.call(this,n,s):this;return e.set(h,t),h.length}function c(e,t){var n=this.slice||!o&&this.subarray;if(n)return n.call(this,e,t);var i=r.alloc.call(this,t-e);return l.call(this,i,0,e,t),i}},37:(e,t,n)=>{var i=n(895),r=e.exports=i.hasArrayBuffer?s(0):[];function s(e){return new Uint8Array(e)}r.alloc=s,r.concat=i.concat,r.from=function(e){if(i.isView(e)){var t=e.byteOffset,n=e.byteLength;(e=e.buffer).byteLength!==n&&(e.slice?e=e.slice(t,t+n):(e=new Uint8Array(e)).byteLength!==n&&(e=Array.prototype.slice.call(e,t,t+n)))}else{if("string"==typeof e)return i.from.call(r,e);if("number"==typeof e)throw new TypeError('"value" argument must not be a number')}return new Uint8Array(e)}},895:(e,t,n)=>{var i=t.global=n(679),r=t.hasBuffer=i&&!!i.isBuffer,s=t.hasArrayBuffer="undefined"!=typeof ArrayBuffer,a=t.isArray=n(826);t.isArrayBuffer=s?function(e){return e instanceof ArrayBuffer||f(e)}:v;var o=t.isBuffer=r?i.isBuffer:v,l=t.isView=s?ArrayBuffer.isView||y("ArrayBuffer","buffer"):v;t.alloc=p,t.concat=function(e,n){n||(n=0,Array.prototype.forEach.call(e,(function(e){n+=e.length})));var i=this!==t&&this||e[0],r=p.call(i,n),s=0;return Array.prototype.forEach.call(e,(function(e){s+=d.copy.call(e,r,s)})),r},t.from=function(e){return"string"==typeof e?m.call(this,e):g(this).from(e)};var c=t.Array=n(683),h=t.Buffer=n(580),u=t.Uint8Array=n(37),d=t.prototype=n(190);function p(e){return g(this).alloc(e)}var f=y("ArrayBuffer");function m(e){var t=3*e.length,n=p.call(this,t),i=d.write.call(n,e);return t!==i&&(n=d.slice.call(n,0,i)),n}function g(e){return o(e)?h:l(e)?u:a(e)?c:r?h:s?u:c}function v(){return!1}function y(e,t){return e="[object "+e+"]",function(n){return null!=n&&{}.toString.call(t?n[t]:n)===e}}},877:(e,t,n)=>{var i=n(826);t.createCodec=o,t.install=function(e){for(var t in e)s.prototype[t]=a(s.prototype[t],e[t])},t.filter=function(e){return i(e)?function(e){return e=e.slice(),function(n){return e.reduce(t,n)};function t(e,t){return t(e)}}(e):e};var r=n(895);function s(e){if(!(this instanceof s))return new s(e);this.options=e,this.init()}function a(e,t){return e&&t?function(){return e.apply(this,arguments),t.apply(this,arguments)}:e||t}function o(e){return new s(e)}s.prototype.init=function(){var e=this.options;return e&&e.uint8array&&(this.bufferish=r.Uint8Array),this},t.preset=o({preset:!0})},766:(e,t,n)=>{n(350),n(312),t.codec={preset:n(877).preset}},170:(e,t,n)=>{t.T=r;var i=n(350).preset;function r(e){if(!(this instanceof r))return new r(e);if(e&&(this.options=e,e.codec)){var t=this.codec=e.codec;t.bufferish&&(this.bufferish=t.bufferish)}}n(822).k.mixin(r.prototype),r.prototype.codec=i,r.prototype.fetch=function(){return this.codec.decode(this)}},299:(e,t,n)=>{t.decode=function(e,t){var n=new i(t);return n.write(e),n.read()};var i=n(170).T},441:(e,t,n)=>{t.Decoder=s;var i=n(258),r=n(170).T;function s(e){if(!(this instanceof s))return new s(e);r.call(this,e)}s.prototype=new r,i.mixin(s.prototype),s.prototype.decode=function(e){arguments.length&&this.write(e),this.flush()},s.prototype.push=function(e){this.emit("data",e)},s.prototype.end=function(e){this.decode(e),this.emit("end")}},517:(e,t,n)=>{t.F=r;var i=n(312).preset;function r(e){if(!(this instanceof r))return new r(e);if(e&&(this.options=e,e.codec)){var t=this.codec=e.codec;t.bufferish&&(this.bufferish=t.bufferish)}}n(822).I.mixin(r.prototype),r.prototype.codec=i,r.prototype.write=function(e){this.codec.encode(this,e)}},764:(e,t,n)=>{t.encode=function(e,t){var n=new i(t);return n.write(e),n.read()};var i=n(517).F},883:(e,t,n)=>{t.Encoder=s;var i=n(258),r=n(517).F;function s(e){if(!(this instanceof s))return new s(e);r.call(this,e)}s.prototype=new r,i.mixin(s.prototype),s.prototype.encode=function(e){this.write(e),this.emit("data",this.read())},s.prototype.end=function(e){arguments.length&&this.encode(e),this.flush(),this.emit("end")}},83:(e,t,n)=>{t.S=function e(t,n){if(!(this instanceof e))return new e(t,n);this.buffer=i.from(t),this.type=n};var i=n(895)},431:(e,t,n)=>{t.setExtPackers=function(e){e.addExtPacker(14,Error,[u,l]),e.addExtPacker(1,EvalError,[u,l]),e.addExtPacker(2,RangeError,[u,l]),e.addExtPacker(3,ReferenceError,[u,l]),e.addExtPacker(4,SyntaxError,[u,l]),e.addExtPacker(5,TypeError,[u,l]),e.addExtPacker(6,URIError,[u,l]),e.addExtPacker(10,RegExp,[h,l]),e.addExtPacker(11,Boolean,[c,l]),e.addExtPacker(12,String,[c,l]),e.addExtPacker(13,Date,[Number,l]),e.addExtPacker(15,Number,[c,l]),"undefined"!=typeof Uint8Array&&(e.addExtPacker(17,Int8Array,a),e.addExtPacker(18,Uint8Array,a),e.addExtPacker(19,Int16Array,a),e.addExtPacker(20,Uint16Array,a),e.addExtPacker(21,Int32Array,a),e.addExtPacker(22,Uint32Array,a),e.addExtPacker(23,Float32Array,a),"undefined"!=typeof Float64Array&&e.addExtPacker(24,Float64Array,a),"undefined"!=typeof Uint8ClampedArray&&e.addExtPacker(25,Uint8ClampedArray,a),e.addExtPacker(26,ArrayBuffer,a),e.addExtPacker(29,DataView,a)),r.hasBuffer&&e.addExtPacker(27,s,r.from)};var i,r=n(895),s=r.global,a=r.Uint8Array.from,o={name:1,message:1,stack:1,columnNumber:1,fileName:1,lineNumber:1};function l(e){return i||(i=n(764).encode),i(e)}function c(e){return e.valueOf()}function h(e){(e=RegExp.prototype.toString.call(e).split("/")).shift();var t=[e.pop()];return t.unshift(e.join("/")),t}function u(e){var t={};for(var n in o)t[n]=e[n];return t}},600:(e,t,n)=>{t.setExtUnpackers=function(e){e.addExtUnpacker(14,[o,c(Error)]),e.addExtUnpacker(1,[o,c(EvalError)]),e.addExtUnpacker(2,[o,c(RangeError)]),e.addExtUnpacker(3,[o,c(ReferenceError)]),e.addExtUnpacker(4,[o,c(SyntaxError)]),e.addExtUnpacker(5,[o,c(TypeError)]),e.addExtUnpacker(6,[o,c(URIError)]),e.addExtUnpacker(10,[o,l]),e.addExtUnpacker(11,[o,h(Boolean)]),e.addExtUnpacker(12,[o,h(String)]),e.addExtUnpacker(13,[o,h(Date)]),e.addExtUnpacker(15,[o,h(Number)]),"undefined"!=typeof Uint8Array&&(e.addExtUnpacker(17,h(Int8Array)),e.addExtUnpacker(18,h(Uint8Array)),e.addExtUnpacker(19,[u,h(Int16Array)]),e.addExtUnpacker(20,[u,h(Uint16Array)]),e.addExtUnpacker(21,[u,h(Int32Array)]),e.addExtUnpacker(22,[u,h(Uint32Array)]),e.addExtUnpacker(23,[u,h(Float32Array)]),"undefined"!=typeof Float64Array&&e.addExtUnpacker(24,[u,h(Float64Array)]),"undefined"!=typeof Uint8ClampedArray&&e.addExtUnpacker(25,h(Uint8ClampedArray)),e.addExtUnpacker(26,u),e.addExtUnpacker(29,[u,h(DataView)])),r.hasBuffer&&e.addExtUnpacker(27,h(s))};var i,r=n(895),s=r.global,a={name:1,message:1,stack:1,columnNumber:1,fileName:1,lineNumber:1};function o(e){return i||(i=n(299).decode),i(e)}function l(e){return RegExp.apply(null,e)}function c(e){return function(t){var n=new e;for(var i in a)n[i]=t[i];return n}}function h(e){return function(t){return new e(t)}}function u(e){return new Uint8Array(e).buffer}},832:(e,t,n)=>{n(350),n(312),t.createCodec=n(877).createCodec},822:(e,t,n)=>{t.k=s,t.I=a;var i=n(895),r="BUFFER_SHORTAGE";function s(){if(!(this instanceof s))return new s}function a(){if(!(this instanceof a))return new a}function o(){return this.buffers&&this.buffers.length?(this.flush(),this.pull()):this.fetch()}function l(e){(this.buffers||(this.buffers=[])).push(e)}function c(e){return function(t){for(var n in e)t[n]=e[n];return t}}s.mixin=c({bufferish:i,write:function(e){var t=this.offset?i.prototype.slice.call(this.buffer,this.offset):this.buffer;this.buffer=t?e?this.bufferish.concat([t,e]):t:e,this.offset=0},fetch:function(){throw new Error("method not implemented: fetch()")},flush:function(){for(;this.offsetthis.buffer.length)throw new Error(r);return this.offset=n,t},offset:0}),s.mixin(s.prototype),a.mixin=c({bufferish:i,write:function(){throw new Error("method not implemented: write()")},fetch:function(){var e=this.start;if(e1?this.bufferish.concat(e):e[0];return e.length=0,t},read:o,reserve:function(e){var t=0|e;if(this.buffer){var n=this.buffer.length,i=0|this.offset,r=i+t;if(rthis.minBufferSize)this.flush(),this.push(e);else{var n=this.reserve(t);i.prototype.copy.call(e,this.buffer,n)}},maxBufferSize:65536,minBufferSize:2048,offset:0,start:0}),a.mixin(a.prototype)},350:(e,t,n)=>{var i=n(83).S,r=n(600),s=n(76).readUint8,a=n(738),o=n(877);function l(){var e=this.options;return this.decode=function(e){var t=a.getReadToken(e);return function(e){var n=s(e),i=t[n];if(!i)throw new Error("Invalid type: "+(n?"0x"+n.toString(16):n));return i(e)}}(e),e&&e.preset&&r.setExtUnpackers(this),this}o.install({addExtUnpacker:function(e,t){(this.extUnpackers||(this.extUnpackers=[]))[e]=o.filter(t)},getExtUnpacker:function(e){return(this.extUnpackers||(this.extUnpackers=[]))[e]||function(t){return new i(t,e)}},init:l}),t.preset=l.call(o.preset)},76:(e,t,n)=>{var i=n(645),r=n(166),s=r.Uint64BE,a=r.Int64BE;t.getReadFormat=function(e){var t=o.hasArrayBuffer&&e&&e.binarraybuffer,n=e&&e.int64;return{map:c&&e&&e.usemap?u:h,array:d,str:p,bin:t?m:f,ext:g,uint8:v,uint16:_,uint32:b,uint64:M(8,n?S:T),int8:y,int16:x,int32:w,int64:M(8,n?A:E),float32:M(4,L),float64:M(8,C)}},t.readUint8=v;var o=n(895),l=n(190),c="undefined"!=typeof Map;function h(e,t){var n,i={},r=new Array(t),s=new Array(t),a=e.codec.decode;for(n=0;n{var i=n(76);function r(e){var t,n=new Array(256);for(t=0;t<=127;t++)n[t]=s(t);for(t=128;t<=143;t++)n[t]=o(t-128,e.map);for(t=144;t<=159;t++)n[t]=o(t-144,e.array);for(t=160;t<=191;t++)n[t]=o(t-160,e.str);for(n[192]=s(null),n[193]=null,n[194]=s(!1),n[195]=s(!0),n[196]=a(e.uint8,e.bin),n[197]=a(e.uint16,e.bin),n[198]=a(e.uint32,e.bin),n[199]=a(e.uint8,e.ext),n[200]=a(e.uint16,e.ext),n[201]=a(e.uint32,e.ext),n[202]=e.float32,n[203]=e.float64,n[204]=e.uint8,n[205]=e.uint16,n[206]=e.uint32,n[207]=e.uint64,n[208]=e.int8,n[209]=e.int16,n[210]=e.int32,n[211]=e.int64,n[212]=o(1,e.ext),n[213]=o(2,e.ext),n[214]=o(4,e.ext),n[215]=o(8,e.ext),n[216]=o(16,e.ext),n[217]=a(e.uint8,e.str),n[218]=a(e.uint16,e.str),n[219]=a(e.uint32,e.str),n[220]=a(e.uint16,e.array),n[221]=a(e.uint32,e.array),n[222]=a(e.uint16,e.map),n[223]=a(e.uint32,e.map),t=224;t<=255;t++)n[t]=s(t-256);return n}function s(e){return function(){return e}}function a(e,t){return function(n){var i=e(n);return t(n,i)}}function o(e,t){return function(n){return t(n,e)}}t.getReadToken=function(e){var t=i.getReadFormat(e);return e&&e.useraw?function(e){var t,n=r(e).slice();for(n[217]=n[196],n[218]=n[197],n[219]=n[198],t=160;t<=191;t++)n[t]=o(t-160,e.bin);return n}(t):r(t)}},312:(e,t,n)=>{var i=n(83).S,r=n(431),s=n(943),a=n(877);function o(){var e=this.options;return this.encode=function(e){var t=s.getWriteType(e);return function(e,n){var i=t[typeof n];if(!i)throw new Error('Unsupported type "'+typeof n+'": '+n);i(e,n)}}(e),e&&e.preset&&r.setExtPackers(this),this}a.install({addExtPacker:function(e,t,n){n=a.filter(n);var r=t.name;function s(t){return n&&(t=n(t)),new i(t,e)}r&&"Object"!==r?(this.extPackers||(this.extPackers={}))[r]=s:(this.extEncoderList||(this.extEncoderList=[])).unshift([t,s])},getExtPacker:function(e){var t=this.extPackers||(this.extPackers={}),n=e.constructor,i=n&&n.name&&t[n.name];if(i)return i;for(var r=this.extEncoderList||(this.extEncoderList=[]),s=r.length,a=0;a{var i=n(645),r=n(166),s=r.Uint64BE,a=r.Int64BE,o=n(370).w,l=n(895),c=l.global,h=l.hasBuffer&&"TYPED_ARRAY_SUPPORT"in c&&!c.TYPED_ARRAY_SUPPORT,u=l.hasBuffer&&c.prototype||{};function d(){var e=o.slice();return e[196]=p(196),e[197]=f(197),e[198]=m(198),e[199]=p(199),e[200]=f(200),e[201]=m(201),e[202]=g(202,4,u.writeFloatBE||_,!0),e[203]=g(203,8,u.writeDoubleBE||x,!0),e[204]=p(204),e[205]=f(205),e[206]=m(206),e[207]=g(207,8,v),e[208]=p(208),e[209]=f(209),e[210]=m(210),e[211]=g(211,8,y),e[217]=p(217),e[218]=f(218),e[219]=m(219),e[220]=f(220),e[221]=m(221),e[222]=f(222),e[223]=m(223),e}function p(e){return function(t,n){var i=t.reserve(2),r=t.buffer;r[i++]=e,r[i]=n}}function f(e){return function(t,n){var i=t.reserve(3),r=t.buffer;r[i++]=e,r[i++]=n>>>8,r[i]=n}}function m(e){return function(t,n){var i=t.reserve(5),r=t.buffer;r[i++]=e,r[i++]=n>>>24,r[i++]=n>>>16,r[i++]=n>>>8,r[i]=n}}function g(e,t,n,i){return function(r,s){var a=r.reserve(t+1);r.buffer[a++]=e,n.call(r.buffer,s,a,i)}}function v(e,t){new s(this,t,e)}function y(e,t){new a(this,t,e)}function _(e,t){i.write(this,e,t,!1,23,4)}function x(e,t){i.write(this,e,t,!1,52,8)}t.getWriteToken=function(e){return e&&e.uint8array?((t=d())[202]=g(202,4,_),t[203]=g(203,8,x),t):h||l.hasBuffer&&e&&e.safe?function(){var e=o.slice();return e[196]=g(196,1,c.prototype.writeUInt8),e[197]=g(197,2,c.prototype.writeUInt16BE),e[198]=g(198,4,c.prototype.writeUInt32BE),e[199]=g(199,1,c.prototype.writeUInt8),e[200]=g(200,2,c.prototype.writeUInt16BE),e[201]=g(201,4,c.prototype.writeUInt32BE),e[202]=g(202,4,c.prototype.writeFloatBE),e[203]=g(203,8,c.prototype.writeDoubleBE),e[204]=g(204,1,c.prototype.writeUInt8),e[205]=g(205,2,c.prototype.writeUInt16BE),e[206]=g(206,4,c.prototype.writeUInt32BE),e[207]=g(207,8,v),e[208]=g(208,1,c.prototype.writeInt8),e[209]=g(209,2,c.prototype.writeInt16BE),e[210]=g(210,4,c.prototype.writeInt32BE),e[211]=g(211,8,y),e[217]=g(217,1,c.prototype.writeUInt8),e[218]=g(218,2,c.prototype.writeUInt16BE),e[219]=g(219,4,c.prototype.writeUInt32BE),e[220]=g(220,2,c.prototype.writeUInt16BE),e[221]=g(221,4,c.prototype.writeUInt32BE),e[222]=g(222,2,c.prototype.writeUInt16BE),e[223]=g(223,4,c.prototype.writeUInt32BE),e}():d();var t}},943:(e,t,n)=>{var i=n(826),r=n(166),s=r.Uint64BE,a=r.Int64BE,o=n(895),l=n(190),c=n(598),h=n(370).w,u=n(83).S,d="undefined"!=typeof Uint8Array,p="undefined"!=typeof Map,f=[];f[1]=212,f[2]=213,f[4]=214,f[8]=215,f[16]=216,t.getWriteType=function(e){var t,n=c.getWriteToken(e),r=e&&e.useraw,m=d&&e&&e.binarraybuffer,g=m?o.isArrayBuffer:o.isBuffer,v=m?function(e,t){b(e,new Uint8Array(t))}:b,y=p&&e&&e.usemap?function(e,t){if(!(t instanceof Map))return w(e,t);var i=t.size;n[i<16?128+i:i<=65535?222:223](e,i);var r=e.codec.encode;t.forEach((function(t,n,i){r(e,n),r(e,t)}))}:w;return{boolean:function(e,t){n[t?195:194](e,t)},function:x,number:function(e,t){var i=0|t;t===i?n[-32<=i&&i<=127?255&i:0<=i?i<=255?204:i<=65535?205:206:-128<=i?208:-32768<=i?209:210](e,i):n[203](e,t)},object:r?function(e,t){if(g(t))return function(e,t){var i=t.length;n[i<32?160+i:i<=65535?218:219](e,i),e.send(t)}(e,t);_(e,t)}:_,string:(t=r?function(e){return e<32?1:e<=65535?3:5}:function(e){return e<32?1:e<=255?2:e<=65535?3:5},function(e,i){var r=i.length,s=5+3*r;e.offset=e.reserve(s);var a=e.buffer,o=t(r),c=e.offset+o;r=l.write.call(a,i,c);var h=t(r);if(o!==h){var u=c+h-o,d=c+r;l.copy.call(a,a,u,c,d)}n[1===h?160+r:h<=3?215+h:219](e,r),e.offset+=r}),symbol:x,undefined:x};function _(e,t){if(null===t)return x(e,t);if(g(t))return v(e,t);if(i(t))return function(e,t){var i=t.length;n[i<16?144+i:i<=65535?220:221](e,i);for(var r=e.codec.encode,s=0;s{for(var n=t.w=new Array(256),i=0;i<=255;i++)n[i]=r(i);function r(e){return function(t){var n=t.reserve(1);t.buffer[n]=e}}},212:(e,t,n)=>{"use strict";n.r(t),n.d(t,{ACESFilmicToneMapping:()=>ne,AddEquation:()=>E,AddOperation:()=>K,AdditiveAnimationBlendMode:()=>qt,AdditiveBlending:()=>b,AlphaFormat:()=>Oe,AlwaysDepth:()=>G,AlwaysStencilFunc:()=>Tn,AmbientLight:()=>td,AmbientLightProbe:()=>wd,AnimationClip:()=>Mu,AnimationLoader:()=>Pu,AnimationMixer:()=>$d,AnimationObjectGroup:()=>Kd,AnimationUtils:()=>hu,ArcCurve:()=>qc,ArrayCamera:()=>gl,ArrowHelper:()=>Vp,Audio:()=>Nd,AudioAnalyser:()=>Ud,AudioContext:()=>_d,AudioListener:()=>kd,AudioLoader:()=>xd,AxesHelper:()=>Wp,AxisHelper:()=>_f,BackSide:()=>m,BasicDepthPacking:()=>sn,BasicShadowMap:()=>h,BinaryTextureLoader:()=>Tf,Bone:()=>tc,BooleanKeyframeTrack:()=>gu,BoundingBoxHelper:()=>xf,Box2:()=>cp,Box3:()=>hi,Box3Helper:()=>Fp,BoxBufferGeometry:()=>xs,BoxGeometry:()=>xs,BoxHelper:()=>Bp,BufferAttribute:()=>Nr,BufferGeometry:()=>es,BufferGeometryLoader:()=>ld,ByteType:()=>Ee,Cache:()=>Eu,Camera:()=>Es,CameraHelper:()=>Ip,CanvasRenderer:()=>Sf,CanvasTexture:()=>kc,CatmullRomCurve3:()=>Qc,CineonToneMapping:()=>te,CircleBufferGeometry:()=>Ic,CircleGeometry:()=>Ic,ClampToEdgeWrapping:()=>de,Clock:()=>Sd,Color:()=>Cr,ColorKeyframeTrack:()=>vu,CompressedTexture:()=>Pc,CompressedTextureLoader:()=>ku,ConeBufferGeometry:()=>Oc,ConeGeometry:()=>Oc,CubeCamera:()=>Ls,CubeReflectionMapping:()=>se,CubeRefractionMapping:()=>ae,CubeTexture:()=>Cs,CubeTextureLoader:()=>Iu,CubeUVReflectionMapping:()=>ce,CubeUVRefractionMapping:()=>he,CubicBezierCurve:()=>nh,CubicBezierCurve3:()=>ih,CubicInterpolant:()=>du,CullFaceBack:()=>o,CullFaceFront:()=>l,CullFaceFrontBack:()=>c,CullFaceNone:()=>a,Curve:()=>Wc,CurvePath:()=>Bu,CustomBlending:()=>T,CustomToneMapping:()=>ie,CylinderBufferGeometry:()=>Dc,CylinderGeometry:()=>Dc,Cylindrical:()=>op,DataTexture:()=>nc,DataTexture2DArray:()=>Aa,DataTexture3D:()=>La,DataTextureLoader:()=>Du,DataUtils:()=>Xp,DecrementStencilOp:()=>pn,DecrementWrapStencilOp:()=>mn,DefaultLoadingManager:()=>Au,DepthFormat:()=>Ge,DepthStencilFormat:()=>Ve,DepthTexture:()=>Nc,DirectionalLight:()=>ed,DirectionalLightHelper:()=>Pp,DiscreteInterpolant:()=>fu,DodecahedronBufferGeometry:()=>Fc,DodecahedronGeometry:()=>Fc,DoubleSide:()=>g,DstAlphaFactor:()=>O,DstColorFactor:()=>F,DynamicBufferAttribute:()=>cf,DynamicCopyUsage:()=>kn,DynamicDrawUsage:()=>Sn,DynamicReadUsage:()=>Cn,EdgesGeometry:()=>Vc,EdgesHelper:()=>bf,EllipseCurve:()=>jc,EqualDepth:()=>j,EqualStencilFunc:()=>_n,EquirectangularReflectionMapping:()=>oe,EquirectangularRefractionMapping:()=>le,Euler:()=>Yi,EventDispatcher:()=>On,ExtrudeBufferGeometry:()=>Bh,ExtrudeGeometry:()=>Bh,FaceColors:()=>Kp,FileLoader:()=>Ru,FlatShading:()=>v,Float16BufferAttribute:()=>Hr,Float32Attribute:()=>vf,Float32BufferAttribute:()=>Gr,Float64Attribute:()=>yf,Float64BufferAttribute:()=>Vr,FloatType:()=>Re,Fog:()=>El,FogExp2:()=>Tl,Font:()=>md,FontLoader:()=>vd,FrontSide:()=>f,Frustum:()=>Bs,GLBufferAttribute:()=>np,GLSL1:()=>In,GLSL3:()=>Dn,GammaEncoding:()=>Qt,GreaterDepth:()=>X,GreaterEqualDepth:()=>q,GreaterEqualStencilFunc:()=>Mn,GreaterStencilFunc:()=>bn,GridHelper:()=>Sp,Group:()=>vl,HalfFloatType:()=>Pe,HemisphereLight:()=>Hu,HemisphereLightHelper:()=>Ep,HemisphereLightProbe:()=>bd,IcosahedronBufferGeometry:()=>Uh,IcosahedronGeometry:()=>Uh,ImageBitmapLoader:()=>pd,ImageLoader:()=>Nu,ImageUtils:()=>Qn,ImmediateRenderObject:()=>pp,IncrementStencilOp:()=>dn,IncrementWrapStencilOp:()=>fn,InstancedBufferAttribute:()=>ac,InstancedBufferGeometry:()=>od,InstancedInterleavedBuffer:()=>tp,InstancedMesh:()=>uc,Int16Attribute:()=>pf,Int16BufferAttribute:()=>Br,Int32Attribute:()=>mf,Int32BufferAttribute:()=>Ur,Int8Attribute:()=>hf,Int8BufferAttribute:()=>Ir,IntType:()=>Le,InterleavedBuffer:()=>Al,InterleavedBufferAttribute:()=>Cl,Interpolant:()=>uu,InterpolateDiscrete:()=>Ut,InterpolateLinear:()=>zt,InterpolateSmooth:()=>Ht,InvertStencilOp:()=>gn,JSONLoader:()=>Af,KeepStencilOp:()=>hn,KeyframeTrack:()=>mu,LOD:()=>Yl,LatheBufferGeometry:()=>zh,LatheGeometry:()=>zh,Layers:()=>Ji,LensFlare:()=>Cf,LessDepth:()=>V,LessEqualDepth:()=>W,LessEqualStencilFunc:()=>xn,LessStencilFunc:()=>yn,Light:()=>zu,LightProbe:()=>rd,Line:()=>yc,Line3:()=>dp,LineBasicMaterial:()=>dc,LineCurve:()=>rh,LineCurve3:()=>sh,LineDashedMaterial:()=>lu,LineLoop:()=>wc,LinePieces:()=>Jp,LineSegments:()=>bc,LineStrip:()=>Yp,LinearEncoding:()=>Zt,LinearFilter:()=>_e,LinearInterpolant:()=>pu,LinearMipMapLinearFilter:()=>Me,LinearMipMapNearestFilter:()=>be,LinearMipmapLinearFilter:()=>we,LinearMipmapNearestFilter:()=>xe,LinearToneMapping:()=>$,Loader:()=>Lu,LoaderUtils:()=>ad,LoadingManager:()=>Su,LogLuvEncoding:()=>en,LoopOnce:()=>Ot,LoopPingPong:()=>Ft,LoopRepeat:()=>Bt,LuminanceAlphaFormat:()=>ze,LuminanceFormat:()=>Ue,MOUSE:()=>r,Material:()=>wr,MaterialLoader:()=>sd,Math:()=>Yn,MathUtils:()=>Yn,Matrix3:()=>Zn,Matrix4:()=>Fi,MaxEquation:()=>C,Mesh:()=>ys,MeshBasicMaterial:()=>Rr,MeshDepthMaterial:()=>hl,MeshDistanceMaterial:()=>ul,MeshFaceMaterial:()=>$p,MeshLambertMaterial:()=>au,MeshMatcapMaterial:()=>ou,MeshNormalMaterial:()=>su,MeshPhongMaterial:()=>iu,MeshPhysicalMaterial:()=>nu,MeshStandardMaterial:()=>tu,MeshToonMaterial:()=>ru,MinEquation:()=>L,MirroredRepeatWrapping:()=>pe,MixOperation:()=>Z,MultiMaterial:()=>ef,MultiplyBlending:()=>M,MultiplyOperation:()=>J,NearestFilter:()=>fe,NearestMipMapLinearFilter:()=>ye,NearestMipMapNearestFilter:()=>ge,NearestMipmapLinearFilter:()=>ve,NearestMipmapNearestFilter:()=>me,NeverDepth:()=>H,NeverStencilFunc:()=>vn,NoBlending:()=>_,NoColors:()=>Zp,NoToneMapping:()=>Q,NormalAnimationBlendMode:()=>jt,NormalBlending:()=>x,NotEqualDepth:()=>Y,NotEqualStencilFunc:()=>wn,NumberKeyframeTrack:()=>yu,Object3D:()=>cr,ObjectLoader:()=>cd,ObjectSpaceNormalMap:()=>ln,OctahedronBufferGeometry:()=>Hh,OctahedronGeometry:()=>Hh,OneFactor:()=>P,OneMinusDstAlphaFactor:()=>B,OneMinusDstColorFactor:()=>U,OneMinusSrcAlphaFactor:()=>D,OneMinusSrcColorFactor:()=>N,OrthographicCamera:()=>Zs,PCFShadowMap:()=>u,PCFSoftShadowMap:()=>d,PMREMGenerator:()=>ua,ParametricBufferGeometry:()=>Gh,ParametricGeometry:()=>Gh,Particle:()=>nf,ParticleBasicMaterial:()=>af,ParticleSystem:()=>rf,ParticleSystemMaterial:()=>of,Path:()=>Fu,PerspectiveCamera:()=>Ss,Plane:()=>Is,PlaneBufferGeometry:()=>zs,PlaneGeometry:()=>zs,PlaneHelper:()=>Up,PointCloud:()=>tf,PointCloudMaterial:()=>sf,PointLight:()=>Qu,PointLightHelper:()=>bp,Points:()=>Lc,PointsMaterial:()=>Mc,PolarGridHelper:()=>Ap,PolyhedronBufferGeometry:()=>Bc,PolyhedronGeometry:()=>Bc,PositionalAudio:()=>Fd,PropertyBinding:()=>Zd,PropertyMixer:()=>zd,QuadraticBezierCurve:()=>ah,QuadraticBezierCurve3:()=>oh,Quaternion:()=>ai,QuaternionKeyframeTrack:()=>xu,QuaternionLinearInterpolant:()=>_u,REVISION:()=>i,RGBADepthPacking:()=>an,RGBAFormat:()=>Fe,RGBAIntegerFormat:()=>Je,RGBA_ASTC_10x10_Format:()=>yt,RGBA_ASTC_10x5_Format:()=>mt,RGBA_ASTC_10x6_Format:()=>gt,RGBA_ASTC_10x8_Format:()=>vt,RGBA_ASTC_12x10_Format:()=>_t,RGBA_ASTC_12x12_Format:()=>xt,RGBA_ASTC_4x4_Format:()=>ot,RGBA_ASTC_5x4_Format:()=>lt,RGBA_ASTC_5x5_Format:()=>ct,RGBA_ASTC_6x5_Format:()=>ht,RGBA_ASTC_6x6_Format:()=>ut,RGBA_ASTC_8x5_Format:()=>dt,RGBA_ASTC_8x6_Format:()=>pt,RGBA_ASTC_8x8_Format:()=>ft,RGBA_BPTC_Format:()=>bt,RGBA_ETC2_EAC_Format:()=>at,RGBA_PVRTC_2BPPV1_Format:()=>it,RGBA_PVRTC_4BPPV1_Format:()=>nt,RGBA_S3TC_DXT1_Format:()=>Ke,RGBA_S3TC_DXT3_Format:()=>Qe,RGBA_S3TC_DXT5_Format:()=>$e,RGBDEncoding:()=>rn,RGBEEncoding:()=>$t,RGBEFormat:()=>He,RGBFormat:()=>Be,RGBIntegerFormat:()=>Ye,RGBM16Encoding:()=>nn,RGBM7Encoding:()=>tn,RGB_ETC1_Format:()=>rt,RGB_ETC2_Format:()=>st,RGB_PVRTC_2BPPV1_Format:()=>tt,RGB_PVRTC_4BPPV1_Format:()=>et,RGB_S3TC_DXT1_Format:()=>Ze,RGFormat:()=>qe,RGIntegerFormat:()=>Xe,RawShaderMaterial:()=>Ks,Ray:()=>Bi,Raycaster:()=>ip,RectAreaLight:()=>nd,RedFormat:()=>We,RedIntegerFormat:()=>je,ReinhardToneMapping:()=>ee,RepeatWrapping:()=>ue,ReplaceStencilOp:()=>un,ReverseSubtractEquation:()=>A,RingBufferGeometry:()=>Vh,RingGeometry:()=>Vh,SRGB8_ALPHA8_ASTC_10x10_Format:()=>Nt,SRGB8_ALPHA8_ASTC_10x5_Format:()=>Rt,SRGB8_ALPHA8_ASTC_10x6_Format:()=>Pt,SRGB8_ALPHA8_ASTC_10x8_Format:()=>kt,SRGB8_ALPHA8_ASTC_12x10_Format:()=>It,SRGB8_ALPHA8_ASTC_12x12_Format:()=>Dt,SRGB8_ALPHA8_ASTC_4x4_Format:()=>wt,SRGB8_ALPHA8_ASTC_5x4_Format:()=>Mt,SRGB8_ALPHA8_ASTC_5x5_Format:()=>Tt,SRGB8_ALPHA8_ASTC_6x5_Format:()=>Et,SRGB8_ALPHA8_ASTC_6x6_Format:()=>St,SRGB8_ALPHA8_ASTC_8x5_Format:()=>At,SRGB8_ALPHA8_ASTC_8x6_Format:()=>Lt,SRGB8_ALPHA8_ASTC_8x8_Format:()=>Ct,Scene:()=>Sl,SceneUtils:()=>Lf,ShaderChunk:()=>Hs,ShaderLib:()=>Vs,ShaderMaterial:()=>Ts,ShadowMaterial:()=>eu,Shape:()=>Uu,ShapeBufferGeometry:()=>Wh,ShapeGeometry:()=>Wh,ShapePath:()=>fd,ShapeUtils:()=>Ih,ShortType:()=>Se,Skeleton:()=>sc,SkeletonHelper:()=>_p,SkinnedMesh:()=>ec,SmoothShading:()=>y,Sphere:()=>Ci,SphereBufferGeometry:()=>jh,SphereGeometry:()=>jh,Spherical:()=>ap,SphericalHarmonics3:()=>id,SplineCurve:()=>lh,SpotLight:()=>Xu,SpotLightHelper:()=>mp,Sprite:()=>Wl,SpriteMaterial:()=>Rl,SrcAlphaFactor:()=>I,SrcAlphaSaturateFactor:()=>z,SrcColorFactor:()=>k,StaticCopyUsage:()=>Pn,StaticDrawUsage:()=>En,StaticReadUsage:()=>Ln,StereoCamera:()=>Ed,StreamCopyUsage:()=>Nn,StreamDrawUsage:()=>An,StreamReadUsage:()=>Rn,StringKeyframeTrack:()=>bu,SubtractEquation:()=>S,SubtractiveBlending:()=>w,TOUCH:()=>s,TangentSpaceNormalMap:()=>on,TetrahedronBufferGeometry:()=>qh,TetrahedronGeometry:()=>qh,TextBufferGeometry:()=>Xh,TextGeometry:()=>Xh,Texture:()=>ei,TextureLoader:()=>Ou,TorusBufferGeometry:()=>Yh,TorusGeometry:()=>Yh,TorusKnotBufferGeometry:()=>Jh,TorusKnotGeometry:()=>Jh,Triangle:()=>xr,TriangleFanDrawMode:()=>Jt,TriangleStripDrawMode:()=>Yt,TrianglesDrawMode:()=>Xt,TubeBufferGeometry:()=>Zh,TubeGeometry:()=>Zh,UVMapping:()=>re,Uint16Attribute:()=>ff,Uint16BufferAttribute:()=>Fr,Uint32Attribute:()=>gf,Uint32BufferAttribute:()=>zr,Uint8Attribute:()=>uf,Uint8BufferAttribute:()=>Dr,Uint8ClampedAttribute:()=>df,Uint8ClampedBufferAttribute:()=>Or,Uniform:()=>ep,UniformsLib:()=>Gs,UniformsUtils:()=>Ms,UnsignedByteType:()=>Te,UnsignedInt248Type:()=>De,UnsignedIntType:()=>Ce,UnsignedShort4444Type:()=>ke,UnsignedShort5551Type:()=>Ne,UnsignedShort565Type:()=>Ie,UnsignedShortType:()=>Ae,VSMShadowMap:()=>p,Vector2:()=>Jn,Vector3:()=>oi,Vector4:()=>ni,VectorKeyframeTrack:()=>wu,Vertex:()=>lf,VertexColors:()=>Qp,VideoTexture:()=>Rc,WebGL1Renderer:()=>Ml,WebGLCubeRenderTarget:()=>Rs,WebGLMultipleRenderTargets:()=>ri,WebGLMultisampleRenderTarget:()=>si,WebGLRenderTarget:()=>ii,WebGLRenderTargetCube:()=>Ef,WebGLRenderer:()=>wl,WebGLUtils:()=>ml,WireframeGeometry:()=>Kh,WireframeHelper:()=>wf,WrapAroundEnding:()=>Wt,XHRLoader:()=>Mf,ZeroCurvatureEnding:()=>Gt,ZeroFactor:()=>R,ZeroSlopeEnding:()=>Vt,ZeroStencilOp:()=>cn,sRGBEncoding:()=>Kt});const i="132",r={LEFT:0,MIDDLE:1,RIGHT:2,ROTATE:0,DOLLY:1,PAN:2},s={ROTATE:0,PAN:1,DOLLY_PAN:2,DOLLY_ROTATE:3},a=0,o=1,l=2,c=3,h=0,u=1,d=2,p=3,f=0,m=1,g=2,v=1,y=2,_=0,x=1,b=2,w=3,M=4,T=5,E=100,S=101,A=102,L=103,C=104,R=200,P=201,k=202,N=203,I=204,D=205,O=206,B=207,F=208,U=209,z=210,H=0,G=1,V=2,W=3,j=4,q=5,X=6,Y=7,J=0,Z=1,K=2,Q=0,$=1,ee=2,te=3,ne=4,ie=5,re=300,se=301,ae=302,oe=303,le=304,ce=306,he=307,ue=1e3,de=1001,pe=1002,fe=1003,me=1004,ge=1004,ve=1005,ye=1005,_e=1006,xe=1007,be=1007,we=1008,Me=1008,Te=1009,Ee=1010,Se=1011,Ae=1012,Le=1013,Ce=1014,Re=1015,Pe=1016,ke=1017,Ne=1018,Ie=1019,De=1020,Oe=1021,Be=1022,Fe=1023,Ue=1024,ze=1025,He=Fe,Ge=1026,Ve=1027,We=1028,je=1029,qe=1030,Xe=1031,Ye=1032,Je=1033,Ze=33776,Ke=33777,Qe=33778,$e=33779,et=35840,tt=35841,nt=35842,it=35843,rt=36196,st=37492,at=37496,ot=37808,lt=37809,ct=37810,ht=37811,ut=37812,dt=37813,pt=37814,ft=37815,mt=37816,gt=37817,vt=37818,yt=37819,_t=37820,xt=37821,bt=36492,wt=37840,Mt=37841,Tt=37842,Et=37843,St=37844,At=37845,Lt=37846,Ct=37847,Rt=37848,Pt=37849,kt=37850,Nt=37851,It=37852,Dt=37853,Ot=2200,Bt=2201,Ft=2202,Ut=2300,zt=2301,Ht=2302,Gt=2400,Vt=2401,Wt=2402,jt=2500,qt=2501,Xt=0,Yt=1,Jt=2,Zt=3e3,Kt=3001,Qt=3007,$t=3002,en=3003,tn=3004,nn=3005,rn=3006,sn=3200,an=3201,on=0,ln=1,cn=0,hn=7680,un=7681,dn=7682,pn=7683,fn=34055,mn=34056,gn=5386,vn=512,yn=513,_n=514,xn=515,bn=516,wn=517,Mn=518,Tn=519,En=35044,Sn=35048,An=35040,Ln=35045,Cn=35049,Rn=35041,Pn=35046,kn=35050,Nn=35042,In="100",Dn="300 es";class On{addEventListener(e,t){void 0===this._listeners&&(this._listeners={});const n=this._listeners;void 0===n[e]&&(n[e]=[]),-1===n[e].indexOf(t)&&n[e].push(t)}hasEventListener(e,t){if(void 0===this._listeners)return!1;const n=this._listeners;return void 0!==n[e]&&-1!==n[e].indexOf(t)}removeEventListener(e,t){if(void 0===this._listeners)return;const n=this._listeners[e];if(void 0!==n){const e=n.indexOf(t);-1!==e&&n.splice(e,1)}}dispatchEvent(e){if(void 0===this._listeners)return;const t=this._listeners[e.type];if(void 0!==t){e.target=this;const n=t.slice(0);for(let t=0,i=n.length;t>8&255]+Bn[e>>16&255]+Bn[e>>24&255]+"-"+Bn[255&t]+Bn[t>>8&255]+"-"+Bn[t>>16&15|64]+Bn[t>>24&255]+"-"+Bn[63&n|128]+Bn[n>>8&255]+"-"+Bn[n>>16&255]+Bn[n>>24&255]+Bn[255&i]+Bn[i>>8&255]+Bn[i>>16&255]+Bn[i>>24&255]).toUpperCase()}function Gn(e,t,n){return Math.max(t,Math.min(n,e))}function Vn(e,t){return(e%t+t)%t}function Wn(e,t,n){return(1-n)*e+n*t}function jn(e){return 0==(e&e-1)&&0!==e}function qn(e){return Math.pow(2,Math.ceil(Math.log(e)/Math.LN2))}function Xn(e){return Math.pow(2,Math.floor(Math.log(e)/Math.LN2))}var Yn=Object.freeze({__proto__:null,DEG2RAD:Un,RAD2DEG:zn,generateUUID:Hn,clamp:Gn,euclideanModulo:Vn,mapLinear:function(e,t,n,i,r){return i+(e-t)*(r-i)/(n-t)},inverseLerp:function(e,t,n){return e!==t?(n-e)/(t-e):0},lerp:Wn,damp:function(e,t,n,i){return Wn(e,t,1-Math.exp(-n*i))},pingpong:function(e,t=1){return t-Math.abs(Vn(e,2*t)-t)},smoothstep:function(e,t,n){return e<=t?0:e>=n?1:(e=(e-t)/(n-t))*e*(3-2*e)},smootherstep:function(e,t,n){return e<=t?0:e>=n?1:(e=(e-t)/(n-t))*e*e*(e*(6*e-15)+10)},randInt:function(e,t){return e+Math.floor(Math.random()*(t-e+1))},randFloat:function(e,t){return e+Math.random()*(t-e)},randFloatSpread:function(e){return e*(.5-Math.random())},seededRandom:function(e){return void 0!==e&&(Fn=e%2147483647),Fn=16807*Fn%2147483647,(Fn-1)/2147483646},degToRad:function(e){return e*Un},radToDeg:function(e){return e*zn},isPowerOfTwo:jn,ceilPowerOfTwo:qn,floorPowerOfTwo:Xn,setQuaternionFromProperEuler:function(e,t,n,i,r){const s=Math.cos,a=Math.sin,o=s(n/2),l=a(n/2),c=s((t+i)/2),h=a((t+i)/2),u=s((t-i)/2),d=a((t-i)/2),p=s((i-t)/2),f=a((i-t)/2);switch(r){case"XYX":e.set(o*h,l*u,l*d,o*c);break;case"YZY":e.set(l*d,o*h,l*u,o*c);break;case"ZXZ":e.set(l*u,l*d,o*h,o*c);break;case"XZX":e.set(o*h,l*f,l*p,o*c);break;case"YXY":e.set(l*p,o*h,l*f,o*c);break;case"ZYZ":e.set(l*f,l*p,o*h,o*c);break;default:console.warn("THREE.MathUtils: .setQuaternionFromProperEuler() encountered an unknown order: "+r)}}});class Jn{constructor(e=0,t=0){this.x=e,this.y=t}get width(){return this.x}set width(e){this.x=e}get height(){return this.y}set height(e){this.y=e}set(e,t){return this.x=e,this.y=t,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,t){switch(e){case 0:this.x=t;break;case 1:this.y=t;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,t){return void 0!==t?(console.warn("THREE.Vector2: .add() now only accepts one argument. Use .addVectors( a, b ) instead."),this.addVectors(e,t)):(this.x+=e.x,this.y+=e.y,this)}addScalar(e){return this.x+=e,this.y+=e,this}addVectors(e,t){return this.x=e.x+t.x,this.y=e.y+t.y,this}addScaledVector(e,t){return this.x+=e.x*t,this.y+=e.y*t,this}sub(e,t){return void 0!==t?(console.warn("THREE.Vector2: .sub() now only accepts one argument. Use .subVectors( a, b ) instead."),this.subVectors(e,t)):(this.x-=e.x,this.y-=e.y,this)}subScalar(e){return this.x-=e,this.y-=e,this}subVectors(e,t){return this.x=e.x-t.x,this.y=e.y-t.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 t=this.x,n=this.y,i=e.elements;return this.x=i[0]*t+i[3]*n+i[6],this.y=i[1]*t+i[4]*n+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,t){return this.x=Math.max(e.x,Math.min(t.x,this.x)),this.y=Math.max(e.y,Math.min(t.y,this.y)),this}clampScalar(e,t){return this.x=Math.max(e,Math.min(t,this.x)),this.y=Math.max(e,Math.min(t,this.y)),this}clampLength(e,t){const n=this.length();return this.divideScalar(n||1).multiplyScalar(Math.max(e,Math.min(t,n)))}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=this.x<0?Math.ceil(this.x):Math.floor(this.x),this.y=this.y<0?Math.ceil(this.y):Math.floor(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}distanceTo(e){return Math.sqrt(this.distanceToSquared(e))}distanceToSquared(e){const t=this.x-e.x,n=this.y-e.y;return t*t+n*n}manhattanDistanceTo(e){return Math.abs(this.x-e.x)+Math.abs(this.y-e.y)}setLength(e){return this.normalize().multiplyScalar(e)}lerp(e,t){return this.x+=(e.x-this.x)*t,this.y+=(e.y-this.y)*t,this}lerpVectors(e,t,n){return this.x=e.x+(t.x-e.x)*n,this.y=e.y+(t.y-e.y)*n,this}equals(e){return e.x===this.x&&e.y===this.y}fromArray(e,t=0){return this.x=e[t],this.y=e[t+1],this}toArray(e=[],t=0){return e[t]=this.x,e[t+1]=this.y,e}fromBufferAttribute(e,t,n){return void 0!==n&&console.warn("THREE.Vector2: offset has been removed from .fromBufferAttribute()."),this.x=e.getX(t),this.y=e.getY(t),this}rotateAround(e,t){const n=Math.cos(t),i=Math.sin(t),r=this.x-e.x,s=this.y-e.y;return this.x=r*n-s*i+e.x,this.y=r*i+s*n+e.y,this}random(){return this.x=Math.random(),this.y=Math.random(),this}}Jn.prototype.isVector2=!0;class Zn{constructor(){this.elements=[1,0,0,0,1,0,0,0,1],arguments.length>0&&console.error("THREE.Matrix3: the constructor no longer reads arguments. use .set() instead.")}set(e,t,n,i,r,s,a,o,l){const c=this.elements;return c[0]=e,c[1]=i,c[2]=a,c[3]=t,c[4]=r,c[5]=o,c[6]=n,c[7]=s,c[8]=l,this}identity(){return this.set(1,0,0,0,1,0,0,0,1),this}copy(e){const t=this.elements,n=e.elements;return t[0]=n[0],t[1]=n[1],t[2]=n[2],t[3]=n[3],t[4]=n[4],t[5]=n[5],t[6]=n[6],t[7]=n[7],t[8]=n[8],this}extractBasis(e,t,n){return e.setFromMatrix3Column(this,0),t.setFromMatrix3Column(this,1),n.setFromMatrix3Column(this,2),this}setFromMatrix4(e){const t=e.elements;return this.set(t[0],t[4],t[8],t[1],t[5],t[9],t[2],t[6],t[10]),this}multiply(e){return this.multiplyMatrices(this,e)}premultiply(e){return this.multiplyMatrices(e,this)}multiplyMatrices(e,t){const n=e.elements,i=t.elements,r=this.elements,s=n[0],a=n[3],o=n[6],l=n[1],c=n[4],h=n[7],u=n[2],d=n[5],p=n[8],f=i[0],m=i[3],g=i[6],v=i[1],y=i[4],_=i[7],x=i[2],b=i[5],w=i[8];return r[0]=s*f+a*v+o*x,r[3]=s*m+a*y+o*b,r[6]=s*g+a*_+o*w,r[1]=l*f+c*v+h*x,r[4]=l*m+c*y+h*b,r[7]=l*g+c*_+h*w,r[2]=u*f+d*v+p*x,r[5]=u*m+d*y+p*b,r[8]=u*g+d*_+p*w,this}multiplyScalar(e){const t=this.elements;return t[0]*=e,t[3]*=e,t[6]*=e,t[1]*=e,t[4]*=e,t[7]*=e,t[2]*=e,t[5]*=e,t[8]*=e,this}determinant(){const e=this.elements,t=e[0],n=e[1],i=e[2],r=e[3],s=e[4],a=e[5],o=e[6],l=e[7],c=e[8];return t*s*c-t*a*l-n*r*c+n*a*o+i*r*l-i*s*o}invert(){const e=this.elements,t=e[0],n=e[1],i=e[2],r=e[3],s=e[4],a=e[5],o=e[6],l=e[7],c=e[8],h=c*s-a*l,u=a*o-c*r,d=l*r-s*o,p=t*h+n*u+i*d;if(0===p)return this.set(0,0,0,0,0,0,0,0,0);const f=1/p;return e[0]=h*f,e[1]=(i*l-c*n)*f,e[2]=(a*n-i*s)*f,e[3]=u*f,e[4]=(c*t-i*o)*f,e[5]=(i*r-a*t)*f,e[6]=d*f,e[7]=(n*o-l*t)*f,e[8]=(s*t-n*r)*f,this}transpose(){let e;const t=this.elements;return e=t[1],t[1]=t[3],t[3]=e,e=t[2],t[2]=t[6],t[6]=e,e=t[5],t[5]=t[7],t[7]=e,this}getNormalMatrix(e){return this.setFromMatrix4(e).invert().transpose()}transposeIntoArray(e){const t=this.elements;return e[0]=t[0],e[1]=t[3],e[2]=t[6],e[3]=t[1],e[4]=t[4],e[5]=t[7],e[6]=t[2],e[7]=t[5],e[8]=t[8],this}setUvTransform(e,t,n,i,r,s,a){const o=Math.cos(r),l=Math.sin(r);return this.set(n*o,n*l,-n*(o*s+l*a)+s+e,-i*l,i*o,-i*(-l*s+o*a)+a+t,0,0,1),this}scale(e,t){const n=this.elements;return n[0]*=e,n[3]*=e,n[6]*=e,n[1]*=t,n[4]*=t,n[7]*=t,this}rotate(e){const t=Math.cos(e),n=Math.sin(e),i=this.elements,r=i[0],s=i[3],a=i[6],o=i[1],l=i[4],c=i[7];return i[0]=t*r+n*o,i[3]=t*s+n*l,i[6]=t*a+n*c,i[1]=-n*r+t*o,i[4]=-n*s+t*l,i[7]=-n*a+t*c,this}translate(e,t){const n=this.elements;return n[0]+=e*n[2],n[3]+=e*n[5],n[6]+=e*n[8],n[1]+=t*n[2],n[4]+=t*n[5],n[7]+=t*n[8],this}equals(e){const t=this.elements,n=e.elements;for(let e=0;e<9;e++)if(t[e]!==n[e])return!1;return!0}fromArray(e,t=0){for(let n=0;n<9;n++)this.elements[n]=e[n+t];return this}toArray(e=[],t=0){const n=this.elements;return e[t]=n[0],e[t+1]=n[1],e[t+2]=n[2],e[t+3]=n[3],e[t+4]=n[4],e[t+5]=n[5],e[t+6]=n[6],e[t+7]=n[7],e[t+8]=n[8],e}clone(){return(new this.constructor).fromArray(this.elements)}}let Kn;Zn.prototype.isMatrix3=!0;class Qn{static getDataURL(e){if(/^data:/i.test(e.src))return e.src;if("undefined"==typeof HTMLCanvasElement)return e.src;let t;if(e instanceof HTMLCanvasElement)t=e;else{void 0===Kn&&(Kn=document.createElementNS("http://www.w3.org/1999/xhtml","canvas")),Kn.width=e.width,Kn.height=e.height;const n=Kn.getContext("2d");e instanceof ImageData?n.putImageData(e,0,0):n.drawImage(e,0,0,e.width,e.height),t=Kn}return t.width>2048||t.height>2048?(console.warn("THREE.ImageUtils.getDataURL: Image converted to jpg for performance reasons",e),t.toDataURL("image/jpeg",.6)):t.toDataURL("image/png")}}let $n=0;class ei extends On{constructor(e=ei.DEFAULT_IMAGE,t=ei.DEFAULT_MAPPING,n=de,i=de,r=_e,s=we,a=Fe,o=Te,l=1,c=Zt){super(),Object.defineProperty(this,"id",{value:$n++}),this.uuid=Hn(),this.name="",this.image=e,this.mipmaps=[],this.mapping=t,this.wrapS=n,this.wrapT=i,this.magFilter=r,this.minFilter=s,this.anisotropy=l,this.format=a,this.internalFormat=null,this.type=o,this.offset=new Jn(0,0),this.repeat=new Jn(1,1),this.center=new Jn(0,0),this.rotation=0,this.matrixAutoUpdate=!0,this.matrix=new Zn,this.generateMipmaps=!0,this.premultiplyAlpha=!1,this.flipY=!0,this.unpackAlignment=4,this.encoding=c,this.version=0,this.onUpdate=null,this.isRenderTargetTexture=!1}updateMatrix(){this.matrix.setUvTransform(this.offset.x,this.offset.y,this.repeat.x,this.repeat.y,this.rotation,this.center.x,this.center.y)}clone(){return(new this.constructor).copy(this)}copy(e){return this.name=e.name,this.image=e.image,this.mipmaps=e.mipmaps.slice(0),this.mapping=e.mapping,this.wrapS=e.wrapS,this.wrapT=e.wrapT,this.magFilter=e.magFilter,this.minFilter=e.minFilter,this.anisotropy=e.anisotropy,this.format=e.format,this.internalFormat=e.internalFormat,this.type=e.type,this.offset.copy(e.offset),this.repeat.copy(e.repeat),this.center.copy(e.center),this.rotation=e.rotation,this.matrixAutoUpdate=e.matrixAutoUpdate,this.matrix.copy(e.matrix),this.generateMipmaps=e.generateMipmaps,this.premultiplyAlpha=e.premultiplyAlpha,this.flipY=e.flipY,this.unpackAlignment=e.unpackAlignment,this.encoding=e.encoding,this}toJSON(e){const t=void 0===e||"string"==typeof e;if(!t&&void 0!==e.textures[this.uuid])return e.textures[this.uuid];const n={metadata:{version:4.5,type:"Texture",generator:"Texture.toJSON"},uuid:this.uuid,name:this.name,mapping:this.mapping,repeat:[this.repeat.x,this.repeat.y],offset:[this.offset.x,this.offset.y],center:[this.center.x,this.center.y],rotation:this.rotation,wrap:[this.wrapS,this.wrapT],format:this.format,type:this.type,encoding:this.encoding,minFilter:this.minFilter,magFilter:this.magFilter,anisotropy:this.anisotropy,flipY:this.flipY,premultiplyAlpha:this.premultiplyAlpha,unpackAlignment:this.unpackAlignment};if(void 0!==this.image){const i=this.image;if(void 0===i.uuid&&(i.uuid=Hn()),!t&&void 0===e.images[i.uuid]){let t;if(Array.isArray(i)){t=[];for(let e=0,n=i.length;e1)switch(this.wrapS){case ue:e.x=e.x-Math.floor(e.x);break;case de:e.x=e.x<0?0:1;break;case pe:1===Math.abs(Math.floor(e.x)%2)?e.x=Math.ceil(e.x)-e.x:e.x=e.x-Math.floor(e.x)}if(e.y<0||e.y>1)switch(this.wrapT){case ue:e.y=e.y-Math.floor(e.y);break;case de:e.y=e.y<0?0:1;break;case pe:1===Math.abs(Math.floor(e.y)%2)?e.y=Math.ceil(e.y)-e.y:e.y=e.y-Math.floor(e.y)}return this.flipY&&(e.y=1-e.y),e}set needsUpdate(e){!0===e&&this.version++}}function ti(e){return"undefined"!=typeof HTMLImageElement&&e instanceof HTMLImageElement||"undefined"!=typeof HTMLCanvasElement&&e instanceof HTMLCanvasElement||"undefined"!=typeof ImageBitmap&&e instanceof ImageBitmap?Qn.getDataURL(e):e.data?{data:Array.prototype.slice.call(e.data),width:e.width,height:e.height,type:e.data.constructor.name}:(console.warn("THREE.Texture: Unable to serialize Texture."),{})}ei.DEFAULT_IMAGE=void 0,ei.DEFAULT_MAPPING=re,ei.prototype.isTexture=!0;class ni{constructor(e=0,t=0,n=0,i=1){this.x=e,this.y=t,this.z=n,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,t,n,i){return this.x=e,this.y=t,this.z=n,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,t){switch(e){case 0:this.x=t;break;case 1:this.y=t;break;case 2:this.z=t;break;case 3:this.w=t;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=void 0!==e.w?e.w:1,this}add(e,t){return void 0!==t?(console.warn("THREE.Vector4: .add() now only accepts one argument. Use .addVectors( a, b ) instead."),this.addVectors(e,t)):(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,t){return this.x=e.x+t.x,this.y=e.y+t.y,this.z=e.z+t.z,this.w=e.w+t.w,this}addScaledVector(e,t){return this.x+=e.x*t,this.y+=e.y*t,this.z+=e.z*t,this.w+=e.w*t,this}sub(e,t){return void 0!==t?(console.warn("THREE.Vector4: .sub() now only accepts one argument. Use .subVectors( a, b ) instead."),this.subVectors(e,t)):(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,t){return this.x=e.x-t.x,this.y=e.y-t.y,this.z=e.z-t.z,this.w=e.w-t.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 t=this.x,n=this.y,i=this.z,r=this.w,s=e.elements;return this.x=s[0]*t+s[4]*n+s[8]*i+s[12]*r,this.y=s[1]*t+s[5]*n+s[9]*i+s[13]*r,this.z=s[2]*t+s[6]*n+s[10]*i+s[14]*r,this.w=s[3]*t+s[7]*n+s[11]*i+s[15]*r,this}divideScalar(e){return this.multiplyScalar(1/e)}setAxisAngleFromQuaternion(e){this.w=2*Math.acos(e.w);const t=Math.sqrt(1-e.w*e.w);return t<1e-4?(this.x=1,this.y=0,this.z=0):(this.x=e.x/t,this.y=e.y/t,this.z=e.z/t),this}setAxisAngleFromRotationMatrix(e){let t,n,i,r;const s=.01,a=.1,o=e.elements,l=o[0],c=o[4],h=o[8],u=o[1],d=o[5],p=o[9],f=o[2],m=o[6],g=o[10];if(Math.abs(c-u)o&&e>v?ev?o=0?1:-1,i=1-t*t;if(i>Number.EPSILON){const r=Math.sqrt(i),s=Math.atan2(r,t*n);e=Math.sin(e*s)/r,a=Math.sin(a*s)/r}const r=a*n;if(o=o*e+u*r,l=l*e+d*r,c=c*e+p*r,h=h*e+f*r,e===1-a){const e=1/Math.sqrt(o*o+l*l+c*c+h*h);o*=e,l*=e,c*=e,h*=e}}e[t]=o,e[t+1]=l,e[t+2]=c,e[t+3]=h}static multiplyQuaternionsFlat(e,t,n,i,r,s){const a=n[i],o=n[i+1],l=n[i+2],c=n[i+3],h=r[s],u=r[s+1],d=r[s+2],p=r[s+3];return e[t]=a*p+c*h+o*d-l*u,e[t+1]=o*p+c*u+l*h-a*d,e[t+2]=l*p+c*d+a*u-o*h,e[t+3]=c*p-a*h-o*u-l*d,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,t,n,i){return this._x=e,this._y=t,this._z=n,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,t){if(!e||!e.isEuler)throw new Error("THREE.Quaternion: .setFromEuler() now expects an Euler rotation rather than a Vector3 and order.");const n=e._x,i=e._y,r=e._z,s=e._order,a=Math.cos,o=Math.sin,l=a(n/2),c=a(i/2),h=a(r/2),u=o(n/2),d=o(i/2),p=o(r/2);switch(s){case"XYZ":this._x=u*c*h+l*d*p,this._y=l*d*h-u*c*p,this._z=l*c*p+u*d*h,this._w=l*c*h-u*d*p;break;case"YXZ":this._x=u*c*h+l*d*p,this._y=l*d*h-u*c*p,this._z=l*c*p-u*d*h,this._w=l*c*h+u*d*p;break;case"ZXY":this._x=u*c*h-l*d*p,this._y=l*d*h+u*c*p,this._z=l*c*p+u*d*h,this._w=l*c*h-u*d*p;break;case"ZYX":this._x=u*c*h-l*d*p,this._y=l*d*h+u*c*p,this._z=l*c*p-u*d*h,this._w=l*c*h+u*d*p;break;case"YZX":this._x=u*c*h+l*d*p,this._y=l*d*h+u*c*p,this._z=l*c*p-u*d*h,this._w=l*c*h-u*d*p;break;case"XZY":this._x=u*c*h-l*d*p,this._y=l*d*h-u*c*p,this._z=l*c*p+u*d*h,this._w=l*c*h+u*d*p;break;default:console.warn("THREE.Quaternion: .setFromEuler() encountered an unknown order: "+s)}return!1!==t&&this._onChangeCallback(),this}setFromAxisAngle(e,t){const n=t/2,i=Math.sin(n);return this._x=e.x*i,this._y=e.y*i,this._z=e.z*i,this._w=Math.cos(n),this._onChangeCallback(),this}setFromRotationMatrix(e){const t=e.elements,n=t[0],i=t[4],r=t[8],s=t[1],a=t[5],o=t[9],l=t[2],c=t[6],h=t[10],u=n+a+h;if(u>0){const e=.5/Math.sqrt(u+1);this._w=.25/e,this._x=(c-o)*e,this._y=(r-l)*e,this._z=(s-i)*e}else if(n>a&&n>h){const e=2*Math.sqrt(1+n-a-h);this._w=(c-o)/e,this._x=.25*e,this._y=(i+s)/e,this._z=(r+l)/e}else if(a>h){const e=2*Math.sqrt(1+a-n-h);this._w=(r-l)/e,this._x=(i+s)/e,this._y=.25*e,this._z=(o+c)/e}else{const e=2*Math.sqrt(1+h-n-a);this._w=(s-i)/e,this._x=(r+l)/e,this._y=(o+c)/e,this._z=.25*e}return this._onChangeCallback(),this}setFromUnitVectors(e,t){let n=e.dot(t)+1;return nMath.abs(e.z)?(this._x=-e.y,this._y=e.x,this._z=0,this._w=n):(this._x=0,this._y=-e.z,this._z=e.y,this._w=n)):(this._x=e.y*t.z-e.z*t.y,this._y=e.z*t.x-e.x*t.z,this._z=e.x*t.y-e.y*t.x,this._w=n),this.normalize()}angleTo(e){return 2*Math.acos(Math.abs(Gn(this.dot(e),-1,1)))}rotateTowards(e,t){const n=this.angleTo(e);if(0===n)return this;const i=Math.min(1,t/n);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 0===e?(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,t){return void 0!==t?(console.warn("THREE.Quaternion: .multiply() now only accepts one argument. Use .multiplyQuaternions( a, b ) instead."),this.multiplyQuaternions(e,t)):this.multiplyQuaternions(this,e)}premultiply(e){return this.multiplyQuaternions(e,this)}multiplyQuaternions(e,t){const n=e._x,i=e._y,r=e._z,s=e._w,a=t._x,o=t._y,l=t._z,c=t._w;return this._x=n*c+s*a+i*l-r*o,this._y=i*c+s*o+r*a-n*l,this._z=r*c+s*l+n*o-i*a,this._w=s*c-n*a-i*o-r*l,this._onChangeCallback(),this}slerp(e,t){if(0===t)return this;if(1===t)return this.copy(e);const n=this._x,i=this._y,r=this._z,s=this._w;let a=s*e._w+n*e._x+i*e._y+r*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=s,this._x=n,this._y=i,this._z=r,this;const o=1-a*a;if(o<=Number.EPSILON){const e=1-t;return this._w=e*s+t*this._w,this._x=e*n+t*this._x,this._y=e*i+t*this._y,this._z=e*r+t*this._z,this.normalize(),this._onChangeCallback(),this}const l=Math.sqrt(o),c=Math.atan2(l,a),h=Math.sin((1-t)*c)/l,u=Math.sin(t*c)/l;return this._w=s*h+this._w*u,this._x=n*h+this._x*u,this._y=i*h+this._y*u,this._z=r*h+this._z*u,this._onChangeCallback(),this}slerpQuaternions(e,t,n){this.copy(e).slerp(t,n)}equals(e){return e._x===this._x&&e._y===this._y&&e._z===this._z&&e._w===this._w}fromArray(e,t=0){return this._x=e[t],this._y=e[t+1],this._z=e[t+2],this._w=e[t+3],this._onChangeCallback(),this}toArray(e=[],t=0){return e[t]=this._x,e[t+1]=this._y,e[t+2]=this._z,e[t+3]=this._w,e}fromBufferAttribute(e,t){return this._x=e.getX(t),this._y=e.getY(t),this._z=e.getZ(t),this._w=e.getW(t),this}_onChange(e){return this._onChangeCallback=e,this}_onChangeCallback(){}}ai.prototype.isQuaternion=!0;class oi{constructor(e=0,t=0,n=0){this.x=e,this.y=t,this.z=n}set(e,t,n){return void 0===n&&(n=this.z),this.x=e,this.y=t,this.z=n,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,t){switch(e){case 0:this.x=t;break;case 1:this.y=t;break;case 2:this.z=t;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,t){return void 0!==t?(console.warn("THREE.Vector3: .add() now only accepts one argument. Use .addVectors( a, b ) instead."),this.addVectors(e,t)):(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,t){return this.x=e.x+t.x,this.y=e.y+t.y,this.z=e.z+t.z,this}addScaledVector(e,t){return this.x+=e.x*t,this.y+=e.y*t,this.z+=e.z*t,this}sub(e,t){return void 0!==t?(console.warn("THREE.Vector3: .sub() now only accepts one argument. Use .subVectors( a, b ) instead."),this.subVectors(e,t)):(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,t){return this.x=e.x-t.x,this.y=e.y-t.y,this.z=e.z-t.z,this}multiply(e,t){return void 0!==t?(console.warn("THREE.Vector3: .multiply() now only accepts one argument. Use .multiplyVectors( a, b ) instead."),this.multiplyVectors(e,t)):(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,t){return this.x=e.x*t.x,this.y=e.y*t.y,this.z=e.z*t.z,this}applyEuler(e){return e&&e.isEuler||console.error("THREE.Vector3: .applyEuler() now expects an Euler rotation rather than a Vector3 and order."),this.applyQuaternion(ci.setFromEuler(e))}applyAxisAngle(e,t){return this.applyQuaternion(ci.setFromAxisAngle(e,t))}applyMatrix3(e){const t=this.x,n=this.y,i=this.z,r=e.elements;return this.x=r[0]*t+r[3]*n+r[6]*i,this.y=r[1]*t+r[4]*n+r[7]*i,this.z=r[2]*t+r[5]*n+r[8]*i,this}applyNormalMatrix(e){return this.applyMatrix3(e).normalize()}applyMatrix4(e){const t=this.x,n=this.y,i=this.z,r=e.elements,s=1/(r[3]*t+r[7]*n+r[11]*i+r[15]);return this.x=(r[0]*t+r[4]*n+r[8]*i+r[12])*s,this.y=(r[1]*t+r[5]*n+r[9]*i+r[13])*s,this.z=(r[2]*t+r[6]*n+r[10]*i+r[14])*s,this}applyQuaternion(e){const t=this.x,n=this.y,i=this.z,r=e.x,s=e.y,a=e.z,o=e.w,l=o*t+s*i-a*n,c=o*n+a*t-r*i,h=o*i+r*n-s*t,u=-r*t-s*n-a*i;return this.x=l*o+u*-r+c*-a-h*-s,this.y=c*o+u*-s+h*-r-l*-a,this.z=h*o+u*-a+l*-s-c*-r,this}project(e){return this.applyMatrix4(e.matrixWorldInverse).applyMatrix4(e.projectionMatrix)}unproject(e){return this.applyMatrix4(e.projectionMatrixInverse).applyMatrix4(e.matrixWorld)}transformDirection(e){const t=this.x,n=this.y,i=this.z,r=e.elements;return this.x=r[0]*t+r[4]*n+r[8]*i,this.y=r[1]*t+r[5]*n+r[9]*i,this.z=r[2]*t+r[6]*n+r[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,t){return this.x=Math.max(e.x,Math.min(t.x,this.x)),this.y=Math.max(e.y,Math.min(t.y,this.y)),this.z=Math.max(e.z,Math.min(t.z,this.z)),this}clampScalar(e,t){return this.x=Math.max(e,Math.min(t,this.x)),this.y=Math.max(e,Math.min(t,this.y)),this.z=Math.max(e,Math.min(t,this.z)),this}clampLength(e,t){const n=this.length();return this.divideScalar(n||1).multiplyScalar(Math.max(e,Math.min(t,n)))}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=this.x<0?Math.ceil(this.x):Math.floor(this.x),this.y=this.y<0?Math.ceil(this.y):Math.floor(this.y),this.z=this.z<0?Math.ceil(this.z):Math.floor(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,t){return this.x+=(e.x-this.x)*t,this.y+=(e.y-this.y)*t,this.z+=(e.z-this.z)*t,this}lerpVectors(e,t,n){return this.x=e.x+(t.x-e.x)*n,this.y=e.y+(t.y-e.y)*n,this.z=e.z+(t.z-e.z)*n,this}cross(e,t){return void 0!==t?(console.warn("THREE.Vector3: .cross() now only accepts one argument. Use .crossVectors( a, b ) instead."),this.crossVectors(e,t)):this.crossVectors(this,e)}crossVectors(e,t){const n=e.x,i=e.y,r=e.z,s=t.x,a=t.y,o=t.z;return this.x=i*o-r*a,this.y=r*s-n*o,this.z=n*a-i*s,this}projectOnVector(e){const t=e.lengthSq();if(0===t)return this.set(0,0,0);const n=e.dot(this)/t;return this.copy(e).multiplyScalar(n)}projectOnPlane(e){return li.copy(this).projectOnVector(e),this.sub(li)}reflect(e){return this.sub(li.copy(e).multiplyScalar(2*this.dot(e)))}angleTo(e){const t=Math.sqrt(this.lengthSq()*e.lengthSq());if(0===t)return Math.PI/2;const n=this.dot(e)/t;return Math.acos(Gn(n,-1,1))}distanceTo(e){return Math.sqrt(this.distanceToSquared(e))}distanceToSquared(e){const t=this.x-e.x,n=this.y-e.y,i=this.z-e.z;return t*t+n*n+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,t,n){const i=Math.sin(t)*e;return this.x=i*Math.sin(n),this.y=Math.cos(t)*e,this.z=i*Math.cos(n),this}setFromCylindrical(e){return this.setFromCylindricalCoords(e.radius,e.theta,e.y)}setFromCylindricalCoords(e,t,n){return this.x=e*Math.sin(t),this.y=n,this.z=e*Math.cos(t),this}setFromMatrixPosition(e){const t=e.elements;return this.x=t[12],this.y=t[13],this.z=t[14],this}setFromMatrixScale(e){const t=this.setFromMatrixColumn(e,0).length(),n=this.setFromMatrixColumn(e,1).length(),i=this.setFromMatrixColumn(e,2).length();return this.x=t,this.y=n,this.z=i,this}setFromMatrixColumn(e,t){return this.fromArray(e.elements,4*t)}setFromMatrix3Column(e,t){return this.fromArray(e.elements,3*t)}equals(e){return e.x===this.x&&e.y===this.y&&e.z===this.z}fromArray(e,t=0){return this.x=e[t],this.y=e[t+1],this.z=e[t+2],this}toArray(e=[],t=0){return e[t]=this.x,e[t+1]=this.y,e[t+2]=this.z,e}fromBufferAttribute(e,t,n){return void 0!==n&&console.warn("THREE.Vector3: offset has been removed from .fromBufferAttribute()."),this.x=e.getX(t),this.y=e.getY(t),this.z=e.getZ(t),this}random(){return this.x=Math.random(),this.y=Math.random(),this.z=Math.random(),this}}oi.prototype.isVector3=!0;const li=new oi,ci=new ai;class hi{constructor(e=new oi(1/0,1/0,1/0),t=new oi(-1/0,-1/0,-1/0)){this.min=e,this.max=t}set(e,t){return this.min.copy(e),this.max.copy(t),this}setFromArray(e){let t=1/0,n=1/0,i=1/0,r=-1/0,s=-1/0,a=-1/0;for(let o=0,l=e.length;or&&(r=l),c>s&&(s=c),h>a&&(a=h)}return this.min.set(t,n,i),this.max.set(r,s,a),this}setFromBufferAttribute(e){let t=1/0,n=1/0,i=1/0,r=-1/0,s=-1/0,a=-1/0;for(let o=0,l=e.count;or&&(r=l),c>s&&(s=c),h>a&&(a=h)}return this.min.set(t,n,i),this.max.set(r,s,a),this}setFromPoints(e){this.makeEmpty();for(let t=0,n=e.length;tthis.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,t){return t.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,di),di.distanceToSquared(e.center)<=e.radius*e.radius}intersectsPlane(e){let t,n;return e.normal.x>0?(t=e.normal.x*this.min.x,n=e.normal.x*this.max.x):(t=e.normal.x*this.max.x,n=e.normal.x*this.min.x),e.normal.y>0?(t+=e.normal.y*this.min.y,n+=e.normal.y*this.max.y):(t+=e.normal.y*this.max.y,n+=e.normal.y*this.min.y),e.normal.z>0?(t+=e.normal.z*this.min.z,n+=e.normal.z*this.max.z):(t+=e.normal.z*this.max.z,n+=e.normal.z*this.min.z),t<=-e.constant&&n>=-e.constant}intersectsTriangle(e){if(this.isEmpty())return!1;this.getCenter(xi),bi.subVectors(this.max,xi),fi.subVectors(e.a,xi),mi.subVectors(e.b,xi),gi.subVectors(e.c,xi),vi.subVectors(mi,fi),yi.subVectors(gi,mi),_i.subVectors(fi,gi);let t=[0,-vi.z,vi.y,0,-yi.z,yi.y,0,-_i.z,_i.y,vi.z,0,-vi.x,yi.z,0,-yi.x,_i.z,0,-_i.x,-vi.y,vi.x,0,-yi.y,yi.x,0,-_i.y,_i.x,0];return!!Ti(t,fi,mi,gi,bi)&&(t=[1,0,0,0,1,0,0,0,1],!!Ti(t,fi,mi,gi,bi)&&(wi.crossVectors(vi,yi),t=[wi.x,wi.y,wi.z],Ti(t,fi,mi,gi,bi)))}clampPoint(e,t){return t.copy(e).clamp(this.min,this.max)}distanceToPoint(e){return di.copy(e).clamp(this.min,this.max).sub(e).length()}getBoundingSphere(e){return this.getCenter(e.center),e.radius=.5*this.getSize(di).length(),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()||(ui[0].set(this.min.x,this.min.y,this.min.z).applyMatrix4(e),ui[1].set(this.min.x,this.min.y,this.max.z).applyMatrix4(e),ui[2].set(this.min.x,this.max.y,this.min.z).applyMatrix4(e),ui[3].set(this.min.x,this.max.y,this.max.z).applyMatrix4(e),ui[4].set(this.max.x,this.min.y,this.min.z).applyMatrix4(e),ui[5].set(this.max.x,this.min.y,this.max.z).applyMatrix4(e),ui[6].set(this.max.x,this.max.y,this.min.z).applyMatrix4(e),ui[7].set(this.max.x,this.max.y,this.max.z).applyMatrix4(e),this.setFromPoints(ui)),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)}}hi.prototype.isBox3=!0;const ui=[new oi,new oi,new oi,new oi,new oi,new oi,new oi,new oi],di=new oi,pi=new hi,fi=new oi,mi=new oi,gi=new oi,vi=new oi,yi=new oi,_i=new oi,xi=new oi,bi=new oi,wi=new oi,Mi=new oi;function Ti(e,t,n,i,r){for(let s=0,a=e.length-3;s<=a;s+=3){Mi.fromArray(e,s);const a=r.x*Math.abs(Mi.x)+r.y*Math.abs(Mi.y)+r.z*Math.abs(Mi.z),o=t.dot(Mi),l=n.dot(Mi),c=i.dot(Mi);if(Math.max(-Math.max(o,l,c),Math.min(o,l,c))>a)return!1}return!0}const Ei=new hi,Si=new oi,Ai=new oi,Li=new oi;class Ci{constructor(e=new oi,t=-1){this.center=e,this.radius=t}set(e,t){return this.center.copy(e),this.radius=t,this}setFromPoints(e,t){const n=this.center;void 0!==t?n.copy(t):Ei.setFromPoints(e).getCenter(n);let i=0;for(let t=0,r=e.length;tthis.radius*this.radius&&(t.sub(this.center).normalize(),t.multiplyScalar(this.radius).add(this.center)),t}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){Li.subVectors(e,this.center);const t=Li.lengthSq();if(t>this.radius*this.radius){const e=Math.sqrt(t),n=.5*(e-this.radius);this.center.add(Li.multiplyScalar(n/e)),this.radius+=n}return this}union(e){return Ai.subVectors(e.center,this.center).normalize().multiplyScalar(e.radius),this.expandByPoint(Si.copy(e.center).add(Ai)),this.expandByPoint(Si.copy(e.center).sub(Ai)),this}equals(e){return e.center.equals(this.center)&&e.radius===this.radius}clone(){return(new this.constructor).copy(this)}}const Ri=new oi,Pi=new oi,ki=new oi,Ni=new oi,Ii=new oi,Di=new oi,Oi=new oi;class Bi{constructor(e=new oi,t=new oi(0,0,-1)){this.origin=e,this.direction=t}set(e,t){return this.origin.copy(e),this.direction.copy(t),this}copy(e){return this.origin.copy(e.origin),this.direction.copy(e.direction),this}at(e,t){return t.copy(this.direction).multiplyScalar(e).add(this.origin)}lookAt(e){return this.direction.copy(e).sub(this.origin).normalize(),this}recast(e){return this.origin.copy(this.at(e,Ri)),this}closestPointToPoint(e,t){t.subVectors(e,this.origin);const n=t.dot(this.direction);return n<0?t.copy(this.origin):t.copy(this.direction).multiplyScalar(n).add(this.origin)}distanceToPoint(e){return Math.sqrt(this.distanceSqToPoint(e))}distanceSqToPoint(e){const t=Ri.subVectors(e,this.origin).dot(this.direction);return t<0?this.origin.distanceToSquared(e):(Ri.copy(this.direction).multiplyScalar(t).add(this.origin),Ri.distanceToSquared(e))}distanceSqToSegment(e,t,n,i){Pi.copy(e).add(t).multiplyScalar(.5),ki.copy(t).sub(e).normalize(),Ni.copy(this.origin).sub(Pi);const r=.5*e.distanceTo(t),s=-this.direction.dot(ki),a=Ni.dot(this.direction),o=-Ni.dot(ki),l=Ni.lengthSq(),c=Math.abs(1-s*s);let h,u,d,p;if(c>0)if(h=s*o-a,u=s*a-o,p=r*c,h>=0)if(u>=-p)if(u<=p){const e=1/c;h*=e,u*=e,d=h*(h+s*u+2*a)+u*(s*h+u+2*o)+l}else u=r,h=Math.max(0,-(s*u+a)),d=-h*h+u*(u+2*o)+l;else u=-r,h=Math.max(0,-(s*u+a)),d=-h*h+u*(u+2*o)+l;else u<=-p?(h=Math.max(0,-(-s*r+a)),u=h>0?-r:Math.min(Math.max(-r,-o),r),d=-h*h+u*(u+2*o)+l):u<=p?(h=0,u=Math.min(Math.max(-r,-o),r),d=u*(u+2*o)+l):(h=Math.max(0,-(s*r+a)),u=h>0?r:Math.min(Math.max(-r,-o),r),d=-h*h+u*(u+2*o)+l);else u=s>0?-r:r,h=Math.max(0,-(s*u+a)),d=-h*h+u*(u+2*o)+l;return n&&n.copy(this.direction).multiplyScalar(h).add(this.origin),i&&i.copy(ki).multiplyScalar(u).add(Pi),d}intersectSphere(e,t){Ri.subVectors(e.center,this.origin);const n=Ri.dot(this.direction),i=Ri.dot(Ri)-n*n,r=e.radius*e.radius;if(i>r)return null;const s=Math.sqrt(r-i),a=n-s,o=n+s;return a<0&&o<0?null:a<0?this.at(o,t):this.at(a,t)}intersectsSphere(e){return this.distanceSqToPoint(e.center)<=e.radius*e.radius}distanceToPlane(e){const t=e.normal.dot(this.direction);if(0===t)return 0===e.distanceToPoint(this.origin)?0:null;const n=-(this.origin.dot(e.normal)+e.constant)/t;return n>=0?n:null}intersectPlane(e,t){const n=this.distanceToPlane(e);return null===n?null:this.at(n,t)}intersectsPlane(e){const t=e.distanceToPoint(this.origin);return 0===t||e.normal.dot(this.direction)*t<0}intersectBox(e,t){let n,i,r,s,a,o;const l=1/this.direction.x,c=1/this.direction.y,h=1/this.direction.z,u=this.origin;return l>=0?(n=(e.min.x-u.x)*l,i=(e.max.x-u.x)*l):(n=(e.max.x-u.x)*l,i=(e.min.x-u.x)*l),c>=0?(r=(e.min.y-u.y)*c,s=(e.max.y-u.y)*c):(r=(e.max.y-u.y)*c,s=(e.min.y-u.y)*c),n>s||r>i?null:((r>n||n!=n)&&(n=r),(s=0?(a=(e.min.z-u.z)*h,o=(e.max.z-u.z)*h):(a=(e.max.z-u.z)*h,o=(e.min.z-u.z)*h),n>o||a>i?null:((a>n||n!=n)&&(n=a),(o=0?n:i,t)))}intersectsBox(e){return null!==this.intersectBox(e,Ri)}intersectTriangle(e,t,n,i,r){Ii.subVectors(t,e),Di.subVectors(n,e),Oi.crossVectors(Ii,Di);let s,a=this.direction.dot(Oi);if(a>0){if(i)return null;s=1}else{if(!(a<0))return null;s=-1,a=-a}Ni.subVectors(this.origin,e);const o=s*this.direction.dot(Di.crossVectors(Ni,Di));if(o<0)return null;const l=s*this.direction.dot(Ii.cross(Ni));if(l<0)return null;if(o+l>a)return null;const c=-s*Ni.dot(Oi);return c<0?null:this.at(c/a,r)}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 Fi{constructor(){this.elements=[1,0,0,0,0,1,0,0,0,0,1,0,0,0,0,1],arguments.length>0&&console.error("THREE.Matrix4: the constructor no longer reads arguments. use .set() instead.")}set(e,t,n,i,r,s,a,o,l,c,h,u,d,p,f,m){const g=this.elements;return g[0]=e,g[4]=t,g[8]=n,g[12]=i,g[1]=r,g[5]=s,g[9]=a,g[13]=o,g[2]=l,g[6]=c,g[10]=h,g[14]=u,g[3]=d,g[7]=p,g[11]=f,g[15]=m,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 Fi).fromArray(this.elements)}copy(e){const t=this.elements,n=e.elements;return t[0]=n[0],t[1]=n[1],t[2]=n[2],t[3]=n[3],t[4]=n[4],t[5]=n[5],t[6]=n[6],t[7]=n[7],t[8]=n[8],t[9]=n[9],t[10]=n[10],t[11]=n[11],t[12]=n[12],t[13]=n[13],t[14]=n[14],t[15]=n[15],this}copyPosition(e){const t=this.elements,n=e.elements;return t[12]=n[12],t[13]=n[13],t[14]=n[14],this}setFromMatrix3(e){const t=e.elements;return this.set(t[0],t[3],t[6],0,t[1],t[4],t[7],0,t[2],t[5],t[8],0,0,0,0,1),this}extractBasis(e,t,n){return e.setFromMatrixColumn(this,0),t.setFromMatrixColumn(this,1),n.setFromMatrixColumn(this,2),this}makeBasis(e,t,n){return this.set(e.x,t.x,n.x,0,e.y,t.y,n.y,0,e.z,t.z,n.z,0,0,0,0,1),this}extractRotation(e){const t=this.elements,n=e.elements,i=1/Ui.setFromMatrixColumn(e,0).length(),r=1/Ui.setFromMatrixColumn(e,1).length(),s=1/Ui.setFromMatrixColumn(e,2).length();return t[0]=n[0]*i,t[1]=n[1]*i,t[2]=n[2]*i,t[3]=0,t[4]=n[4]*r,t[5]=n[5]*r,t[6]=n[6]*r,t[7]=0,t[8]=n[8]*s,t[9]=n[9]*s,t[10]=n[10]*s,t[11]=0,t[12]=0,t[13]=0,t[14]=0,t[15]=1,this}makeRotationFromEuler(e){e&&e.isEuler||console.error("THREE.Matrix4: .makeRotationFromEuler() now expects a Euler rotation rather than a Vector3 and order.");const t=this.elements,n=e.x,i=e.y,r=e.z,s=Math.cos(n),a=Math.sin(n),o=Math.cos(i),l=Math.sin(i),c=Math.cos(r),h=Math.sin(r);if("XYZ"===e.order){const e=s*c,n=s*h,i=a*c,r=a*h;t[0]=o*c,t[4]=-o*h,t[8]=l,t[1]=n+i*l,t[5]=e-r*l,t[9]=-a*o,t[2]=r-e*l,t[6]=i+n*l,t[10]=s*o}else if("YXZ"===e.order){const e=o*c,n=o*h,i=l*c,r=l*h;t[0]=e+r*a,t[4]=i*a-n,t[8]=s*l,t[1]=s*h,t[5]=s*c,t[9]=-a,t[2]=n*a-i,t[6]=r+e*a,t[10]=s*o}else if("ZXY"===e.order){const e=o*c,n=o*h,i=l*c,r=l*h;t[0]=e-r*a,t[4]=-s*h,t[8]=i+n*a,t[1]=n+i*a,t[5]=s*c,t[9]=r-e*a,t[2]=-s*l,t[6]=a,t[10]=s*o}else if("ZYX"===e.order){const e=s*c,n=s*h,i=a*c,r=a*h;t[0]=o*c,t[4]=i*l-n,t[8]=e*l+r,t[1]=o*h,t[5]=r*l+e,t[9]=n*l-i,t[2]=-l,t[6]=a*o,t[10]=s*o}else if("YZX"===e.order){const e=s*o,n=s*l,i=a*o,r=a*l;t[0]=o*c,t[4]=r-e*h,t[8]=i*h+n,t[1]=h,t[5]=s*c,t[9]=-a*c,t[2]=-l*c,t[6]=n*h+i,t[10]=e-r*h}else if("XZY"===e.order){const e=s*o,n=s*l,i=a*o,r=a*l;t[0]=o*c,t[4]=-h,t[8]=l*c,t[1]=e*h+r,t[5]=s*c,t[9]=n*h-i,t[2]=i*h-n,t[6]=a*c,t[10]=r*h+e}return t[3]=0,t[7]=0,t[11]=0,t[12]=0,t[13]=0,t[14]=0,t[15]=1,this}makeRotationFromQuaternion(e){return this.compose(Hi,e,Gi)}lookAt(e,t,n){const i=this.elements;return ji.subVectors(e,t),0===ji.lengthSq()&&(ji.z=1),ji.normalize(),Vi.crossVectors(n,ji),0===Vi.lengthSq()&&(1===Math.abs(n.z)?ji.x+=1e-4:ji.z+=1e-4,ji.normalize(),Vi.crossVectors(n,ji)),Vi.normalize(),Wi.crossVectors(ji,Vi),i[0]=Vi.x,i[4]=Wi.x,i[8]=ji.x,i[1]=Vi.y,i[5]=Wi.y,i[9]=ji.y,i[2]=Vi.z,i[6]=Wi.z,i[10]=ji.z,this}multiply(e,t){return void 0!==t?(console.warn("THREE.Matrix4: .multiply() now only accepts one argument. Use .multiplyMatrices( a, b ) instead."),this.multiplyMatrices(e,t)):this.multiplyMatrices(this,e)}premultiply(e){return this.multiplyMatrices(e,this)}multiplyMatrices(e,t){const n=e.elements,i=t.elements,r=this.elements,s=n[0],a=n[4],o=n[8],l=n[12],c=n[1],h=n[5],u=n[9],d=n[13],p=n[2],f=n[6],m=n[10],g=n[14],v=n[3],y=n[7],_=n[11],x=n[15],b=i[0],w=i[4],M=i[8],T=i[12],E=i[1],S=i[5],A=i[9],L=i[13],C=i[2],R=i[6],P=i[10],k=i[14],N=i[3],I=i[7],D=i[11],O=i[15];return r[0]=s*b+a*E+o*C+l*N,r[4]=s*w+a*S+o*R+l*I,r[8]=s*M+a*A+o*P+l*D,r[12]=s*T+a*L+o*k+l*O,r[1]=c*b+h*E+u*C+d*N,r[5]=c*w+h*S+u*R+d*I,r[9]=c*M+h*A+u*P+d*D,r[13]=c*T+h*L+u*k+d*O,r[2]=p*b+f*E+m*C+g*N,r[6]=p*w+f*S+m*R+g*I,r[10]=p*M+f*A+m*P+g*D,r[14]=p*T+f*L+m*k+g*O,r[3]=v*b+y*E+_*C+x*N,r[7]=v*w+y*S+_*R+x*I,r[11]=v*M+y*A+_*P+x*D,r[15]=v*T+y*L+_*k+x*O,this}multiplyScalar(e){const t=this.elements;return t[0]*=e,t[4]*=e,t[8]*=e,t[12]*=e,t[1]*=e,t[5]*=e,t[9]*=e,t[13]*=e,t[2]*=e,t[6]*=e,t[10]*=e,t[14]*=e,t[3]*=e,t[7]*=e,t[11]*=e,t[15]*=e,this}determinant(){const e=this.elements,t=e[0],n=e[4],i=e[8],r=e[12],s=e[1],a=e[5],o=e[9],l=e[13],c=e[2],h=e[6],u=e[10],d=e[14];return e[3]*(+r*o*h-i*l*h-r*a*u+n*l*u+i*a*d-n*o*d)+e[7]*(+t*o*d-t*l*u+r*s*u-i*s*d+i*l*c-r*o*c)+e[11]*(+t*l*h-t*a*d-r*s*h+n*s*d+r*a*c-n*l*c)+e[15]*(-i*a*c-t*o*h+t*a*u+i*s*h-n*s*u+n*o*c)}transpose(){const e=this.elements;let t;return t=e[1],e[1]=e[4],e[4]=t,t=e[2],e[2]=e[8],e[8]=t,t=e[6],e[6]=e[9],e[9]=t,t=e[3],e[3]=e[12],e[12]=t,t=e[7],e[7]=e[13],e[13]=t,t=e[11],e[11]=e[14],e[14]=t,this}setPosition(e,t,n){const i=this.elements;return e.isVector3?(i[12]=e.x,i[13]=e.y,i[14]=e.z):(i[12]=e,i[13]=t,i[14]=n),this}invert(){const e=this.elements,t=e[0],n=e[1],i=e[2],r=e[3],s=e[4],a=e[5],o=e[6],l=e[7],c=e[8],h=e[9],u=e[10],d=e[11],p=e[12],f=e[13],m=e[14],g=e[15],v=h*m*l-f*u*l+f*o*d-a*m*d-h*o*g+a*u*g,y=p*u*l-c*m*l-p*o*d+s*m*d+c*o*g-s*u*g,_=c*f*l-p*h*l+p*a*d-s*f*d-c*a*g+s*h*g,x=p*h*o-c*f*o-p*a*u+s*f*u+c*a*m-s*h*m,b=t*v+n*y+i*_+r*x;if(0===b)return this.set(0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0);const w=1/b;return e[0]=v*w,e[1]=(f*u*r-h*m*r-f*i*d+n*m*d+h*i*g-n*u*g)*w,e[2]=(a*m*r-f*o*r+f*i*l-n*m*l-a*i*g+n*o*g)*w,e[3]=(h*o*r-a*u*r-h*i*l+n*u*l+a*i*d-n*o*d)*w,e[4]=y*w,e[5]=(c*m*r-p*u*r+p*i*d-t*m*d-c*i*g+t*u*g)*w,e[6]=(p*o*r-s*m*r-p*i*l+t*m*l+s*i*g-t*o*g)*w,e[7]=(s*u*r-c*o*r+c*i*l-t*u*l-s*i*d+t*o*d)*w,e[8]=_*w,e[9]=(p*h*r-c*f*r-p*n*d+t*f*d+c*n*g-t*h*g)*w,e[10]=(s*f*r-p*a*r+p*n*l-t*f*l-s*n*g+t*a*g)*w,e[11]=(c*a*r-s*h*r-c*n*l+t*h*l+s*n*d-t*a*d)*w,e[12]=x*w,e[13]=(c*f*i-p*h*i+p*n*u-t*f*u-c*n*m+t*h*m)*w,e[14]=(p*a*i-s*f*i-p*n*o+t*f*o+s*n*m-t*a*m)*w,e[15]=(s*h*i-c*a*i+c*n*o-t*h*o-s*n*u+t*a*u)*w,this}scale(e){const t=this.elements,n=e.x,i=e.y,r=e.z;return t[0]*=n,t[4]*=i,t[8]*=r,t[1]*=n,t[5]*=i,t[9]*=r,t[2]*=n,t[6]*=i,t[10]*=r,t[3]*=n,t[7]*=i,t[11]*=r,this}getMaxScaleOnAxis(){const e=this.elements,t=e[0]*e[0]+e[1]*e[1]+e[2]*e[2],n=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(t,n,i))}makeTranslation(e,t,n){return this.set(1,0,0,e,0,1,0,t,0,0,1,n,0,0,0,1),this}makeRotationX(e){const t=Math.cos(e),n=Math.sin(e);return this.set(1,0,0,0,0,t,-n,0,0,n,t,0,0,0,0,1),this}makeRotationY(e){const t=Math.cos(e),n=Math.sin(e);return this.set(t,0,n,0,0,1,0,0,-n,0,t,0,0,0,0,1),this}makeRotationZ(e){const t=Math.cos(e),n=Math.sin(e);return this.set(t,-n,0,0,n,t,0,0,0,0,1,0,0,0,0,1),this}makeRotationAxis(e,t){const n=Math.cos(t),i=Math.sin(t),r=1-n,s=e.x,a=e.y,o=e.z,l=r*s,c=r*a;return this.set(l*s+n,l*a-i*o,l*o+i*a,0,l*a+i*o,c*a+n,c*o-i*s,0,l*o-i*a,c*o+i*s,r*o*o+n,0,0,0,0,1),this}makeScale(e,t,n){return this.set(e,0,0,0,0,t,0,0,0,0,n,0,0,0,0,1),this}makeShear(e,t,n,i,r,s){return this.set(1,n,r,0,e,1,s,0,t,i,1,0,0,0,0,1),this}compose(e,t,n){const i=this.elements,r=t._x,s=t._y,a=t._z,o=t._w,l=r+r,c=s+s,h=a+a,u=r*l,d=r*c,p=r*h,f=s*c,m=s*h,g=a*h,v=o*l,y=o*c,_=o*h,x=n.x,b=n.y,w=n.z;return i[0]=(1-(f+g))*x,i[1]=(d+_)*x,i[2]=(p-y)*x,i[3]=0,i[4]=(d-_)*b,i[5]=(1-(u+g))*b,i[6]=(m+v)*b,i[7]=0,i[8]=(p+y)*w,i[9]=(m-v)*w,i[10]=(1-(u+f))*w,i[11]=0,i[12]=e.x,i[13]=e.y,i[14]=e.z,i[15]=1,this}decompose(e,t,n){const i=this.elements;let r=Ui.set(i[0],i[1],i[2]).length();const s=Ui.set(i[4],i[5],i[6]).length(),a=Ui.set(i[8],i[9],i[10]).length();this.determinant()<0&&(r=-r),e.x=i[12],e.y=i[13],e.z=i[14],zi.copy(this);const o=1/r,l=1/s,c=1/a;return zi.elements[0]*=o,zi.elements[1]*=o,zi.elements[2]*=o,zi.elements[4]*=l,zi.elements[5]*=l,zi.elements[6]*=l,zi.elements[8]*=c,zi.elements[9]*=c,zi.elements[10]*=c,t.setFromRotationMatrix(zi),n.x=r,n.y=s,n.z=a,this}makePerspective(e,t,n,i,r,s){void 0===s&&console.warn("THREE.Matrix4: .makePerspective() has been redefined and has a new signature. Please check the docs.");const a=this.elements,o=2*r/(t-e),l=2*r/(n-i),c=(t+e)/(t-e),h=(n+i)/(n-i),u=-(s+r)/(s-r),d=-2*s*r/(s-r);return a[0]=o,a[4]=0,a[8]=c,a[12]=0,a[1]=0,a[5]=l,a[9]=h,a[13]=0,a[2]=0,a[6]=0,a[10]=u,a[14]=d,a[3]=0,a[7]=0,a[11]=-1,a[15]=0,this}makeOrthographic(e,t,n,i,r,s){const a=this.elements,o=1/(t-e),l=1/(n-i),c=1/(s-r),h=(t+e)*o,u=(n+i)*l,d=(s+r)*c;return a[0]=2*o,a[4]=0,a[8]=0,a[12]=-h,a[1]=0,a[5]=2*l,a[9]=0,a[13]=-u,a[2]=0,a[6]=0,a[10]=-2*c,a[14]=-d,a[3]=0,a[7]=0,a[11]=0,a[15]=1,this}equals(e){const t=this.elements,n=e.elements;for(let e=0;e<16;e++)if(t[e]!==n[e])return!1;return!0}fromArray(e,t=0){for(let n=0;n<16;n++)this.elements[n]=e[n+t];return this}toArray(e=[],t=0){const n=this.elements;return e[t]=n[0],e[t+1]=n[1],e[t+2]=n[2],e[t+3]=n[3],e[t+4]=n[4],e[t+5]=n[5],e[t+6]=n[6],e[t+7]=n[7],e[t+8]=n[8],e[t+9]=n[9],e[t+10]=n[10],e[t+11]=n[11],e[t+12]=n[12],e[t+13]=n[13],e[t+14]=n[14],e[t+15]=n[15],e}}Fi.prototype.isMatrix4=!0;const Ui=new oi,zi=new Fi,Hi=new oi(0,0,0),Gi=new oi(1,1,1),Vi=new oi,Wi=new oi,ji=new oi,qi=new Fi,Xi=new ai;class Yi{constructor(e=0,t=0,n=0,i=Yi.DefaultOrder){this._x=e,this._y=t,this._z=n,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,t,n,i=this._order){return this._x=e,this._y=t,this._z=n,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,t=this._order,n=!0){const i=e.elements,r=i[0],s=i[4],a=i[8],o=i[1],l=i[5],c=i[9],h=i[2],u=i[6],d=i[10];switch(t){case"XYZ":this._y=Math.asin(Gn(a,-1,1)),Math.abs(a)<.9999999?(this._x=Math.atan2(-c,d),this._z=Math.atan2(-s,r)):(this._x=Math.atan2(u,l),this._z=0);break;case"YXZ":this._x=Math.asin(-Gn(c,-1,1)),Math.abs(c)<.9999999?(this._y=Math.atan2(a,d),this._z=Math.atan2(o,l)):(this._y=Math.atan2(-h,r),this._z=0);break;case"ZXY":this._x=Math.asin(Gn(u,-1,1)),Math.abs(u)<.9999999?(this._y=Math.atan2(-h,d),this._z=Math.atan2(-s,l)):(this._y=0,this._z=Math.atan2(o,r));break;case"ZYX":this._y=Math.asin(-Gn(h,-1,1)),Math.abs(h)<.9999999?(this._x=Math.atan2(u,d),this._z=Math.atan2(o,r)):(this._x=0,this._z=Math.atan2(-s,l));break;case"YZX":this._z=Math.asin(Gn(o,-1,1)),Math.abs(o)<.9999999?(this._x=Math.atan2(-c,l),this._y=Math.atan2(-h,r)):(this._x=0,this._y=Math.atan2(a,d));break;case"XZY":this._z=Math.asin(-Gn(s,-1,1)),Math.abs(s)<.9999999?(this._x=Math.atan2(u,l),this._y=Math.atan2(a,r)):(this._x=Math.atan2(-c,d),this._y=0);break;default:console.warn("THREE.Euler: .setFromRotationMatrix() encountered an unknown order: "+t)}return this._order=t,!0===n&&this._onChangeCallback(),this}setFromQuaternion(e,t,n){return qi.makeRotationFromQuaternion(e),this.setFromRotationMatrix(qi,t,n)}setFromVector3(e,t=this._order){return this.set(e.x,e.y,e.z,t)}reorder(e){return Xi.setFromEuler(this),this.setFromQuaternion(Xi,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],void 0!==e[3]&&(this._order=e[3]),this._onChangeCallback(),this}toArray(e=[],t=0){return e[t]=this._x,e[t+1]=this._y,e[t+2]=this._z,e[t+3]=this._order,e}toVector3(e){return e?e.set(this._x,this._y,this._z):new oi(this._x,this._y,this._z)}_onChange(e){return this._onChangeCallback=e,this}_onChangeCallback(){}}Yi.prototype.isEuler=!0,Yi.DefaultOrder="XYZ",Yi.RotationOrders=["XYZ","YZX","ZXY","XZY","YXZ","ZYX"];class Ji{constructor(){this.mask=1}set(e){this.mask=1<1){for(let e=0;e1){for(let e=0;e0){i.children=[];for(let t=0;t0){i.animations=[];for(let t=0;t0&&(n.geometries=t),i.length>0&&(n.materials=i),r.length>0&&(n.textures=r),a.length>0&&(n.images=a),o.length>0&&(n.shapes=o),l.length>0&&(n.skeletons=l),c.length>0&&(n.animations=c)}return n.object=i,n;function s(e){const t=[];for(const n in e){const i=e[n];delete i.metadata,t.push(i)}return t}}clone(e){return(new this.constructor).copy(this,e)}copy(e,t=!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.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.userData=JSON.parse(JSON.stringify(e.userData)),!0===t)for(let t=0;t0?i.multiplyScalar(1/Math.sqrt(r)):i.set(0,0,0)}static getBarycoord(e,t,n,i,r){hr.subVectors(i,t),ur.subVectors(n,t),dr.subVectors(e,t);const s=hr.dot(hr),a=hr.dot(ur),o=hr.dot(dr),l=ur.dot(ur),c=ur.dot(dr),h=s*l-a*a;if(0===h)return r.set(-2,-1,-1);const u=1/h,d=(l*o-a*c)*u,p=(s*c-a*o)*u;return r.set(1-d-p,p,d)}static containsPoint(e,t,n,i){return this.getBarycoord(e,t,n,i,pr),pr.x>=0&&pr.y>=0&&pr.x+pr.y<=1}static getUV(e,t,n,i,r,s,a,o){return this.getBarycoord(e,t,n,i,pr),o.set(0,0),o.addScaledVector(r,pr.x),o.addScaledVector(s,pr.y),o.addScaledVector(a,pr.z),o}static isFrontFacing(e,t,n,i){return hr.subVectors(n,t),ur.subVectors(e,t),hr.cross(ur).dot(i)<0}set(e,t,n){return this.a.copy(e),this.b.copy(t),this.c.copy(n),this}setFromPointsAndIndices(e,t,n,i){return this.a.copy(e[t]),this.b.copy(e[n]),this.c.copy(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 hr.subVectors(this.c,this.b),ur.subVectors(this.a,this.b),.5*hr.cross(ur).length()}getMidpoint(e){return e.addVectors(this.a,this.b).add(this.c).multiplyScalar(1/3)}getNormal(e){return xr.getNormal(this.a,this.b,this.c,e)}getPlane(e){return e.setFromCoplanarPoints(this.a,this.b,this.c)}getBarycoord(e,t){return xr.getBarycoord(e,this.a,this.b,this.c,t)}getUV(e,t,n,i,r){return xr.getUV(e,this.a,this.b,this.c,t,n,i,r)}containsPoint(e){return xr.containsPoint(e,this.a,this.b,this.c)}isFrontFacing(e){return xr.isFrontFacing(this.a,this.b,this.c,e)}intersectsBox(e){return e.intersectsTriangle(this)}closestPointToPoint(e,t){const n=this.a,i=this.b,r=this.c;let s,a;fr.subVectors(i,n),mr.subVectors(r,n),vr.subVectors(e,n);const o=fr.dot(vr),l=mr.dot(vr);if(o<=0&&l<=0)return t.copy(n);yr.subVectors(e,i);const c=fr.dot(yr),h=mr.dot(yr);if(c>=0&&h<=c)return t.copy(i);const u=o*h-c*l;if(u<=0&&o>=0&&c<=0)return s=o/(o-c),t.copy(n).addScaledVector(fr,s);_r.subVectors(e,r);const d=fr.dot(_r),p=mr.dot(_r);if(p>=0&&d<=p)return t.copy(r);const f=d*l-o*p;if(f<=0&&l>=0&&p<=0)return a=l/(l-p),t.copy(n).addScaledVector(mr,a);const m=c*p-d*h;if(m<=0&&h-c>=0&&d-p>=0)return gr.subVectors(r,i),a=(h-c)/(h-c+(d-p)),t.copy(i).addScaledVector(gr,a);const g=1/(m+f+u);return s=f*g,a=u*g,t.copy(n).addScaledVector(fr,s).addScaledVector(mr,a)}equals(e){return e.a.equals(this.a)&&e.b.equals(this.b)&&e.c.equals(this.c)}}let br=0;class wr extends On{constructor(){super(),Object.defineProperty(this,"id",{value:br++}),this.uuid=Hn(),this.name="",this.type="Material",this.fog=!0,this.blending=x,this.side=f,this.vertexColors=!1,this.opacity=1,this.format=Fe,this.transparent=!1,this.blendSrc=I,this.blendDst=D,this.blendEquation=E,this.blendSrcAlpha=null,this.blendDstAlpha=null,this.blendEquationAlpha=null,this.depthFunc=W,this.depthTest=!0,this.depthWrite=!0,this.stencilWriteMask=255,this.stencilFunc=Tn,this.stencilRef=0,this.stencilFuncMask=255,this.stencilFail=hn,this.stencilZFail=hn,this.stencilZPass=hn,this.stencilWrite=!1,this.clippingPlanes=null,this.clipIntersection=!1,this.clipShadows=!1,this.shadowSide=null,this.colorWrite=!0,this.precision=null,this.polygonOffset=!1,this.polygonOffsetFactor=0,this.polygonOffsetUnits=0,this.dithering=!1,this.alphaToCoverage=!1,this.premultipliedAlpha=!1,this.visible=!0,this.toneMapped=!0,this.userData={},this.version=0,this._alphaTest=0}get alphaTest(){return this._alphaTest}set alphaTest(e){this._alphaTest>0!=e>0&&this.version++,this._alphaTest=e}onBuild(){}onBeforeCompile(){}customProgramCacheKey(){return this.onBeforeCompile.toString()}setValues(e){if(void 0!==e)for(const t in e){const n=e[t];if(void 0===n){console.warn("THREE.Material: '"+t+"' parameter is undefined.");continue}if("shading"===t){console.warn("THREE."+this.type+": .shading has been removed. Use the boolean .flatShading instead."),this.flatShading=n===v;continue}const i=this[t];void 0!==i?i&&i.isColor?i.set(n):i&&i.isVector3&&n&&n.isVector3?i.copy(n):this[t]=n:console.warn("THREE."+this.type+": '"+t+"' is not a property of this material.")}}toJSON(e){const t=void 0===e||"string"==typeof e;t&&(e={textures:{},images:{}});const n={metadata:{version:4.5,type:"Material",generator:"Material.toJSON"}};function i(e){const t=[];for(const n in e){const i=e[n];delete i.metadata,t.push(i)}return t}if(n.uuid=this.uuid,n.type=this.type,""!==this.name&&(n.name=this.name),this.color&&this.color.isColor&&(n.color=this.color.getHex()),void 0!==this.roughness&&(n.roughness=this.roughness),void 0!==this.metalness&&(n.metalness=this.metalness),this.sheenTint&&this.sheenTint.isColor&&(n.sheenTint=this.sheenTint.getHex()),this.emissive&&this.emissive.isColor&&(n.emissive=this.emissive.getHex()),this.emissiveIntensity&&1!==this.emissiveIntensity&&(n.emissiveIntensity=this.emissiveIntensity),this.specular&&this.specular.isColor&&(n.specular=this.specular.getHex()),void 0!==this.specularIntensity&&(n.specularIntensity=this.specularIntensity),this.specularTint&&this.specularTint.isColor&&(n.specularTint=this.specularTint.getHex()),void 0!==this.shininess&&(n.shininess=this.shininess),void 0!==this.clearcoat&&(n.clearcoat=this.clearcoat),void 0!==this.clearcoatRoughness&&(n.clearcoatRoughness=this.clearcoatRoughness),this.clearcoatMap&&this.clearcoatMap.isTexture&&(n.clearcoatMap=this.clearcoatMap.toJSON(e).uuid),this.clearcoatRoughnessMap&&this.clearcoatRoughnessMap.isTexture&&(n.clearcoatRoughnessMap=this.clearcoatRoughnessMap.toJSON(e).uuid),this.clearcoatNormalMap&&this.clearcoatNormalMap.isTexture&&(n.clearcoatNormalMap=this.clearcoatNormalMap.toJSON(e).uuid,n.clearcoatNormalScale=this.clearcoatNormalScale.toArray()),this.map&&this.map.isTexture&&(n.map=this.map.toJSON(e).uuid),this.matcap&&this.matcap.isTexture&&(n.matcap=this.matcap.toJSON(e).uuid),this.alphaMap&&this.alphaMap.isTexture&&(n.alphaMap=this.alphaMap.toJSON(e).uuid),this.lightMap&&this.lightMap.isTexture&&(n.lightMap=this.lightMap.toJSON(e).uuid,n.lightMapIntensity=this.lightMapIntensity),this.aoMap&&this.aoMap.isTexture&&(n.aoMap=this.aoMap.toJSON(e).uuid,n.aoMapIntensity=this.aoMapIntensity),this.bumpMap&&this.bumpMap.isTexture&&(n.bumpMap=this.bumpMap.toJSON(e).uuid,n.bumpScale=this.bumpScale),this.normalMap&&this.normalMap.isTexture&&(n.normalMap=this.normalMap.toJSON(e).uuid,n.normalMapType=this.normalMapType,n.normalScale=this.normalScale.toArray()),this.displacementMap&&this.displacementMap.isTexture&&(n.displacementMap=this.displacementMap.toJSON(e).uuid,n.displacementScale=this.displacementScale,n.displacementBias=this.displacementBias),this.roughnessMap&&this.roughnessMap.isTexture&&(n.roughnessMap=this.roughnessMap.toJSON(e).uuid),this.metalnessMap&&this.metalnessMap.isTexture&&(n.metalnessMap=this.metalnessMap.toJSON(e).uuid),this.emissiveMap&&this.emissiveMap.isTexture&&(n.emissiveMap=this.emissiveMap.toJSON(e).uuid),this.specularMap&&this.specularMap.isTexture&&(n.specularMap=this.specularMap.toJSON(e).uuid),this.specularIntensityMap&&this.specularIntensityMap.isTexture&&(n.specularIntensityMap=this.specularIntensityMap.toJSON(e).uuid),this.specularTintMap&&this.specularTintMap.isTexture&&(n.specularTintMap=this.specularTintMap.toJSON(e).uuid),this.envMap&&this.envMap.isTexture&&(n.envMap=this.envMap.toJSON(e).uuid,void 0!==this.combine&&(n.combine=this.combine)),void 0!==this.envMapIntensity&&(n.envMapIntensity=this.envMapIntensity),void 0!==this.reflectivity&&(n.reflectivity=this.reflectivity),void 0!==this.refractionRatio&&(n.refractionRatio=this.refractionRatio),this.gradientMap&&this.gradientMap.isTexture&&(n.gradientMap=this.gradientMap.toJSON(e).uuid),void 0!==this.transmission&&(n.transmission=this.transmission),this.transmissionMap&&this.transmissionMap.isTexture&&(n.transmissionMap=this.transmissionMap.toJSON(e).uuid),void 0!==this.thickness&&(n.thickness=this.thickness),this.thicknessMap&&this.thicknessMap.isTexture&&(n.thicknessMap=this.thicknessMap.toJSON(e).uuid),void 0!==this.attenuationDistance&&(n.attenuationDistance=this.attenuationDistance),void 0!==this.attenuationTint&&(n.attenuationTint=this.attenuationTint.getHex()),void 0!==this.size&&(n.size=this.size),null!==this.shadowSide&&(n.shadowSide=this.shadowSide),void 0!==this.sizeAttenuation&&(n.sizeAttenuation=this.sizeAttenuation),this.blending!==x&&(n.blending=this.blending),this.side!==f&&(n.side=this.side),this.vertexColors&&(n.vertexColors=!0),this.opacity<1&&(n.opacity=this.opacity),this.format!==Fe&&(n.format=this.format),!0===this.transparent&&(n.transparent=this.transparent),n.depthFunc=this.depthFunc,n.depthTest=this.depthTest,n.depthWrite=this.depthWrite,n.colorWrite=this.colorWrite,n.stencilWrite=this.stencilWrite,n.stencilWriteMask=this.stencilWriteMask,n.stencilFunc=this.stencilFunc,n.stencilRef=this.stencilRef,n.stencilFuncMask=this.stencilFuncMask,n.stencilFail=this.stencilFail,n.stencilZFail=this.stencilZFail,n.stencilZPass=this.stencilZPass,this.rotation&&0!==this.rotation&&(n.rotation=this.rotation),!0===this.polygonOffset&&(n.polygonOffset=!0),0!==this.polygonOffsetFactor&&(n.polygonOffsetFactor=this.polygonOffsetFactor),0!==this.polygonOffsetUnits&&(n.polygonOffsetUnits=this.polygonOffsetUnits),this.linewidth&&1!==this.linewidth&&(n.linewidth=this.linewidth),void 0!==this.dashSize&&(n.dashSize=this.dashSize),void 0!==this.gapSize&&(n.gapSize=this.gapSize),void 0!==this.scale&&(n.scale=this.scale),!0===this.dithering&&(n.dithering=!0),this.alphaTest>0&&(n.alphaTest=this.alphaTest),!0===this.alphaToCoverage&&(n.alphaToCoverage=this.alphaToCoverage),!0===this.premultipliedAlpha&&(n.premultipliedAlpha=this.premultipliedAlpha),!0===this.wireframe&&(n.wireframe=this.wireframe),this.wireframeLinewidth>1&&(n.wireframeLinewidth=this.wireframeLinewidth),"round"!==this.wireframeLinecap&&(n.wireframeLinecap=this.wireframeLinecap),"round"!==this.wireframeLinejoin&&(n.wireframeLinejoin=this.wireframeLinejoin),!0===this.flatShading&&(n.flatShading=this.flatShading),!1===this.visible&&(n.visible=!1),!1===this.toneMapped&&(n.toneMapped=!1),"{}"!==JSON.stringify(this.userData)&&(n.userData=this.userData),t){const t=i(e.textures),r=i(e.images);t.length>0&&(n.textures=t),r.length>0&&(n.images=r)}return n}clone(){return(new this.constructor).copy(this)}copy(e){this.name=e.name,this.fog=e.fog,this.blending=e.blending,this.side=e.side,this.vertexColors=e.vertexColors,this.opacity=e.opacity,this.format=e.format,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.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 t=e.clippingPlanes;let n=null;if(null!==t){const e=t.length;n=new Array(e);for(let i=0;i!==e;++i)n[i]=t[i].clone()}return this.clippingPlanes=n,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.alphaToCoverage=e.alphaToCoverage,this.premultipliedAlpha=e.premultipliedAlpha,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){!0===e&&this.version++}}wr.prototype.isMaterial=!0;const Mr={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},Tr={h:0,s:0,l:0},Er={h:0,s:0,l:0};function Sr(e,t,n){return n<0&&(n+=1),n>1&&(n-=1),n<1/6?e+6*(t-e)*n:n<.5?t:n<2/3?e+6*(t-e)*(2/3-n):e}function Ar(e){return e<.04045?.0773993808*e:Math.pow(.9478672986*e+.0521327014,2.4)}function Lr(e){return e<.0031308?12.92*e:1.055*Math.pow(e,.41666)-.055}class Cr{constructor(e,t,n){return void 0===t&&void 0===n?this.set(e):this.setRGB(e,t,n)}set(e){return e&&e.isColor?this.copy(e):"number"==typeof e?this.setHex(e):"string"==typeof e&&this.setStyle(e),this}setScalar(e){return this.r=e,this.g=e,this.b=e,this}setHex(e){return e=Math.floor(e),this.r=(e>>16&255)/255,this.g=(e>>8&255)/255,this.b=(255&e)/255,this}setRGB(e,t,n){return this.r=e,this.g=t,this.b=n,this}setHSL(e,t,n){if(e=Vn(e,1),t=Gn(t,0,1),n=Gn(n,0,1),0===t)this.r=this.g=this.b=n;else{const i=n<=.5?n*(1+t):n+t-n*t,r=2*n-i;this.r=Sr(r,i,e+1/3),this.g=Sr(r,i,e),this.b=Sr(r,i,e-1/3)}return this}setStyle(e){function t(t){void 0!==t&&parseFloat(t)<1&&console.warn("THREE.Color: Alpha component of "+e+" will be ignored.")}let n;if(n=/^((?:rgb|hsl)a?)\\(([^\\)]*)\\)/.exec(e)){let e;const i=n[1],r=n[2];switch(i){case"rgb":case"rgba":if(e=/^\\s*(\\d+)\\s*,\\s*(\\d+)\\s*,\\s*(\\d+)\\s*(?:,\\s*(\\d*\\.?\\d+)\\s*)?$/.exec(r))return this.r=Math.min(255,parseInt(e[1],10))/255,this.g=Math.min(255,parseInt(e[2],10))/255,this.b=Math.min(255,parseInt(e[3],10))/255,t(e[4]),this;if(e=/^\\s*(\\d+)\\%\\s*,\\s*(\\d+)\\%\\s*,\\s*(\\d+)\\%\\s*(?:,\\s*(\\d*\\.?\\d+)\\s*)?$/.exec(r))return this.r=Math.min(100,parseInt(e[1],10))/100,this.g=Math.min(100,parseInt(e[2],10))/100,this.b=Math.min(100,parseInt(e[3],10))/100,t(e[4]),this;break;case"hsl":case"hsla":if(e=/^\\s*(\\d*\\.?\\d+)\\s*,\\s*(\\d+)\\%\\s*,\\s*(\\d+)\\%\\s*(?:,\\s*(\\d*\\.?\\d+)\\s*)?$/.exec(r)){const n=parseFloat(e[1])/360,i=parseInt(e[2],10)/100,r=parseInt(e[3],10)/100;return t(e[4]),this.setHSL(n,i,r)}}}else if(n=/^\\#([A-Fa-f\\d]+)$/.exec(e)){const e=n[1],t=e.length;if(3===t)return this.r=parseInt(e.charAt(0)+e.charAt(0),16)/255,this.g=parseInt(e.charAt(1)+e.charAt(1),16)/255,this.b=parseInt(e.charAt(2)+e.charAt(2),16)/255,this;if(6===t)return this.r=parseInt(e.charAt(0)+e.charAt(1),16)/255,this.g=parseInt(e.charAt(2)+e.charAt(3),16)/255,this.b=parseInt(e.charAt(4)+e.charAt(5),16)/255,this}return e&&e.length>0?this.setColorName(e):this}setColorName(e){const t=Mr[e.toLowerCase()];return void 0!==t?this.setHex(t):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}copyGammaToLinear(e,t=2){return this.r=Math.pow(e.r,t),this.g=Math.pow(e.g,t),this.b=Math.pow(e.b,t),this}copyLinearToGamma(e,t=2){const n=t>0?1/t:1;return this.r=Math.pow(e.r,n),this.g=Math.pow(e.g,n),this.b=Math.pow(e.b,n),this}convertGammaToLinear(e){return this.copyGammaToLinear(this,e),this}convertLinearToGamma(e){return this.copyLinearToGamma(this,e),this}copySRGBToLinear(e){return this.r=Ar(e.r),this.g=Ar(e.g),this.b=Ar(e.b),this}copyLinearToSRGB(e){return this.r=Lr(e.r),this.g=Lr(e.g),this.b=Lr(e.b),this}convertSRGBToLinear(){return this.copySRGBToLinear(this),this}convertLinearToSRGB(){return this.copyLinearToSRGB(this),this}getHex(){return 255*this.r<<16^255*this.g<<8^255*this.b<<0}getHexString(){return("000000"+this.getHex().toString(16)).slice(-6)}getHSL(e){const t=this.r,n=this.g,i=this.b,r=Math.max(t,n,i),s=Math.min(t,n,i);let a,o;const l=(s+r)/2;if(s===r)a=0,o=0;else{const e=r-s;switch(o=l<=.5?e/(r+s):e/(2-r-s),r){case t:a=(n-i)/e+(nt&&(t=e[n]);return t}const jr={Int8Array,Uint8Array,Uint8ClampedArray,Int16Array,Uint16Array,Int32Array,Uint32Array,Float32Array,Float64Array};function qr(e,t){return new jr[e](t)}let Xr=0;const Yr=new Fi,Jr=new cr,Zr=new oi,Kr=new hi,Qr=new hi,$r=new oi;class es extends On{constructor(){super(),Object.defineProperty(this,"id",{value:Xr++}),this.uuid=Hn(),this.name="",this.type="BufferGeometry",this.index=null,this.attributes={},this.morphAttributes={},this.morphTargetsRelative=!1,this.groups=[],this.boundingBox=null,this.boundingSphere=null,this.drawRange={start:0,count:1/0},this.userData={}}getIndex(){return this.index}setIndex(e){return Array.isArray(e)?this.index=new(Wr(e)>65535?zr:Fr)(e,1):this.index=e,this}getAttribute(e){return this.attributes[e]}setAttribute(e,t){return this.attributes[e]=t,this}deleteAttribute(e){return delete this.attributes[e],this}hasAttribute(e){return void 0!==this.attributes[e]}addGroup(e,t,n=0){this.groups.push({start:e,count:t,materialIndex:n})}clearGroups(){this.groups=[]}setDrawRange(e,t){this.drawRange.start=e,this.drawRange.count=t}applyMatrix4(e){const t=this.attributes.position;void 0!==t&&(t.applyMatrix4(e),t.needsUpdate=!0);const n=this.attributes.normal;if(void 0!==n){const t=(new Zn).getNormalMatrix(e);n.applyNormalMatrix(t),n.needsUpdate=!0}const i=this.attributes.tangent;return void 0!==i&&(i.transformDirection(e),i.needsUpdate=!0),null!==this.boundingBox&&this.computeBoundingBox(),null!==this.boundingSphere&&this.computeBoundingSphere(),this}applyQuaternion(e){return Yr.makeRotationFromQuaternion(e),this.applyMatrix4(Yr),this}rotateX(e){return Yr.makeRotationX(e),this.applyMatrix4(Yr),this}rotateY(e){return Yr.makeRotationY(e),this.applyMatrix4(Yr),this}rotateZ(e){return Yr.makeRotationZ(e),this.applyMatrix4(Yr),this}translate(e,t,n){return Yr.makeTranslation(e,t,n),this.applyMatrix4(Yr),this}scale(e,t,n){return Yr.makeScale(e,t,n),this.applyMatrix4(Yr),this}lookAt(e){return Jr.lookAt(e),Jr.updateMatrix(),this.applyMatrix4(Jr.matrix),this}center(){return this.computeBoundingBox(),this.boundingBox.getCenter(Zr).negate(),this.translate(Zr.x,Zr.y,Zr.z),this}setFromPoints(e){const t=[];for(let n=0,i=e.length;n0&&(e.userData=this.userData),void 0!==this.parameters){const t=this.parameters;for(const n in t)void 0!==t[n]&&(e[n]=t[n]);return e}e.data={attributes:{}};const t=this.index;null!==t&&(e.data.index={type:t.array.constructor.name,array:Array.prototype.slice.call(t.array)});const n=this.attributes;for(const t in n){const i=n[t];e.data.attributes[t]=i.toJSON(e.data)}const i={};let r=!1;for(const t in this.morphAttributes){const n=this.morphAttributes[t],s=[];for(let t=0,i=n.length;t0&&(i[t]=s,r=!0)}r&&(e.data.morphAttributes=i,e.data.morphTargetsRelative=this.morphTargetsRelative);const s=this.groups;s.length>0&&(e.data.groups=JSON.parse(JSON.stringify(s)));const a=this.boundingSphere;return null!==a&&(e.data.boundingSphere={center:a.center.toArray(),radius:a.radius}),e}clone(){return(new es).copy(this)}copy(e){this.index=null,this.attributes={},this.morphAttributes={},this.groups=[],this.boundingBox=null,this.boundingSphere=null;const t={};this.name=e.name;const n=e.index;null!==n&&this.setIndex(n.clone(t));const i=e.attributes;for(const e in i){const n=i[e];this.setAttribute(e,n.clone(t))}const r=e.morphAttributes;for(const e in r){const n=[],i=r[e];for(let e=0,r=i.length;e0){const e=t[n[0]];if(void 0!==e){this.morphTargetInfluences=[],this.morphTargetDictionary={};for(let t=0,n=e.length;t0&&console.error("THREE.Mesh.updateMorphTargets() no longer supports THREE.Geometry. Use THREE.BufferGeometry instead.")}}raycast(e,t){const n=this.geometry,i=this.material,r=this.matrixWorld;if(void 0===i)return;if(null===n.boundingSphere&&n.computeBoundingSphere(),is.copy(n.boundingSphere),is.applyMatrix4(r),!1===e.ray.intersectsSphere(is))return;if(ts.copy(r).invert(),ns.copy(e.ray).applyMatrix4(ts),null!==n.boundingBox&&!1===ns.intersectsBox(n.boundingBox))return;let s;if(n.isBufferGeometry){const r=n.index,a=n.attributes.position,o=n.morphAttributes.position,l=n.morphTargetsRelative,c=n.attributes.uv,h=n.attributes.uv2,u=n.groups,d=n.drawRange;if(null!==r)if(Array.isArray(i))for(let n=0,p=u.length;nn.far?null:{distance:c,point:vs.clone(),object:e}}(e,t,n,i,rs,ss,as,gs);if(p){o&&(ps.fromBufferAttribute(o,c),fs.fromBufferAttribute(o,h),ms.fromBufferAttribute(o,u),p.uv=xr.getUV(gs,rs,ss,as,ps,fs,ms,new Jn)),l&&(ps.fromBufferAttribute(l,c),fs.fromBufferAttribute(l,h),ms.fromBufferAttribute(l,u),p.uv2=xr.getUV(gs,rs,ss,as,ps,fs,ms,new Jn));const e={a:c,b:h,c:u,normal:new oi,materialIndex:0};xr.getNormal(rs,ss,as,e.normal),p.face=e}return p}ys.prototype.isMesh=!0;class xs extends es{constructor(e=1,t=1,n=1,i=1,r=1,s=1){super(),this.type="BoxGeometry",this.parameters={width:e,height:t,depth:n,widthSegments:i,heightSegments:r,depthSegments:s};const a=this;i=Math.floor(i),r=Math.floor(r),s=Math.floor(s);const o=[],l=[],c=[],h=[];let u=0,d=0;function p(e,t,n,i,r,s,p,f,m,g,v){const y=s/m,_=p/g,x=s/2,b=p/2,w=f/2,M=m+1,T=g+1;let E=0,S=0;const A=new oi;for(let s=0;s0?1:-1,c.push(A.x,A.y,A.z),h.push(o/m),h.push(1-s/g),E+=1}}for(let e=0;e0&&(t.defines=this.defines),t.vertexShader=this.vertexShader,t.fragmentShader=this.fragmentShader;const n={};for(const e in this.extensions)!0===this.extensions[e]&&(n[e]=!0);return Object.keys(n).length>0&&(t.extensions=n),t}}Ts.prototype.isShaderMaterial=!0;class Es extends cr{constructor(){super(),this.type="Camera",this.matrixWorldInverse=new Fi,this.projectionMatrix=new Fi,this.projectionMatrixInverse=new Fi}copy(e,t){return super.copy(e,t),this.matrixWorldInverse.copy(e.matrixWorldInverse),this.projectionMatrix.copy(e.projectionMatrix),this.projectionMatrixInverse.copy(e.projectionMatrixInverse),this}getWorldDirection(e){this.updateWorldMatrix(!0,!1);const t=this.matrixWorld.elements;return e.set(-t[8],-t[9],-t[10]).normalize()}updateMatrixWorld(e){super.updateMatrixWorld(e),this.matrixWorldInverse.copy(this.matrixWorld).invert()}updateWorldMatrix(e,t){super.updateWorldMatrix(e,t),this.matrixWorldInverse.copy(this.matrixWorld).invert()}clone(){return(new this.constructor).copy(this)}}Es.prototype.isCamera=!0;class Ss extends Es{constructor(e=50,t=1,n=.1,i=2e3){super(),this.type="PerspectiveCamera",this.fov=e,this.zoom=1,this.near=n,this.far=i,this.focus=10,this.aspect=t,this.view=null,this.filmGauge=35,this.filmOffset=0,this.updateProjectionMatrix()}copy(e,t){return super.copy(e,t),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=null===e.view?null:Object.assign({},e.view),this.filmGauge=e.filmGauge,this.filmOffset=e.filmOffset,this}setFocalLength(e){const t=.5*this.getFilmHeight()/e;this.fov=2*zn*Math.atan(t),this.updateProjectionMatrix()}getFocalLength(){const e=Math.tan(.5*Un*this.fov);return.5*this.getFilmHeight()/e}getEffectiveFOV(){return 2*zn*Math.atan(Math.tan(.5*Un*this.fov)/this.zoom)}getFilmWidth(){return this.filmGauge*Math.min(this.aspect,1)}getFilmHeight(){return this.filmGauge/Math.max(this.aspect,1)}setViewOffset(e,t,n,i,r,s){this.aspect=e/t,null===this.view&&(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=t,this.view.offsetX=n,this.view.offsetY=i,this.view.width=r,this.view.height=s,this.updateProjectionMatrix()}clearViewOffset(){null!==this.view&&(this.view.enabled=!1),this.updateProjectionMatrix()}updateProjectionMatrix(){const e=this.near;let t=e*Math.tan(.5*Un*this.fov)/this.zoom,n=2*t,i=this.aspect*n,r=-.5*i;const s=this.view;if(null!==this.view&&this.view.enabled){const e=s.fullWidth,a=s.fullHeight;r+=s.offsetX*i/e,t-=s.offsetY*n/a,i*=s.width/e,n*=s.height/a}const a=this.filmOffset;0!==a&&(r+=e*a/this.getFilmWidth()),this.projectionMatrix.makePerspective(r,r+i,t,t-n,e,this.far),this.projectionMatrixInverse.copy(this.projectionMatrix).invert()}toJSON(e){const t=super.toJSON(e);return t.object.fov=this.fov,t.object.zoom=this.zoom,t.object.near=this.near,t.object.far=this.far,t.object.focus=this.focus,t.object.aspect=this.aspect,null!==this.view&&(t.object.view=Object.assign({},this.view)),t.object.filmGauge=this.filmGauge,t.object.filmOffset=this.filmOffset,t}}Ss.prototype.isPerspectiveCamera=!0;const As=90;class Ls extends cr{constructor(e,t,n){if(super(),this.type="CubeCamera",!0!==n.isWebGLCubeRenderTarget)return void console.error("THREE.CubeCamera: The constructor now expects an instance of WebGLCubeRenderTarget as third parameter.");this.renderTarget=n;const i=new Ss(As,1,e,t);i.layers=this.layers,i.up.set(0,-1,0),i.lookAt(new oi(1,0,0)),this.add(i);const r=new Ss(As,1,e,t);r.layers=this.layers,r.up.set(0,-1,0),r.lookAt(new oi(-1,0,0)),this.add(r);const s=new Ss(As,1,e,t);s.layers=this.layers,s.up.set(0,0,1),s.lookAt(new oi(0,1,0)),this.add(s);const a=new Ss(As,1,e,t);a.layers=this.layers,a.up.set(0,0,-1),a.lookAt(new oi(0,-1,0)),this.add(a);const o=new Ss(As,1,e,t);o.layers=this.layers,o.up.set(0,-1,0),o.lookAt(new oi(0,0,1)),this.add(o);const l=new Ss(As,1,e,t);l.layers=this.layers,l.up.set(0,-1,0),l.lookAt(new oi(0,0,-1)),this.add(l)}update(e,t){null===this.parent&&this.updateMatrixWorld();const n=this.renderTarget,[i,r,s,a,o,l]=this.children,c=e.xr.enabled,h=e.getRenderTarget();e.xr.enabled=!1;const u=n.texture.generateMipmaps;n.texture.generateMipmaps=!1,e.setRenderTarget(n,0),e.render(t,i),e.setRenderTarget(n,1),e.render(t,r),e.setRenderTarget(n,2),e.render(t,s),e.setRenderTarget(n,3),e.render(t,a),e.setRenderTarget(n,4),e.render(t,o),n.texture.generateMipmaps=u,e.setRenderTarget(n,5),e.render(t,l),e.setRenderTarget(h),e.xr.enabled=c}}class Cs extends ei{constructor(e,t,n,i,r,s,a,o,l,c){super(e=void 0!==e?e:[],t=void 0!==t?t:se,n,i,r,s,a=void 0!==a?a:Be,o,l,c),this.flipY=!1}get images(){return this.image}set images(e){this.image=e}}Cs.prototype.isCubeTexture=!0;class Rs extends ii{constructor(e,t,n){Number.isInteger(t)&&(console.warn("THREE.WebGLCubeRenderTarget: constructor signature is now WebGLCubeRenderTarget( size, options )"),t=n),super(e,e,t),t=t||{},this.texture=new Cs(void 0,t.mapping,t.wrapS,t.wrapT,t.magFilter,t.minFilter,t.format,t.type,t.anisotropy,t.encoding),this.texture.isRenderTargetTexture=!0,this.texture.generateMipmaps=void 0!==t.generateMipmaps&&t.generateMipmaps,this.texture.minFilter=void 0!==t.minFilter?t.minFilter:_e,this.texture._needsFlipEnvMap=!1}fromEquirectangularTexture(e,t){this.texture.type=t.type,this.texture.format=Fe,this.texture.encoding=t.encoding,this.texture.generateMipmaps=t.generateMipmaps,this.texture.minFilter=t.minFilter,this.texture.magFilter=t.magFilter;const n={tEquirect:{value:null}},i="\\n\\n\\t\\t\\t\\tvarying vec3 vWorldDirection;\\n\\n\\t\\t\\t\\tvec3 transformDirection( in vec3 dir, in mat4 matrix ) {\\n\\n\\t\\t\\t\\t\\treturn normalize( ( matrix * vec4( dir, 0.0 ) ).xyz );\\n\\n\\t\\t\\t\\t}\\n\\n\\t\\t\\t\\tvoid main() {\\n\\n\\t\\t\\t\\t\\tvWorldDirection = transformDirection( position, modelMatrix );\\n\\n\\t\\t\\t\\t\\t#include \\n\\t\\t\\t\\t\\t#include \\n\\n\\t\\t\\t\\t}\\n\\t\\t\\t",r="\\n\\n\\t\\t\\t\\tuniform sampler2D tEquirect;\\n\\n\\t\\t\\t\\tvarying vec3 vWorldDirection;\\n\\n\\t\\t\\t\\t#include \\n\\n\\t\\t\\t\\tvoid main() {\\n\\n\\t\\t\\t\\t\\tvec3 direction = normalize( vWorldDirection );\\n\\n\\t\\t\\t\\t\\tvec2 sampleUV = equirectUv( direction );\\n\\n\\t\\t\\t\\t\\tgl_FragColor = texture2D( tEquirect, sampleUV );\\n\\n\\t\\t\\t\\t}\\n\\t\\t\\t",s=new xs(5,5,5),a=new Ts({name:"CubemapFromEquirect",uniforms:bs(n),vertexShader:i,fragmentShader:r,side:m,blending:_});a.uniforms.tEquirect.value=t;const o=new ys(s,a),l=t.minFilter;return t.minFilter===we&&(t.minFilter=_e),new Ls(1,10,this).update(e,o),t.minFilter=l,o.geometry.dispose(),o.material.dispose(),this}clear(e,t,n,i){const r=e.getRenderTarget();for(let r=0;r<6;r++)e.setRenderTarget(this,r),e.clear(t,n,i);e.setRenderTarget(r)}}Rs.prototype.isWebGLCubeRenderTarget=!0;const Ps=new oi,ks=new oi,Ns=new Zn;class Is{constructor(e=new oi(1,0,0),t=0){this.normal=e,this.constant=t}set(e,t){return this.normal.copy(e),this.constant=t,this}setComponents(e,t,n,i){return this.normal.set(e,t,n),this.constant=i,this}setFromNormalAndCoplanarPoint(e,t){return this.normal.copy(e),this.constant=-t.dot(this.normal),this}setFromCoplanarPoints(e,t,n){const i=Ps.subVectors(n,t).cross(ks.subVectors(e,t)).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,t){return t.copy(this.normal).multiplyScalar(-this.distanceToPoint(e)).add(e)}intersectLine(e,t){const n=e.delta(Ps),i=this.normal.dot(n);if(0===i)return 0===this.distanceToPoint(e.start)?t.copy(e.start):null;const r=-(e.start.dot(this.normal)+this.constant)/i;return r<0||r>1?null:t.copy(n).multiplyScalar(r).add(e.start)}intersectsLine(e){const t=this.distanceToPoint(e.start),n=this.distanceToPoint(e.end);return t<0&&n>0||n<0&&t>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,t){const n=t||Ns.getNormalMatrix(e),i=this.coplanarPoint(Ps).applyMatrix4(e),r=this.normal.applyMatrix3(n).normalize();return this.constant=-i.dot(r),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)}}Is.prototype.isPlane=!0;const Ds=new Ci,Os=new oi;class Bs{constructor(e=new Is,t=new Is,n=new Is,i=new Is,r=new Is,s=new Is){this.planes=[e,t,n,i,r,s]}set(e,t,n,i,r,s){const a=this.planes;return a[0].copy(e),a[1].copy(t),a[2].copy(n),a[3].copy(i),a[4].copy(r),a[5].copy(s),this}copy(e){const t=this.planes;for(let n=0;n<6;n++)t[n].copy(e.planes[n]);return this}setFromProjectionMatrix(e){const t=this.planes,n=e.elements,i=n[0],r=n[1],s=n[2],a=n[3],o=n[4],l=n[5],c=n[6],h=n[7],u=n[8],d=n[9],p=n[10],f=n[11],m=n[12],g=n[13],v=n[14],y=n[15];return t[0].setComponents(a-i,h-o,f-u,y-m).normalize(),t[1].setComponents(a+i,h+o,f+u,y+m).normalize(),t[2].setComponents(a+r,h+l,f+d,y+g).normalize(),t[3].setComponents(a-r,h-l,f-d,y-g).normalize(),t[4].setComponents(a-s,h-c,f-p,y-v).normalize(),t[5].setComponents(a+s,h+c,f+p,y+v).normalize(),this}intersectsObject(e){const t=e.geometry;return null===t.boundingSphere&&t.computeBoundingSphere(),Ds.copy(t.boundingSphere).applyMatrix4(e.matrixWorld),this.intersectsSphere(Ds)}intersectsSprite(e){return Ds.center.set(0,0,0),Ds.radius=.7071067811865476,Ds.applyMatrix4(e.matrixWorld),this.intersectsSphere(Ds)}intersectsSphere(e){const t=this.planes,n=e.center,i=-e.radius;for(let e=0;e<6;e++)if(t[e].distanceToPoint(n)0?e.max.x:e.min.x,Os.y=i.normal.y>0?e.max.y:e.min.y,Os.z=i.normal.z>0?e.max.z:e.min.z,i.distanceToPoint(Os)<0)return!1}return!0}containsPoint(e){const t=this.planes;for(let n=0;n<6;n++)if(t[n].distanceToPoint(e)<0)return!1;return!0}clone(){return(new this.constructor).copy(this)}}function Fs(){let e=null,t=!1,n=null,i=null;function r(t,s){n(t,s),i=e.requestAnimationFrame(r)}return{start:function(){!0!==t&&null!==n&&(i=e.requestAnimationFrame(r),t=!0)},stop:function(){e.cancelAnimationFrame(i),t=!1},setAnimationLoop:function(e){n=e},setContext:function(t){e=t}}}function Us(e,t){const n=t.isWebGL2,i=new WeakMap;return{get:function(e){return e.isInterleavedBufferAttribute&&(e=e.data),i.get(e)},remove:function(t){t.isInterleavedBufferAttribute&&(t=t.data);const n=i.get(t);n&&(e.deleteBuffer(n.buffer),i.delete(t))},update:function(t,r){if(t.isGLBufferAttribute){const e=i.get(t);return void((!e||e.version 0.0 ) ? v : 0.5 * inversesqrt( max( 1.0 - x * x, 1e-7 ) ) - v;\\n\\treturn cross( v1, v2 ) * theta_sintheta;\\n}\\nvec3 LTC_Evaluate( const in vec3 N, const in vec3 V, const in vec3 P, const in mat3 mInv, const in vec3 rectCoords[ 4 ] ) {\\n\\tvec3 v1 = rectCoords[ 1 ] - rectCoords[ 0 ];\\n\\tvec3 v2 = rectCoords[ 3 ] - rectCoords[ 0 ];\\n\\tvec3 lightNormal = cross( v1, v2 );\\n\\tif( dot( lightNormal, P - rectCoords[ 0 ] ) < 0.0 ) return vec3( 0.0 );\\n\\tvec3 T1, T2;\\n\\tT1 = normalize( V - N * dot( V, N ) );\\n\\tT2 = - cross( N, T1 );\\n\\tmat3 mat = mInv * transposeMat3( mat3( T1, T2, N ) );\\n\\tvec3 coords[ 4 ];\\n\\tcoords[ 0 ] = mat * ( rectCoords[ 0 ] - P );\\n\\tcoords[ 1 ] = mat * ( rectCoords[ 1 ] - P );\\n\\tcoords[ 2 ] = mat * ( rectCoords[ 2 ] - P );\\n\\tcoords[ 3 ] = mat * ( rectCoords[ 3 ] - P );\\n\\tcoords[ 0 ] = normalize( coords[ 0 ] );\\n\\tcoords[ 1 ] = normalize( coords[ 1 ] );\\n\\tcoords[ 2 ] = normalize( coords[ 2 ] );\\n\\tcoords[ 3 ] = normalize( coords[ 3 ] );\\n\\tvec3 vectorFormFactor = vec3( 0.0 );\\n\\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 0 ], coords[ 1 ] );\\n\\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 1 ], coords[ 2 ] );\\n\\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 2 ], coords[ 3 ] );\\n\\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 3 ], coords[ 0 ] );\\n\\tfloat result = LTC_ClippedSphereFormFactor( vectorFormFactor );\\n\\treturn vec3( result );\\n}\\nfloat G_BlinnPhong_Implicit( ) {\\n\\treturn 0.25;\\n}\\nfloat D_BlinnPhong( const in float shininess, const in float dotNH ) {\\n\\treturn RECIPROCAL_PI * ( shininess * 0.5 + 1.0 ) * pow( dotNH, shininess );\\n}\\nvec3 BRDF_BlinnPhong( const in IncidentLight incidentLight, const in GeometricContext geometry, const in vec3 specularColor, const in float shininess ) {\\n\\tvec3 halfDir = normalize( incidentLight.direction + geometry.viewDir );\\n\\tfloat dotNH = saturate( dot( geometry.normal, halfDir ) );\\n\\tfloat dotVH = saturate( dot( geometry.viewDir, halfDir ) );\\n\\tvec3 F = F_Schlick( specularColor, 1.0, dotVH );\\n\\tfloat G = G_BlinnPhong_Implicit( );\\n\\tfloat D = D_BlinnPhong( shininess, dotNH );\\n\\treturn F * ( G * D );\\n}\\n#if defined( USE_SHEEN )\\nfloat D_Charlie( float roughness, float NoH ) {\\n\\tfloat invAlpha = 1.0 / roughness;\\n\\tfloat cos2h = NoH * NoH;\\n\\tfloat sin2h = max( 1.0 - cos2h, 0.0078125 );\\n\\treturn ( 2.0 + invAlpha ) * pow( sin2h, invAlpha * 0.5 ) / ( 2.0 * PI );\\n}\\nfloat V_Neubelt( float NoV, float NoL ) {\\n\\treturn saturate( 1.0 / ( 4.0 * ( NoL + NoV - NoL * NoV ) ) );\\n}\\nvec3 BRDF_Sheen( const in float roughness, const in vec3 L, const in GeometricContext geometry, vec3 specularColor ) {\\n\\tvec3 N = geometry.normal;\\n\\tvec3 V = geometry.viewDir;\\n\\tvec3 H = normalize( V + L );\\n\\tfloat dotNH = saturate( dot( N, H ) );\\n\\treturn specularColor * D_Charlie( roughness, dotNH ) * V_Neubelt( dot(N, V), dot(N, L) );\\n}\\n#endif",bumpmap_pars_fragment:"#ifdef USE_BUMPMAP\\n\\tuniform sampler2D bumpMap;\\n\\tuniform float bumpScale;\\n\\tvec2 dHdxy_fwd() {\\n\\t\\tvec2 dSTdx = dFdx( vUv );\\n\\t\\tvec2 dSTdy = dFdy( vUv );\\n\\t\\tfloat Hll = bumpScale * texture2D( bumpMap, vUv ).x;\\n\\t\\tfloat dBx = bumpScale * texture2D( bumpMap, vUv + dSTdx ).x - Hll;\\n\\t\\tfloat dBy = bumpScale * texture2D( bumpMap, vUv + dSTdy ).x - Hll;\\n\\t\\treturn vec2( dBx, dBy );\\n\\t}\\n\\tvec3 perturbNormalArb( vec3 surf_pos, vec3 surf_norm, vec2 dHdxy, float faceDirection ) {\\n\\t\\tvec3 vSigmaX = vec3( dFdx( surf_pos.x ), dFdx( surf_pos.y ), dFdx( surf_pos.z ) );\\n\\t\\tvec3 vSigmaY = vec3( dFdy( surf_pos.x ), dFdy( surf_pos.y ), dFdy( surf_pos.z ) );\\n\\t\\tvec3 vN = surf_norm;\\n\\t\\tvec3 R1 = cross( vSigmaY, vN );\\n\\t\\tvec3 R2 = cross( vN, vSigmaX );\\n\\t\\tfloat fDet = dot( vSigmaX, R1 ) * faceDirection;\\n\\t\\tvec3 vGrad = sign( fDet ) * ( dHdxy.x * R1 + dHdxy.y * R2 );\\n\\t\\treturn normalize( abs( fDet ) * surf_norm - vGrad );\\n\\t}\\n#endif",clipping_planes_fragment:"#if NUM_CLIPPING_PLANES > 0\\n\\tvec4 plane;\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < UNION_CLIPPING_PLANES; i ++ ) {\\n\\t\\tplane = clippingPlanes[ i ];\\n\\t\\tif ( dot( vClipPosition, plane.xyz ) > plane.w ) discard;\\n\\t}\\n\\t#pragma unroll_loop_end\\n\\t#if UNION_CLIPPING_PLANES < NUM_CLIPPING_PLANES\\n\\t\\tbool clipped = true;\\n\\t\\t#pragma unroll_loop_start\\n\\t\\tfor ( int i = UNION_CLIPPING_PLANES; i < NUM_CLIPPING_PLANES; i ++ ) {\\n\\t\\t\\tplane = clippingPlanes[ i ];\\n\\t\\t\\tclipped = ( dot( vClipPosition, plane.xyz ) > plane.w ) && clipped;\\n\\t\\t}\\n\\t\\t#pragma unroll_loop_end\\n\\t\\tif ( clipped ) discard;\\n\\t#endif\\n#endif",clipping_planes_pars_fragment:"#if NUM_CLIPPING_PLANES > 0\\n\\tvarying vec3 vClipPosition;\\n\\tuniform vec4 clippingPlanes[ NUM_CLIPPING_PLANES ];\\n#endif",clipping_planes_pars_vertex:"#if NUM_CLIPPING_PLANES > 0\\n\\tvarying vec3 vClipPosition;\\n#endif",clipping_planes_vertex:"#if NUM_CLIPPING_PLANES > 0\\n\\tvClipPosition = - mvPosition.xyz;\\n#endif",color_fragment:"#if defined( USE_COLOR_ALPHA )\\n\\tdiffuseColor *= vColor;\\n#elif defined( USE_COLOR )\\n\\tdiffuseColor.rgb *= vColor;\\n#endif",color_pars_fragment:"#if defined( USE_COLOR_ALPHA )\\n\\tvarying vec4 vColor;\\n#elif defined( USE_COLOR )\\n\\tvarying vec3 vColor;\\n#endif",color_pars_vertex:"#if defined( USE_COLOR_ALPHA )\\n\\tvarying vec4 vColor;\\n#elif defined( USE_COLOR ) || defined( USE_INSTANCING_COLOR )\\n\\tvarying vec3 vColor;\\n#endif",color_vertex:"#if defined( USE_COLOR_ALPHA )\\n\\tvColor = vec4( 1.0 );\\n#elif defined( USE_COLOR ) || defined( USE_INSTANCING_COLOR )\\n\\tvColor = vec3( 1.0 );\\n#endif\\n#ifdef USE_COLOR\\n\\tvColor *= color;\\n#endif\\n#ifdef USE_INSTANCING_COLOR\\n\\tvColor.xyz *= instanceColor.xyz;\\n#endif",common:"#define PI 3.141592653589793\\n#define PI2 6.283185307179586\\n#define PI_HALF 1.5707963267948966\\n#define RECIPROCAL_PI 0.3183098861837907\\n#define RECIPROCAL_PI2 0.15915494309189535\\n#define EPSILON 1e-6\\n#ifndef saturate\\n#define saturate( a ) clamp( a, 0.0, 1.0 )\\n#endif\\n#define whiteComplement( a ) ( 1.0 - saturate( a ) )\\nfloat pow2( const in float x ) { return x*x; }\\nfloat pow3( const in float x ) { return x*x*x; }\\nfloat pow4( const in float x ) { float x2 = x*x; return x2*x2; }\\nfloat max3( const in vec3 v ) { return max( max( v.x, v.y ), v.z ); }\\nfloat average( const in vec3 color ) { return dot( color, vec3( 0.3333 ) ); }\\nhighp float rand( const in vec2 uv ) {\\n\\tconst highp float a = 12.9898, b = 78.233, c = 43758.5453;\\n\\thighp float dt = dot( uv.xy, vec2( a,b ) ), sn = mod( dt, PI );\\n\\treturn fract( sin( sn ) * c );\\n}\\n#ifdef HIGH_PRECISION\\n\\tfloat precisionSafeLength( vec3 v ) { return length( v ); }\\n#else\\n\\tfloat precisionSafeLength( vec3 v ) {\\n\\t\\tfloat maxComponent = max3( abs( v ) );\\n\\t\\treturn length( v / maxComponent ) * maxComponent;\\n\\t}\\n#endif\\nstruct IncidentLight {\\n\\tvec3 color;\\n\\tvec3 direction;\\n\\tbool visible;\\n};\\nstruct ReflectedLight {\\n\\tvec3 directDiffuse;\\n\\tvec3 directSpecular;\\n\\tvec3 indirectDiffuse;\\n\\tvec3 indirectSpecular;\\n};\\nstruct GeometricContext {\\n\\tvec3 position;\\n\\tvec3 normal;\\n\\tvec3 viewDir;\\n#ifdef USE_CLEARCOAT\\n\\tvec3 clearcoatNormal;\\n#endif\\n};\\nvec3 transformDirection( in vec3 dir, in mat4 matrix ) {\\n\\treturn normalize( ( matrix * vec4( dir, 0.0 ) ).xyz );\\n}\\nvec3 inverseTransformDirection( in vec3 dir, in mat4 matrix ) {\\n\\treturn normalize( ( vec4( dir, 0.0 ) * matrix ).xyz );\\n}\\nmat3 transposeMat3( const in mat3 m ) {\\n\\tmat3 tmp;\\n\\ttmp[ 0 ] = vec3( m[ 0 ].x, m[ 1 ].x, m[ 2 ].x );\\n\\ttmp[ 1 ] = vec3( m[ 0 ].y, m[ 1 ].y, m[ 2 ].y );\\n\\ttmp[ 2 ] = vec3( m[ 0 ].z, m[ 1 ].z, m[ 2 ].z );\\n\\treturn tmp;\\n}\\nfloat linearToRelativeLuminance( const in vec3 color ) {\\n\\tvec3 weights = vec3( 0.2126, 0.7152, 0.0722 );\\n\\treturn dot( weights, color.rgb );\\n}\\nbool isPerspectiveMatrix( mat4 m ) {\\n\\treturn m[ 2 ][ 3 ] == - 1.0;\\n}\\nvec2 equirectUv( in vec3 dir ) {\\n\\tfloat u = atan( dir.z, dir.x ) * RECIPROCAL_PI2 + 0.5;\\n\\tfloat v = asin( clamp( dir.y, - 1.0, 1.0 ) ) * RECIPROCAL_PI + 0.5;\\n\\treturn vec2( u, v );\\n}",cube_uv_reflection_fragment:"#ifdef ENVMAP_TYPE_CUBE_UV\\n\\t#define cubeUV_maxMipLevel 8.0\\n\\t#define cubeUV_minMipLevel 4.0\\n\\t#define cubeUV_maxTileSize 256.0\\n\\t#define cubeUV_minTileSize 16.0\\n\\tfloat getFace( vec3 direction ) {\\n\\t\\tvec3 absDirection = abs( direction );\\n\\t\\tfloat face = - 1.0;\\n\\t\\tif ( absDirection.x > absDirection.z ) {\\n\\t\\t\\tif ( absDirection.x > absDirection.y )\\n\\t\\t\\t\\tface = direction.x > 0.0 ? 0.0 : 3.0;\\n\\t\\t\\telse\\n\\t\\t\\t\\tface = direction.y > 0.0 ? 1.0 : 4.0;\\n\\t\\t} else {\\n\\t\\t\\tif ( absDirection.z > absDirection.y )\\n\\t\\t\\t\\tface = direction.z > 0.0 ? 2.0 : 5.0;\\n\\t\\t\\telse\\n\\t\\t\\t\\tface = direction.y > 0.0 ? 1.0 : 4.0;\\n\\t\\t}\\n\\t\\treturn face;\\n\\t}\\n\\tvec2 getUV( vec3 direction, float face ) {\\n\\t\\tvec2 uv;\\n\\t\\tif ( face == 0.0 ) {\\n\\t\\t\\tuv = vec2( direction.z, direction.y ) / abs( direction.x );\\n\\t\\t} else if ( face == 1.0 ) {\\n\\t\\t\\tuv = vec2( - direction.x, - direction.z ) / abs( direction.y );\\n\\t\\t} else if ( face == 2.0 ) {\\n\\t\\t\\tuv = vec2( - direction.x, direction.y ) / abs( direction.z );\\n\\t\\t} else if ( face == 3.0 ) {\\n\\t\\t\\tuv = vec2( - direction.z, direction.y ) / abs( direction.x );\\n\\t\\t} else if ( face == 4.0 ) {\\n\\t\\t\\tuv = vec2( - direction.x, direction.z ) / abs( direction.y );\\n\\t\\t} else {\\n\\t\\t\\tuv = vec2( direction.x, direction.y ) / abs( direction.z );\\n\\t\\t}\\n\\t\\treturn 0.5 * ( uv + 1.0 );\\n\\t}\\n\\tvec3 bilinearCubeUV( sampler2D envMap, vec3 direction, float mipInt ) {\\n\\t\\tfloat face = getFace( direction );\\n\\t\\tfloat filterInt = max( cubeUV_minMipLevel - mipInt, 0.0 );\\n\\t\\tmipInt = max( mipInt, cubeUV_minMipLevel );\\n\\t\\tfloat faceSize = exp2( mipInt );\\n\\t\\tfloat texelSize = 1.0 / ( 3.0 * cubeUV_maxTileSize );\\n\\t\\tvec2 uv = getUV( direction, face ) * ( faceSize - 1.0 );\\n\\t\\tvec2 f = fract( uv );\\n\\t\\tuv += 0.5 - f;\\n\\t\\tif ( face > 2.0 ) {\\n\\t\\t\\tuv.y += faceSize;\\n\\t\\t\\tface -= 3.0;\\n\\t\\t}\\n\\t\\tuv.x += face * faceSize;\\n\\t\\tif ( mipInt < cubeUV_maxMipLevel ) {\\n\\t\\t\\tuv.y += 2.0 * cubeUV_maxTileSize;\\n\\t\\t}\\n\\t\\tuv.y += filterInt * 2.0 * cubeUV_minTileSize;\\n\\t\\tuv.x += 3.0 * max( 0.0, cubeUV_maxTileSize - 2.0 * faceSize );\\n\\t\\tuv *= texelSize;\\n\\t\\tvec3 tl = envMapTexelToLinear( texture2D( envMap, uv ) ).rgb;\\n\\t\\tuv.x += texelSize;\\n\\t\\tvec3 tr = envMapTexelToLinear( texture2D( envMap, uv ) ).rgb;\\n\\t\\tuv.y += texelSize;\\n\\t\\tvec3 br = envMapTexelToLinear( texture2D( envMap, uv ) ).rgb;\\n\\t\\tuv.x -= texelSize;\\n\\t\\tvec3 bl = envMapTexelToLinear( texture2D( envMap, uv ) ).rgb;\\n\\t\\tvec3 tm = mix( tl, tr, f.x );\\n\\t\\tvec3 bm = mix( bl, br, f.x );\\n\\t\\treturn mix( tm, bm, f.y );\\n\\t}\\n\\t#define r0 1.0\\n\\t#define v0 0.339\\n\\t#define m0 - 2.0\\n\\t#define r1 0.8\\n\\t#define v1 0.276\\n\\t#define m1 - 1.0\\n\\t#define r4 0.4\\n\\t#define v4 0.046\\n\\t#define m4 2.0\\n\\t#define r5 0.305\\n\\t#define v5 0.016\\n\\t#define m5 3.0\\n\\t#define r6 0.21\\n\\t#define v6 0.0038\\n\\t#define m6 4.0\\n\\tfloat roughnessToMip( float roughness ) {\\n\\t\\tfloat mip = 0.0;\\n\\t\\tif ( roughness >= r1 ) {\\n\\t\\t\\tmip = ( r0 - roughness ) * ( m1 - m0 ) / ( r0 - r1 ) + m0;\\n\\t\\t} else if ( roughness >= r4 ) {\\n\\t\\t\\tmip = ( r1 - roughness ) * ( m4 - m1 ) / ( r1 - r4 ) + m1;\\n\\t\\t} else if ( roughness >= r5 ) {\\n\\t\\t\\tmip = ( r4 - roughness ) * ( m5 - m4 ) / ( r4 - r5 ) + m4;\\n\\t\\t} else if ( roughness >= r6 ) {\\n\\t\\t\\tmip = ( r5 - roughness ) * ( m6 - m5 ) / ( r5 - r6 ) + m5;\\n\\t\\t} else {\\n\\t\\t\\tmip = - 2.0 * log2( 1.16 * roughness );\\t\\t}\\n\\t\\treturn mip;\\n\\t}\\n\\tvec4 textureCubeUV( sampler2D envMap, vec3 sampleDir, float roughness ) {\\n\\t\\tfloat mip = clamp( roughnessToMip( roughness ), m0, cubeUV_maxMipLevel );\\n\\t\\tfloat mipF = fract( mip );\\n\\t\\tfloat mipInt = floor( mip );\\n\\t\\tvec3 color0 = bilinearCubeUV( envMap, sampleDir, mipInt );\\n\\t\\tif ( mipF == 0.0 ) {\\n\\t\\t\\treturn vec4( color0, 1.0 );\\n\\t\\t} else {\\n\\t\\t\\tvec3 color1 = bilinearCubeUV( envMap, sampleDir, mipInt + 1.0 );\\n\\t\\t\\treturn vec4( mix( color0, color1, mipF ), 1.0 );\\n\\t\\t}\\n\\t}\\n#endif",defaultnormal_vertex:"vec3 transformedNormal = objectNormal;\\n#ifdef USE_INSTANCING\\n\\tmat3 m = mat3( instanceMatrix );\\n\\ttransformedNormal /= vec3( dot( m[ 0 ], m[ 0 ] ), dot( m[ 1 ], m[ 1 ] ), dot( m[ 2 ], m[ 2 ] ) );\\n\\ttransformedNormal = m * transformedNormal;\\n#endif\\ntransformedNormal = normalMatrix * transformedNormal;\\n#ifdef FLIP_SIDED\\n\\ttransformedNormal = - transformedNormal;\\n#endif\\n#ifdef USE_TANGENT\\n\\tvec3 transformedTangent = ( modelViewMatrix * vec4( objectTangent, 0.0 ) ).xyz;\\n\\t#ifdef FLIP_SIDED\\n\\t\\ttransformedTangent = - transformedTangent;\\n\\t#endif\\n#endif",displacementmap_pars_vertex:"#ifdef USE_DISPLACEMENTMAP\\n\\tuniform sampler2D displacementMap;\\n\\tuniform float displacementScale;\\n\\tuniform float displacementBias;\\n#endif",displacementmap_vertex:"#ifdef USE_DISPLACEMENTMAP\\n\\ttransformed += normalize( objectNormal ) * ( texture2D( displacementMap, vUv ).x * displacementScale + displacementBias );\\n#endif",emissivemap_fragment:"#ifdef USE_EMISSIVEMAP\\n\\tvec4 emissiveColor = texture2D( emissiveMap, vUv );\\n\\temissiveColor.rgb = emissiveMapTexelToLinear( emissiveColor ).rgb;\\n\\ttotalEmissiveRadiance *= emissiveColor.rgb;\\n#endif",emissivemap_pars_fragment:"#ifdef USE_EMISSIVEMAP\\n\\tuniform sampler2D emissiveMap;\\n#endif",encodings_fragment:"gl_FragColor = linearToOutputTexel( gl_FragColor );",encodings_pars_fragment:"\\nvec4 LinearToLinear( in vec4 value ) {\\n\\treturn value;\\n}\\nvec4 GammaToLinear( in vec4 value, in float gammaFactor ) {\\n\\treturn vec4( pow( value.rgb, vec3( gammaFactor ) ), value.a );\\n}\\nvec4 LinearToGamma( in vec4 value, in float gammaFactor ) {\\n\\treturn vec4( pow( value.rgb, vec3( 1.0 / gammaFactor ) ), value.a );\\n}\\nvec4 sRGBToLinear( in vec4 value ) {\\n\\treturn vec4( mix( pow( value.rgb * 0.9478672986 + vec3( 0.0521327014 ), vec3( 2.4 ) ), value.rgb * 0.0773993808, vec3( lessThanEqual( value.rgb, vec3( 0.04045 ) ) ) ), value.a );\\n}\\nvec4 LinearTosRGB( in vec4 value ) {\\n\\treturn 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 );\\n}\\nvec4 RGBEToLinear( in vec4 value ) {\\n\\treturn vec4( value.rgb * exp2( value.a * 255.0 - 128.0 ), 1.0 );\\n}\\nvec4 LinearToRGBE( in vec4 value ) {\\n\\tfloat maxComponent = max( max( value.r, value.g ), value.b );\\n\\tfloat fExp = clamp( ceil( log2( maxComponent ) ), -128.0, 127.0 );\\n\\treturn vec4( value.rgb / exp2( fExp ), ( fExp + 128.0 ) / 255.0 );\\n}\\nvec4 RGBMToLinear( in vec4 value, in float maxRange ) {\\n\\treturn vec4( value.rgb * value.a * maxRange, 1.0 );\\n}\\nvec4 LinearToRGBM( in vec4 value, in float maxRange ) {\\n\\tfloat maxRGB = max( value.r, max( value.g, value.b ) );\\n\\tfloat M = clamp( maxRGB / maxRange, 0.0, 1.0 );\\n\\tM = ceil( M * 255.0 ) / 255.0;\\n\\treturn vec4( value.rgb / ( M * maxRange ), M );\\n}\\nvec4 RGBDToLinear( in vec4 value, in float maxRange ) {\\n\\treturn vec4( value.rgb * ( ( maxRange / 255.0 ) / value.a ), 1.0 );\\n}\\nvec4 LinearToRGBD( in vec4 value, in float maxRange ) {\\n\\tfloat maxRGB = max( value.r, max( value.g, value.b ) );\\n\\tfloat D = max( maxRange / maxRGB, 1.0 );\\n\\tD = clamp( floor( D ) / 255.0, 0.0, 1.0 );\\n\\treturn vec4( value.rgb * ( D * ( 255.0 / maxRange ) ), D );\\n}\\nconst mat3 cLogLuvM = mat3( 0.2209, 0.3390, 0.4184, 0.1138, 0.6780, 0.7319, 0.0102, 0.1130, 0.2969 );\\nvec4 LinearToLogLuv( in vec4 value ) {\\n\\tvec3 Xp_Y_XYZp = cLogLuvM * value.rgb;\\n\\tXp_Y_XYZp = max( Xp_Y_XYZp, vec3( 1e-6, 1e-6, 1e-6 ) );\\n\\tvec4 vResult;\\n\\tvResult.xy = Xp_Y_XYZp.xy / Xp_Y_XYZp.z;\\n\\tfloat Le = 2.0 * log2(Xp_Y_XYZp.y) + 127.0;\\n\\tvResult.w = fract( Le );\\n\\tvResult.z = ( Le - ( floor( vResult.w * 255.0 ) ) / 255.0 ) / 255.0;\\n\\treturn vResult;\\n}\\nconst mat3 cLogLuvInverseM = mat3( 6.0014, -2.7008, -1.7996, -1.3320, 3.1029, -5.7721, 0.3008, -1.0882, 5.6268 );\\nvec4 LogLuvToLinear( in vec4 value ) {\\n\\tfloat Le = value.z * 255.0 + value.w;\\n\\tvec3 Xp_Y_XYZp;\\n\\tXp_Y_XYZp.y = exp2( ( Le - 127.0 ) / 2.0 );\\n\\tXp_Y_XYZp.z = Xp_Y_XYZp.y / value.y;\\n\\tXp_Y_XYZp.x = value.x * Xp_Y_XYZp.z;\\n\\tvec3 vRGB = cLogLuvInverseM * Xp_Y_XYZp.rgb;\\n\\treturn vec4( max( vRGB, 0.0 ), 1.0 );\\n}",envmap_fragment:"#ifdef USE_ENVMAP\\n\\t#ifdef ENV_WORLDPOS\\n\\t\\tvec3 cameraToFrag;\\n\\t\\tif ( isOrthographic ) {\\n\\t\\t\\tcameraToFrag = normalize( vec3( - viewMatrix[ 0 ][ 2 ], - viewMatrix[ 1 ][ 2 ], - viewMatrix[ 2 ][ 2 ] ) );\\n\\t\\t} else {\\n\\t\\t\\tcameraToFrag = normalize( vWorldPosition - cameraPosition );\\n\\t\\t}\\n\\t\\tvec3 worldNormal = inverseTransformDirection( normal, viewMatrix );\\n\\t\\t#ifdef ENVMAP_MODE_REFLECTION\\n\\t\\t\\tvec3 reflectVec = reflect( cameraToFrag, worldNormal );\\n\\t\\t#else\\n\\t\\t\\tvec3 reflectVec = refract( cameraToFrag, worldNormal, refractionRatio );\\n\\t\\t#endif\\n\\t#else\\n\\t\\tvec3 reflectVec = vReflect;\\n\\t#endif\\n\\t#ifdef ENVMAP_TYPE_CUBE\\n\\t\\tvec4 envColor = textureCube( envMap, vec3( flipEnvMap * reflectVec.x, reflectVec.yz ) );\\n\\t\\tenvColor = envMapTexelToLinear( envColor );\\n\\t#elif defined( ENVMAP_TYPE_CUBE_UV )\\n\\t\\tvec4 envColor = textureCubeUV( envMap, reflectVec, 0.0 );\\n\\t#else\\n\\t\\tvec4 envColor = vec4( 0.0 );\\n\\t#endif\\n\\t#ifdef ENVMAP_BLENDING_MULTIPLY\\n\\t\\toutgoingLight = mix( outgoingLight, outgoingLight * envColor.xyz, specularStrength * reflectivity );\\n\\t#elif defined( ENVMAP_BLENDING_MIX )\\n\\t\\toutgoingLight = mix( outgoingLight, envColor.xyz, specularStrength * reflectivity );\\n\\t#elif defined( ENVMAP_BLENDING_ADD )\\n\\t\\toutgoingLight += envColor.xyz * specularStrength * reflectivity;\\n\\t#endif\\n#endif",envmap_common_pars_fragment:"#ifdef USE_ENVMAP\\n\\tuniform float envMapIntensity;\\n\\tuniform float flipEnvMap;\\n\\tuniform int maxMipLevel;\\n\\t#ifdef ENVMAP_TYPE_CUBE\\n\\t\\tuniform samplerCube envMap;\\n\\t#else\\n\\t\\tuniform sampler2D envMap;\\n\\t#endif\\n\\t\\n#endif",envmap_pars_fragment:"#ifdef USE_ENVMAP\\n\\tuniform float reflectivity;\\n\\t#if defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( PHONG )\\n\\t\\t#define ENV_WORLDPOS\\n\\t#endif\\n\\t#ifdef ENV_WORLDPOS\\n\\t\\tvarying vec3 vWorldPosition;\\n\\t\\tuniform float refractionRatio;\\n\\t#else\\n\\t\\tvarying vec3 vReflect;\\n\\t#endif\\n#endif",envmap_pars_vertex:"#ifdef USE_ENVMAP\\n\\t#if defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) ||defined( PHONG )\\n\\t\\t#define ENV_WORLDPOS\\n\\t#endif\\n\\t#ifdef ENV_WORLDPOS\\n\\t\\t\\n\\t\\tvarying vec3 vWorldPosition;\\n\\t#else\\n\\t\\tvarying vec3 vReflect;\\n\\t\\tuniform float refractionRatio;\\n\\t#endif\\n#endif",envmap_physical_pars_fragment:"#if defined( USE_ENVMAP )\\n\\t#ifdef ENVMAP_MODE_REFRACTION\\n\\t\\tuniform float refractionRatio;\\n\\t#endif\\n\\tvec3 getIBLIrradiance( const in GeometricContext geometry ) {\\n\\t\\t#if defined( ENVMAP_TYPE_CUBE_UV )\\n\\t\\t\\tvec3 worldNormal = inverseTransformDirection( geometry.normal, viewMatrix );\\n\\t\\t\\tvec4 envMapColor = textureCubeUV( envMap, worldNormal, 1.0 );\\n\\t\\t\\treturn PI * envMapColor.rgb * envMapIntensity;\\n\\t\\t#else\\n\\t\\t\\treturn vec3( 0.0 );\\n\\t\\t#endif\\n\\t}\\n\\tvec3 getIBLRadiance( const in vec3 viewDir, const in vec3 normal, const in float roughness ) {\\n\\t\\t#if defined( ENVMAP_TYPE_CUBE_UV )\\n\\t\\t\\tvec3 reflectVec;\\n\\t\\t\\t#ifdef ENVMAP_MODE_REFLECTION\\n\\t\\t\\t\\treflectVec = reflect( - viewDir, normal );\\n\\t\\t\\t\\treflectVec = normalize( mix( reflectVec, normal, roughness * roughness) );\\n\\t\\t\\t#else\\n\\t\\t\\t\\treflectVec = refract( - viewDir, normal, refractionRatio );\\n\\t\\t\\t#endif\\n\\t\\t\\treflectVec = inverseTransformDirection( reflectVec, viewMatrix );\\n\\t\\t\\tvec4 envMapColor = textureCubeUV( envMap, reflectVec, roughness );\\n\\t\\t\\treturn envMapColor.rgb * envMapIntensity;\\n\\t\\t#else\\n\\t\\t\\treturn vec3( 0.0 );\\n\\t\\t#endif\\n\\t}\\n#endif",envmap_vertex:"#ifdef USE_ENVMAP\\n\\t#ifdef ENV_WORLDPOS\\n\\t\\tvWorldPosition = worldPosition.xyz;\\n\\t#else\\n\\t\\tvec3 cameraToVertex;\\n\\t\\tif ( isOrthographic ) {\\n\\t\\t\\tcameraToVertex = normalize( vec3( - viewMatrix[ 0 ][ 2 ], - viewMatrix[ 1 ][ 2 ], - viewMatrix[ 2 ][ 2 ] ) );\\n\\t\\t} else {\\n\\t\\t\\tcameraToVertex = normalize( worldPosition.xyz - cameraPosition );\\n\\t\\t}\\n\\t\\tvec3 worldNormal = inverseTransformDirection( transformedNormal, viewMatrix );\\n\\t\\t#ifdef ENVMAP_MODE_REFLECTION\\n\\t\\t\\tvReflect = reflect( cameraToVertex, worldNormal );\\n\\t\\t#else\\n\\t\\t\\tvReflect = refract( cameraToVertex, worldNormal, refractionRatio );\\n\\t\\t#endif\\n\\t#endif\\n#endif",fog_vertex:"#ifdef USE_FOG\\n\\tvFogDepth = - mvPosition.z;\\n#endif",fog_pars_vertex:"#ifdef USE_FOG\\n\\tvarying float vFogDepth;\\n#endif",fog_fragment:"#ifdef USE_FOG\\n\\t#ifdef FOG_EXP2\\n\\t\\tfloat fogFactor = 1.0 - exp( - fogDensity * fogDensity * vFogDepth * vFogDepth );\\n\\t#else\\n\\t\\tfloat fogFactor = smoothstep( fogNear, fogFar, vFogDepth );\\n\\t#endif\\n\\tgl_FragColor.rgb = mix( gl_FragColor.rgb, fogColor, fogFactor );\\n#endif",fog_pars_fragment:"#ifdef USE_FOG\\n\\tuniform vec3 fogColor;\\n\\tvarying float vFogDepth;\\n\\t#ifdef FOG_EXP2\\n\\t\\tuniform float fogDensity;\\n\\t#else\\n\\t\\tuniform float fogNear;\\n\\t\\tuniform float fogFar;\\n\\t#endif\\n#endif",gradientmap_pars_fragment:"#ifdef USE_GRADIENTMAP\\n\\tuniform sampler2D gradientMap;\\n#endif\\nvec3 getGradientIrradiance( vec3 normal, vec3 lightDirection ) {\\n\\tfloat dotNL = dot( normal, lightDirection );\\n\\tvec2 coord = vec2( dotNL * 0.5 + 0.5, 0.0 );\\n\\t#ifdef USE_GRADIENTMAP\\n\\t\\treturn texture2D( gradientMap, coord ).rgb;\\n\\t#else\\n\\t\\treturn ( coord.x < 0.7 ) ? vec3( 0.7 ) : vec3( 1.0 );\\n\\t#endif\\n}",lightmap_fragment:"#ifdef USE_LIGHTMAP\\n\\tvec4 lightMapTexel = texture2D( lightMap, vUv2 );\\n\\tvec3 lightMapIrradiance = lightMapTexelToLinear( lightMapTexel ).rgb * lightMapIntensity;\\n\\t#ifndef PHYSICALLY_CORRECT_LIGHTS\\n\\t\\tlightMapIrradiance *= PI;\\n\\t#endif\\n\\treflectedLight.indirectDiffuse += lightMapIrradiance;\\n#endif",lightmap_pars_fragment:"#ifdef USE_LIGHTMAP\\n\\tuniform sampler2D lightMap;\\n\\tuniform float lightMapIntensity;\\n#endif",lights_lambert_vertex:"vec3 diffuse = vec3( 1.0 );\\nGeometricContext geometry;\\ngeometry.position = mvPosition.xyz;\\ngeometry.normal = normalize( transformedNormal );\\ngeometry.viewDir = ( isOrthographic ) ? vec3( 0, 0, 1 ) : normalize( -mvPosition.xyz );\\nGeometricContext backGeometry;\\nbackGeometry.position = geometry.position;\\nbackGeometry.normal = -geometry.normal;\\nbackGeometry.viewDir = geometry.viewDir;\\nvLightFront = vec3( 0.0 );\\nvIndirectFront = vec3( 0.0 );\\n#ifdef DOUBLE_SIDED\\n\\tvLightBack = vec3( 0.0 );\\n\\tvIndirectBack = vec3( 0.0 );\\n#endif\\nIncidentLight directLight;\\nfloat dotNL;\\nvec3 directLightColor_Diffuse;\\nvIndirectFront += getAmbientLightIrradiance( ambientLightColor );\\nvIndirectFront += getLightProbeIrradiance( lightProbe, geometry );\\n#ifdef DOUBLE_SIDED\\n\\tvIndirectBack += getAmbientLightIrradiance( ambientLightColor );\\n\\tvIndirectBack += getLightProbeIrradiance( lightProbe, backGeometry );\\n#endif\\n#if NUM_POINT_LIGHTS > 0\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_POINT_LIGHTS; i ++ ) {\\n\\t\\tgetPointLightInfo( pointLights[ i ], geometry, directLight );\\n\\t\\tdotNL = dot( geometry.normal, directLight.direction );\\n\\t\\tdirectLightColor_Diffuse = directLight.color;\\n\\t\\tvLightFront += saturate( dotNL ) * directLightColor_Diffuse;\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\tvLightBack += saturate( - dotNL ) * directLightColor_Diffuse;\\n\\t\\t#endif\\n\\t}\\n\\t#pragma unroll_loop_end\\n#endif\\n#if NUM_SPOT_LIGHTS > 0\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_SPOT_LIGHTS; i ++ ) {\\n\\t\\tgetSpotLightInfo( spotLights[ i ], geometry, directLight );\\n\\t\\tdotNL = dot( geometry.normal, directLight.direction );\\n\\t\\tdirectLightColor_Diffuse = directLight.color;\\n\\t\\tvLightFront += saturate( dotNL ) * directLightColor_Diffuse;\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\tvLightBack += saturate( - dotNL ) * directLightColor_Diffuse;\\n\\t\\t#endif\\n\\t}\\n\\t#pragma unroll_loop_end\\n#endif\\n#if NUM_DIR_LIGHTS > 0\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_DIR_LIGHTS; i ++ ) {\\n\\t\\tgetDirectionalLightInfo( directionalLights[ i ], geometry, directLight );\\n\\t\\tdotNL = dot( geometry.normal, directLight.direction );\\n\\t\\tdirectLightColor_Diffuse = directLight.color;\\n\\t\\tvLightFront += saturate( dotNL ) * directLightColor_Diffuse;\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\tvLightBack += saturate( - dotNL ) * directLightColor_Diffuse;\\n\\t\\t#endif\\n\\t}\\n\\t#pragma unroll_loop_end\\n#endif\\n#if NUM_HEMI_LIGHTS > 0\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_HEMI_LIGHTS; i ++ ) {\\n\\t\\tvIndirectFront += getHemisphereLightIrradiance( hemisphereLights[ i ], geometry );\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\tvIndirectBack += getHemisphereLightIrradiance( hemisphereLights[ i ], backGeometry );\\n\\t\\t#endif\\n\\t}\\n\\t#pragma unroll_loop_end\\n#endif",lights_pars_begin:"uniform bool receiveShadow;\\nuniform vec3 ambientLightColor;\\nuniform vec3 lightProbe[ 9 ];\\nvec3 shGetIrradianceAt( in vec3 normal, in vec3 shCoefficients[ 9 ] ) {\\n\\tfloat x = normal.x, y = normal.y, z = normal.z;\\n\\tvec3 result = shCoefficients[ 0 ] * 0.886227;\\n\\tresult += shCoefficients[ 1 ] * 2.0 * 0.511664 * y;\\n\\tresult += shCoefficients[ 2 ] * 2.0 * 0.511664 * z;\\n\\tresult += shCoefficients[ 3 ] * 2.0 * 0.511664 * x;\\n\\tresult += shCoefficients[ 4 ] * 2.0 * 0.429043 * x * y;\\n\\tresult += shCoefficients[ 5 ] * 2.0 * 0.429043 * y * z;\\n\\tresult += shCoefficients[ 6 ] * ( 0.743125 * z * z - 0.247708 );\\n\\tresult += shCoefficients[ 7 ] * 2.0 * 0.429043 * x * z;\\n\\tresult += shCoefficients[ 8 ] * 0.429043 * ( x * x - y * y );\\n\\treturn result;\\n}\\nvec3 getLightProbeIrradiance( const in vec3 lightProbe[ 9 ], const in GeometricContext geometry ) {\\n\\tvec3 worldNormal = inverseTransformDirection( geometry.normal, viewMatrix );\\n\\tvec3 irradiance = shGetIrradianceAt( worldNormal, lightProbe );\\n\\treturn irradiance;\\n}\\nvec3 getAmbientLightIrradiance( const in vec3 ambientLightColor ) {\\n\\tvec3 irradiance = ambientLightColor;\\n\\treturn irradiance;\\n}\\nfloat getDistanceAttenuation( const in float lightDistance, const in float cutoffDistance, const in float decayExponent ) {\\n\\t#if defined ( PHYSICALLY_CORRECT_LIGHTS )\\n\\t\\tfloat distanceFalloff = 1.0 / max( pow( lightDistance, decayExponent ), 0.01 );\\n\\t\\tif ( cutoffDistance > 0.0 ) {\\n\\t\\t\\tdistanceFalloff *= pow2( saturate( 1.0 - pow4( lightDistance / cutoffDistance ) ) );\\n\\t\\t}\\n\\t\\treturn distanceFalloff;\\n\\t#else\\n\\t\\tif ( cutoffDistance > 0.0 && decayExponent > 0.0 ) {\\n\\t\\t\\treturn pow( saturate( - lightDistance / cutoffDistance + 1.0 ), decayExponent );\\n\\t\\t}\\n\\t\\treturn 1.0;\\n\\t#endif\\n}\\nfloat getSpotAttenuation( const in float coneCosine, const in float penumbraCosine, const in float angleCosine ) {\\n\\treturn smoothstep( coneCosine, penumbraCosine, angleCosine );\\n}\\n#if NUM_DIR_LIGHTS > 0\\n\\tstruct DirectionalLight {\\n\\t\\tvec3 direction;\\n\\t\\tvec3 color;\\n\\t};\\n\\tuniform DirectionalLight directionalLights[ NUM_DIR_LIGHTS ];\\n\\tvoid getDirectionalLightInfo( const in DirectionalLight directionalLight, const in GeometricContext geometry, out IncidentLight light ) {\\n\\t\\tlight.color = directionalLight.color;\\n\\t\\tlight.direction = directionalLight.direction;\\n\\t\\tlight.visible = true;\\n\\t}\\n#endif\\n#if NUM_POINT_LIGHTS > 0\\n\\tstruct PointLight {\\n\\t\\tvec3 position;\\n\\t\\tvec3 color;\\n\\t\\tfloat distance;\\n\\t\\tfloat decay;\\n\\t};\\n\\tuniform PointLight pointLights[ NUM_POINT_LIGHTS ];\\n\\tvoid getPointLightInfo( const in PointLight pointLight, const in GeometricContext geometry, out IncidentLight light ) {\\n\\t\\tvec3 lVector = pointLight.position - geometry.position;\\n\\t\\tlight.direction = normalize( lVector );\\n\\t\\tfloat lightDistance = length( lVector );\\n\\t\\tlight.color = pointLight.color;\\n\\t\\tlight.color *= getDistanceAttenuation( lightDistance, pointLight.distance, pointLight.decay );\\n\\t\\tlight.visible = ( light.color != vec3( 0.0 ) );\\n\\t}\\n#endif\\n#if NUM_SPOT_LIGHTS > 0\\n\\tstruct SpotLight {\\n\\t\\tvec3 position;\\n\\t\\tvec3 direction;\\n\\t\\tvec3 color;\\n\\t\\tfloat distance;\\n\\t\\tfloat decay;\\n\\t\\tfloat coneCos;\\n\\t\\tfloat penumbraCos;\\n\\t};\\n\\tuniform SpotLight spotLights[ NUM_SPOT_LIGHTS ];\\n\\tvoid getSpotLightInfo( const in SpotLight spotLight, const in GeometricContext geometry, out IncidentLight light ) {\\n\\t\\tvec3 lVector = spotLight.position - geometry.position;\\n\\t\\tlight.direction = normalize( lVector );\\n\\t\\tfloat angleCos = dot( light.direction, spotLight.direction );\\n\\t\\tfloat spotAttenuation = getSpotAttenuation( spotLight.coneCos, spotLight.penumbraCos, angleCos );\\n\\t\\tif ( spotAttenuation > 0.0 ) {\\n\\t\\t\\tfloat lightDistance = length( lVector );\\n\\t\\t\\tlight.color = spotLight.color * spotAttenuation;\\n\\t\\t\\tlight.color *= getDistanceAttenuation( lightDistance, spotLight.distance, spotLight.decay );\\n\\t\\t\\tlight.visible = ( light.color != vec3( 0.0 ) );\\n\\t\\t} else {\\n\\t\\t\\tlight.color = vec3( 0.0 );\\n\\t\\t\\tlight.visible = false;\\n\\t\\t}\\n\\t}\\n#endif\\n#if NUM_RECT_AREA_LIGHTS > 0\\n\\tstruct RectAreaLight {\\n\\t\\tvec3 color;\\n\\t\\tvec3 position;\\n\\t\\tvec3 halfWidth;\\n\\t\\tvec3 halfHeight;\\n\\t};\\n\\tuniform sampler2D ltc_1;\\tuniform sampler2D ltc_2;\\n\\tuniform RectAreaLight rectAreaLights[ NUM_RECT_AREA_LIGHTS ];\\n#endif\\n#if NUM_HEMI_LIGHTS > 0\\n\\tstruct HemisphereLight {\\n\\t\\tvec3 direction;\\n\\t\\tvec3 skyColor;\\n\\t\\tvec3 groundColor;\\n\\t};\\n\\tuniform HemisphereLight hemisphereLights[ NUM_HEMI_LIGHTS ];\\n\\tvec3 getHemisphereLightIrradiance( const in HemisphereLight hemiLight, const in GeometricContext geometry ) {\\n\\t\\tfloat dotNL = dot( geometry.normal, hemiLight.direction );\\n\\t\\tfloat hemiDiffuseWeight = 0.5 * dotNL + 0.5;\\n\\t\\tvec3 irradiance = mix( hemiLight.groundColor, hemiLight.skyColor, hemiDiffuseWeight );\\n\\t\\treturn irradiance;\\n\\t}\\n#endif",lights_toon_fragment:"ToonMaterial material;\\nmaterial.diffuseColor = diffuseColor.rgb;",lights_toon_pars_fragment:"varying vec3 vViewPosition;\\nstruct ToonMaterial {\\n\\tvec3 diffuseColor;\\n};\\nvoid RE_Direct_Toon( const in IncidentLight directLight, const in GeometricContext geometry, const in ToonMaterial material, inout ReflectedLight reflectedLight ) {\\n\\tvec3 irradiance = getGradientIrradiance( geometry.normal, directLight.direction ) * directLight.color;\\n\\treflectedLight.directDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );\\n}\\nvoid RE_IndirectDiffuse_Toon( const in vec3 irradiance, const in GeometricContext geometry, const in ToonMaterial material, inout ReflectedLight reflectedLight ) {\\n\\treflectedLight.indirectDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );\\n}\\n#define RE_Direct\\t\\t\\t\\tRE_Direct_Toon\\n#define RE_IndirectDiffuse\\t\\tRE_IndirectDiffuse_Toon\\n#define Material_LightProbeLOD( material )\\t(0)",lights_phong_fragment:"BlinnPhongMaterial material;\\nmaterial.diffuseColor = diffuseColor.rgb;\\nmaterial.specularColor = specular;\\nmaterial.specularShininess = shininess;\\nmaterial.specularStrength = specularStrength;",lights_phong_pars_fragment:"varying vec3 vViewPosition;\\nstruct BlinnPhongMaterial {\\n\\tvec3 diffuseColor;\\n\\tvec3 specularColor;\\n\\tfloat specularShininess;\\n\\tfloat specularStrength;\\n};\\nvoid RE_Direct_BlinnPhong( const in IncidentLight directLight, const in GeometricContext geometry, const in BlinnPhongMaterial material, inout ReflectedLight reflectedLight ) {\\n\\tfloat dotNL = saturate( dot( geometry.normal, directLight.direction ) );\\n\\tvec3 irradiance = dotNL * directLight.color;\\n\\treflectedLight.directDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );\\n\\treflectedLight.directSpecular += irradiance * BRDF_BlinnPhong( directLight, geometry, material.specularColor, material.specularShininess ) * material.specularStrength;\\n}\\nvoid RE_IndirectDiffuse_BlinnPhong( const in vec3 irradiance, const in GeometricContext geometry, const in BlinnPhongMaterial material, inout ReflectedLight reflectedLight ) {\\n\\treflectedLight.indirectDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );\\n}\\n#define RE_Direct\\t\\t\\t\\tRE_Direct_BlinnPhong\\n#define RE_IndirectDiffuse\\t\\tRE_IndirectDiffuse_BlinnPhong\\n#define Material_LightProbeLOD( material )\\t(0)",lights_physical_fragment:"PhysicalMaterial material;\\nmaterial.diffuseColor = diffuseColor.rgb * ( 1.0 - metalnessFactor );\\nvec3 dxy = max( abs( dFdx( geometryNormal ) ), abs( dFdy( geometryNormal ) ) );\\nfloat geometryRoughness = max( max( dxy.x, dxy.y ), dxy.z );\\nmaterial.roughness = max( roughnessFactor, 0.0525 );material.roughness += geometryRoughness;\\nmaterial.roughness = min( material.roughness, 1.0 );\\n#ifdef IOR\\n\\t#ifdef SPECULAR\\n\\t\\tfloat specularIntensityFactor = specularIntensity;\\n\\t\\tvec3 specularTintFactor = specularTint;\\n\\t\\t#ifdef USE_SPECULARINTENSITYMAP\\n\\t\\t\\tspecularIntensityFactor *= texture2D( specularIntensityMap, vUv ).a;\\n\\t\\t#endif\\n\\t\\t#ifdef USE_SPECULARTINTMAP\\n\\t\\t\\tspecularTintFactor *= specularTintMapTexelToLinear( texture2D( specularTintMap, vUv ) ).rgb;\\n\\t\\t#endif\\n\\t\\tmaterial.specularF90 = mix( specularIntensityFactor, 1.0, metalnessFactor );\\n\\t#else\\n\\t\\tfloat specularIntensityFactor = 1.0;\\n\\t\\tvec3 specularTintFactor = vec3( 1.0 );\\n\\t\\tmaterial.specularF90 = 1.0;\\n\\t#endif\\n\\tmaterial.specularColor = mix( min( pow2( ( ior - 1.0 ) / ( ior + 1.0 ) ) * specularTintFactor, vec3( 1.0 ) ) * specularIntensityFactor, diffuseColor.rgb, metalnessFactor );\\n#else\\n\\tmaterial.specularColor = mix( vec3( 0.04 ), diffuseColor.rgb, metalnessFactor );\\n\\tmaterial.specularF90 = 1.0;\\n#endif\\n#ifdef USE_CLEARCOAT\\n\\tmaterial.clearcoat = clearcoat;\\n\\tmaterial.clearcoatRoughness = clearcoatRoughness;\\n\\tmaterial.clearcoatF0 = vec3( 0.04 );\\n\\tmaterial.clearcoatF90 = 1.0;\\n\\t#ifdef USE_CLEARCOATMAP\\n\\t\\tmaterial.clearcoat *= texture2D( clearcoatMap, vUv ).x;\\n\\t#endif\\n\\t#ifdef USE_CLEARCOAT_ROUGHNESSMAP\\n\\t\\tmaterial.clearcoatRoughness *= texture2D( clearcoatRoughnessMap, vUv ).y;\\n\\t#endif\\n\\tmaterial.clearcoat = saturate( material.clearcoat );\\tmaterial.clearcoatRoughness = max( material.clearcoatRoughness, 0.0525 );\\n\\tmaterial.clearcoatRoughness += geometryRoughness;\\n\\tmaterial.clearcoatRoughness = min( material.clearcoatRoughness, 1.0 );\\n#endif\\n#ifdef USE_SHEEN\\n\\tmaterial.sheenTint = sheenTint;\\n#endif",lights_physical_pars_fragment:"struct PhysicalMaterial {\\n\\tvec3 diffuseColor;\\n\\tfloat roughness;\\n\\tvec3 specularColor;\\n\\tfloat specularF90;\\n\\t#ifdef USE_CLEARCOAT\\n\\t\\tfloat clearcoat;\\n\\t\\tfloat clearcoatRoughness;\\n\\t\\tvec3 clearcoatF0;\\n\\t\\tfloat clearcoatF90;\\n\\t#endif\\n\\t#ifdef USE_SHEEN\\n\\t\\tvec3 sheenTint;\\n\\t#endif\\n};\\nvec3 clearcoatSpecular = vec3( 0.0 );\\nvec2 DFGApprox( const in vec3 normal, const in vec3 viewDir, const in float roughness ) {\\n\\tfloat dotNV = saturate( dot( normal, viewDir ) );\\n\\tconst vec4 c0 = vec4( - 1, - 0.0275, - 0.572, 0.022 );\\n\\tconst vec4 c1 = vec4( 1, 0.0425, 1.04, - 0.04 );\\n\\tvec4 r = roughness * c0 + c1;\\n\\tfloat a004 = min( r.x * r.x, exp2( - 9.28 * dotNV ) ) * r.x + r.y;\\n\\tvec2 fab = vec2( - 1.04, 1.04 ) * a004 + r.zw;\\n\\treturn fab;\\n}\\nvec3 EnvironmentBRDF( const in vec3 normal, const in vec3 viewDir, const in vec3 specularColor, const in float specularF90, const in float roughness ) {\\n\\tvec2 fab = DFGApprox( normal, viewDir, roughness );\\n\\treturn specularColor * fab.x + specularF90 * fab.y;\\n}\\nvoid 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 ) {\\n\\tvec2 fab = DFGApprox( normal, viewDir, roughness );\\n\\tvec3 FssEss = specularColor * fab.x + specularF90 * fab.y;\\n\\tfloat Ess = fab.x + fab.y;\\n\\tfloat Ems = 1.0 - Ess;\\n\\tvec3 Favg = specularColor + ( 1.0 - specularColor ) * 0.047619;\\tvec3 Fms = FssEss * Favg / ( 1.0 - Ems * Favg );\\n\\tsingleScatter += FssEss;\\n\\tmultiScatter += Fms * Ems;\\n}\\n#if NUM_RECT_AREA_LIGHTS > 0\\n\\tvoid RE_Direct_RectArea_Physical( const in RectAreaLight rectAreaLight, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {\\n\\t\\tvec3 normal = geometry.normal;\\n\\t\\tvec3 viewDir = geometry.viewDir;\\n\\t\\tvec3 position = geometry.position;\\n\\t\\tvec3 lightPos = rectAreaLight.position;\\n\\t\\tvec3 halfWidth = rectAreaLight.halfWidth;\\n\\t\\tvec3 halfHeight = rectAreaLight.halfHeight;\\n\\t\\tvec3 lightColor = rectAreaLight.color;\\n\\t\\tfloat roughness = material.roughness;\\n\\t\\tvec3 rectCoords[ 4 ];\\n\\t\\trectCoords[ 0 ] = lightPos + halfWidth - halfHeight;\\t\\trectCoords[ 1 ] = lightPos - halfWidth - halfHeight;\\n\\t\\trectCoords[ 2 ] = lightPos - halfWidth + halfHeight;\\n\\t\\trectCoords[ 3 ] = lightPos + halfWidth + halfHeight;\\n\\t\\tvec2 uv = LTC_Uv( normal, viewDir, roughness );\\n\\t\\tvec4 t1 = texture2D( ltc_1, uv );\\n\\t\\tvec4 t2 = texture2D( ltc_2, uv );\\n\\t\\tmat3 mInv = mat3(\\n\\t\\t\\tvec3( t1.x, 0, t1.y ),\\n\\t\\t\\tvec3( 0, 1, 0 ),\\n\\t\\t\\tvec3( t1.z, 0, t1.w )\\n\\t\\t);\\n\\t\\tvec3 fresnel = ( material.specularColor * t2.x + ( vec3( 1.0 ) - material.specularColor ) * t2.y );\\n\\t\\treflectedLight.directSpecular += lightColor * fresnel * LTC_Evaluate( normal, viewDir, position, mInv, rectCoords );\\n\\t\\treflectedLight.directDiffuse += lightColor * material.diffuseColor * LTC_Evaluate( normal, viewDir, position, mat3( 1.0 ), rectCoords );\\n\\t}\\n#endif\\nvoid RE_Direct_Physical( const in IncidentLight directLight, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {\\n\\tfloat dotNL = saturate( dot( geometry.normal, directLight.direction ) );\\n\\tvec3 irradiance = dotNL * directLight.color;\\n\\t#ifdef USE_CLEARCOAT\\n\\t\\tfloat dotNLcc = saturate( dot( geometry.clearcoatNormal, directLight.direction ) );\\n\\t\\tvec3 ccIrradiance = dotNLcc * directLight.color;\\n\\t\\tclearcoatSpecular += ccIrradiance * BRDF_GGX( directLight, geometry.viewDir, geometry.clearcoatNormal, material.clearcoatF0, material.clearcoatF90, material.clearcoatRoughness );\\n\\t#endif\\n\\t#ifdef USE_SHEEN\\n\\t\\treflectedLight.directSpecular += irradiance * BRDF_Sheen( material.roughness, directLight.direction, geometry, material.sheenTint );\\n\\t#else\\n\\t\\treflectedLight.directSpecular += irradiance * BRDF_GGX( directLight, geometry.viewDir, geometry.normal, material.specularColor, material.specularF90, material.roughness );\\n\\t#endif\\n\\treflectedLight.directDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );\\n}\\nvoid RE_IndirectDiffuse_Physical( const in vec3 irradiance, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {\\n\\treflectedLight.indirectDiffuse += irradiance * BRDF_Lambert( material.diffuseColor );\\n}\\nvoid RE_IndirectSpecular_Physical( const in vec3 radiance, const in vec3 irradiance, const in vec3 clearcoatRadiance, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight) {\\n\\t#ifdef USE_CLEARCOAT\\n\\t\\tclearcoatSpecular += clearcoatRadiance * EnvironmentBRDF( geometry.clearcoatNormal, geometry.viewDir, material.clearcoatF0, material.clearcoatF90, material.clearcoatRoughness );\\n\\t#endif\\n\\tvec3 singleScattering = vec3( 0.0 );\\n\\tvec3 multiScattering = vec3( 0.0 );\\n\\tvec3 cosineWeightedIrradiance = irradiance * RECIPROCAL_PI;\\n\\tcomputeMultiscattering( geometry.normal, geometry.viewDir, material.specularColor, material.specularF90, material.roughness, singleScattering, multiScattering );\\n\\tvec3 diffuse = material.diffuseColor * ( 1.0 - ( singleScattering + multiScattering ) );\\n\\treflectedLight.indirectSpecular += radiance * singleScattering;\\n\\treflectedLight.indirectSpecular += multiScattering * cosineWeightedIrradiance;\\n\\treflectedLight.indirectDiffuse += diffuse * cosineWeightedIrradiance;\\n}\\n#define RE_Direct\\t\\t\\t\\tRE_Direct_Physical\\n#define RE_Direct_RectArea\\t\\tRE_Direct_RectArea_Physical\\n#define RE_IndirectDiffuse\\t\\tRE_IndirectDiffuse_Physical\\n#define RE_IndirectSpecular\\t\\tRE_IndirectSpecular_Physical\\nfloat computeSpecularOcclusion( const in float dotNV, const in float ambientOcclusion, const in float roughness ) {\\n\\treturn saturate( pow( dotNV + ambientOcclusion, exp2( - 16.0 * roughness - 1.0 ) ) - 1.0 + ambientOcclusion );\\n}",lights_fragment_begin:"\\nGeometricContext geometry;\\ngeometry.position = - vViewPosition;\\ngeometry.normal = normal;\\ngeometry.viewDir = ( isOrthographic ) ? vec3( 0, 0, 1 ) : normalize( vViewPosition );\\n#ifdef USE_CLEARCOAT\\n\\tgeometry.clearcoatNormal = clearcoatNormal;\\n#endif\\nIncidentLight directLight;\\n#if ( NUM_POINT_LIGHTS > 0 ) && defined( RE_Direct )\\n\\tPointLight pointLight;\\n\\t#if defined( USE_SHADOWMAP ) && NUM_POINT_LIGHT_SHADOWS > 0\\n\\tPointLightShadow pointLightShadow;\\n\\t#endif\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_POINT_LIGHTS; i ++ ) {\\n\\t\\tpointLight = pointLights[ i ];\\n\\t\\tgetPointLightInfo( pointLight, geometry, directLight );\\n\\t\\t#if defined( USE_SHADOWMAP ) && ( UNROLLED_LOOP_INDEX < NUM_POINT_LIGHT_SHADOWS )\\n\\t\\tpointLightShadow = pointLightShadows[ i ];\\n\\t\\tdirectLight.color *= all( bvec2( directLight.visible, receiveShadow ) ) ? getPointShadow( pointShadowMap[ i ], pointLightShadow.shadowMapSize, pointLightShadow.shadowBias, pointLightShadow.shadowRadius, vPointShadowCoord[ i ], pointLightShadow.shadowCameraNear, pointLightShadow.shadowCameraFar ) : 1.0;\\n\\t\\t#endif\\n\\t\\tRE_Direct( directLight, geometry, material, reflectedLight );\\n\\t}\\n\\t#pragma unroll_loop_end\\n#endif\\n#if ( NUM_SPOT_LIGHTS > 0 ) && defined( RE_Direct )\\n\\tSpotLight spotLight;\\n\\t#if defined( USE_SHADOWMAP ) && NUM_SPOT_LIGHT_SHADOWS > 0\\n\\tSpotLightShadow spotLightShadow;\\n\\t#endif\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_SPOT_LIGHTS; i ++ ) {\\n\\t\\tspotLight = spotLights[ i ];\\n\\t\\tgetSpotLightInfo( spotLight, geometry, directLight );\\n\\t\\t#if defined( USE_SHADOWMAP ) && ( UNROLLED_LOOP_INDEX < NUM_SPOT_LIGHT_SHADOWS )\\n\\t\\tspotLightShadow = spotLightShadows[ i ];\\n\\t\\tdirectLight.color *= all( bvec2( directLight.visible, receiveShadow ) ) ? getShadow( spotShadowMap[ i ], spotLightShadow.shadowMapSize, spotLightShadow.shadowBias, spotLightShadow.shadowRadius, vSpotShadowCoord[ i ] ) : 1.0;\\n\\t\\t#endif\\n\\t\\tRE_Direct( directLight, geometry, material, reflectedLight );\\n\\t}\\n\\t#pragma unroll_loop_end\\n#endif\\n#if ( NUM_DIR_LIGHTS > 0 ) && defined( RE_Direct )\\n\\tDirectionalLight directionalLight;\\n\\t#if defined( USE_SHADOWMAP ) && NUM_DIR_LIGHT_SHADOWS > 0\\n\\tDirectionalLightShadow directionalLightShadow;\\n\\t#endif\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_DIR_LIGHTS; i ++ ) {\\n\\t\\tdirectionalLight = directionalLights[ i ];\\n\\t\\tgetDirectionalLightInfo( directionalLight, geometry, directLight );\\n\\t\\t#if defined( USE_SHADOWMAP ) && ( UNROLLED_LOOP_INDEX < NUM_DIR_LIGHT_SHADOWS )\\n\\t\\tdirectionalLightShadow = directionalLightShadows[ i ];\\n\\t\\tdirectLight.color *= all( bvec2( directLight.visible, receiveShadow ) ) ? getShadow( directionalShadowMap[ i ], directionalLightShadow.shadowMapSize, directionalLightShadow.shadowBias, directionalLightShadow.shadowRadius, vDirectionalShadowCoord[ i ] ) : 1.0;\\n\\t\\t#endif\\n\\t\\tRE_Direct( directLight, geometry, material, reflectedLight );\\n\\t}\\n\\t#pragma unroll_loop_end\\n#endif\\n#if ( NUM_RECT_AREA_LIGHTS > 0 ) && defined( RE_Direct_RectArea )\\n\\tRectAreaLight rectAreaLight;\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_RECT_AREA_LIGHTS; i ++ ) {\\n\\t\\trectAreaLight = rectAreaLights[ i ];\\n\\t\\tRE_Direct_RectArea( rectAreaLight, geometry, material, reflectedLight );\\n\\t}\\n\\t#pragma unroll_loop_end\\n#endif\\n#if defined( RE_IndirectDiffuse )\\n\\tvec3 iblIrradiance = vec3( 0.0 );\\n\\tvec3 irradiance = getAmbientLightIrradiance( ambientLightColor );\\n\\tirradiance += getLightProbeIrradiance( lightProbe, geometry );\\n\\t#if ( NUM_HEMI_LIGHTS > 0 )\\n\\t\\t#pragma unroll_loop_start\\n\\t\\tfor ( int i = 0; i < NUM_HEMI_LIGHTS; i ++ ) {\\n\\t\\t\\tirradiance += getHemisphereLightIrradiance( hemisphereLights[ i ], geometry );\\n\\t\\t}\\n\\t\\t#pragma unroll_loop_end\\n\\t#endif\\n#endif\\n#if defined( RE_IndirectSpecular )\\n\\tvec3 radiance = vec3( 0.0 );\\n\\tvec3 clearcoatRadiance = vec3( 0.0 );\\n#endif",lights_fragment_maps:"#if defined( RE_IndirectDiffuse )\\n\\t#ifdef USE_LIGHTMAP\\n\\t\\tvec4 lightMapTexel = texture2D( lightMap, vUv2 );\\n\\t\\tvec3 lightMapIrradiance = lightMapTexelToLinear( lightMapTexel ).rgb * lightMapIntensity;\\n\\t\\t#ifndef PHYSICALLY_CORRECT_LIGHTS\\n\\t\\t\\tlightMapIrradiance *= PI;\\n\\t\\t#endif\\n\\t\\tirradiance += lightMapIrradiance;\\n\\t#endif\\n\\t#if defined( USE_ENVMAP ) && defined( STANDARD ) && defined( ENVMAP_TYPE_CUBE_UV )\\n\\t\\tiblIrradiance += getIBLIrradiance( geometry );\\n\\t#endif\\n#endif\\n#if defined( USE_ENVMAP ) && defined( RE_IndirectSpecular )\\n\\tradiance += getIBLRadiance( geometry.viewDir, geometry.normal, material.roughness );\\n\\t#ifdef USE_CLEARCOAT\\n\\t\\tclearcoatRadiance += getIBLRadiance( geometry.viewDir, geometry.clearcoatNormal, material.clearcoatRoughness );\\n\\t#endif\\n#endif",lights_fragment_end:"#if defined( RE_IndirectDiffuse )\\n\\tRE_IndirectDiffuse( irradiance, geometry, material, reflectedLight );\\n#endif\\n#if defined( RE_IndirectSpecular )\\n\\tRE_IndirectSpecular( radiance, iblIrradiance, clearcoatRadiance, geometry, material, reflectedLight );\\n#endif",logdepthbuf_fragment:"#if defined( USE_LOGDEPTHBUF ) && defined( USE_LOGDEPTHBUF_EXT )\\n\\tgl_FragDepthEXT = vIsPerspective == 0.0 ? gl_FragCoord.z : log2( vFragDepth ) * logDepthBufFC * 0.5;\\n#endif",logdepthbuf_pars_fragment:"#if defined( USE_LOGDEPTHBUF ) && defined( USE_LOGDEPTHBUF_EXT )\\n\\tuniform float logDepthBufFC;\\n\\tvarying float vFragDepth;\\n\\tvarying float vIsPerspective;\\n#endif",logdepthbuf_pars_vertex:"#ifdef USE_LOGDEPTHBUF\\n\\t#ifdef USE_LOGDEPTHBUF_EXT\\n\\t\\tvarying float vFragDepth;\\n\\t\\tvarying float vIsPerspective;\\n\\t#else\\n\\t\\tuniform float logDepthBufFC;\\n\\t#endif\\n#endif",logdepthbuf_vertex:"#ifdef USE_LOGDEPTHBUF\\n\\t#ifdef USE_LOGDEPTHBUF_EXT\\n\\t\\tvFragDepth = 1.0 + gl_Position.w;\\n\\t\\tvIsPerspective = float( isPerspectiveMatrix( projectionMatrix ) );\\n\\t#else\\n\\t\\tif ( isPerspectiveMatrix( projectionMatrix ) ) {\\n\\t\\t\\tgl_Position.z = log2( max( EPSILON, gl_Position.w + 1.0 ) ) * logDepthBufFC - 1.0;\\n\\t\\t\\tgl_Position.z *= gl_Position.w;\\n\\t\\t}\\n\\t#endif\\n#endif",map_fragment:"#ifdef USE_MAP\\n\\tvec4 texelColor = texture2D( map, vUv );\\n\\ttexelColor = mapTexelToLinear( texelColor );\\n\\tdiffuseColor *= texelColor;\\n#endif",map_pars_fragment:"#ifdef USE_MAP\\n\\tuniform sampler2D map;\\n#endif",map_particle_fragment:"#if defined( USE_MAP ) || defined( USE_ALPHAMAP )\\n\\tvec2 uv = ( uvTransform * vec3( gl_PointCoord.x, 1.0 - gl_PointCoord.y, 1 ) ).xy;\\n#endif\\n#ifdef USE_MAP\\n\\tvec4 mapTexel = texture2D( map, uv );\\n\\tdiffuseColor *= mapTexelToLinear( mapTexel );\\n#endif\\n#ifdef USE_ALPHAMAP\\n\\tdiffuseColor.a *= texture2D( alphaMap, uv ).g;\\n#endif",map_particle_pars_fragment:"#if defined( USE_MAP ) || defined( USE_ALPHAMAP )\\n\\tuniform mat3 uvTransform;\\n#endif\\n#ifdef USE_MAP\\n\\tuniform sampler2D map;\\n#endif\\n#ifdef USE_ALPHAMAP\\n\\tuniform sampler2D alphaMap;\\n#endif",metalnessmap_fragment:"float metalnessFactor = metalness;\\n#ifdef USE_METALNESSMAP\\n\\tvec4 texelMetalness = texture2D( metalnessMap, vUv );\\n\\tmetalnessFactor *= texelMetalness.b;\\n#endif",metalnessmap_pars_fragment:"#ifdef USE_METALNESSMAP\\n\\tuniform sampler2D metalnessMap;\\n#endif",morphnormal_vertex:"#ifdef USE_MORPHNORMALS\\n\\tobjectNormal *= morphTargetBaseInfluence;\\n\\tobjectNormal += morphNormal0 * morphTargetInfluences[ 0 ];\\n\\tobjectNormal += morphNormal1 * morphTargetInfluences[ 1 ];\\n\\tobjectNormal += morphNormal2 * morphTargetInfluences[ 2 ];\\n\\tobjectNormal += morphNormal3 * morphTargetInfluences[ 3 ];\\n#endif",morphtarget_pars_vertex:"#ifdef USE_MORPHTARGETS\\n\\tuniform float morphTargetBaseInfluence;\\n\\t#ifndef USE_MORPHNORMALS\\n\\t\\tuniform float morphTargetInfluences[ 8 ];\\n\\t#else\\n\\t\\tuniform float morphTargetInfluences[ 4 ];\\n\\t#endif\\n#endif",morphtarget_vertex:"#ifdef USE_MORPHTARGETS\\n\\ttransformed *= morphTargetBaseInfluence;\\n\\ttransformed += morphTarget0 * morphTargetInfluences[ 0 ];\\n\\ttransformed += morphTarget1 * morphTargetInfluences[ 1 ];\\n\\ttransformed += morphTarget2 * morphTargetInfluences[ 2 ];\\n\\ttransformed += morphTarget3 * morphTargetInfluences[ 3 ];\\n\\t#ifndef USE_MORPHNORMALS\\n\\t\\ttransformed += morphTarget4 * morphTargetInfluences[ 4 ];\\n\\t\\ttransformed += morphTarget5 * morphTargetInfluences[ 5 ];\\n\\t\\ttransformed += morphTarget6 * morphTargetInfluences[ 6 ];\\n\\t\\ttransformed += morphTarget7 * morphTargetInfluences[ 7 ];\\n\\t#endif\\n#endif",normal_fragment_begin:"float faceDirection = gl_FrontFacing ? 1.0 : - 1.0;\\n#ifdef FLAT_SHADED\\n\\tvec3 fdx = vec3( dFdx( vViewPosition.x ), dFdx( vViewPosition.y ), dFdx( vViewPosition.z ) );\\n\\tvec3 fdy = vec3( dFdy( vViewPosition.x ), dFdy( vViewPosition.y ), dFdy( vViewPosition.z ) );\\n\\tvec3 normal = normalize( cross( fdx, fdy ) );\\n#else\\n\\tvec3 normal = normalize( vNormal );\\n\\t#ifdef DOUBLE_SIDED\\n\\t\\tnormal = normal * faceDirection;\\n\\t#endif\\n\\t#ifdef USE_TANGENT\\n\\t\\tvec3 tangent = normalize( vTangent );\\n\\t\\tvec3 bitangent = normalize( vBitangent );\\n\\t\\t#ifdef DOUBLE_SIDED\\n\\t\\t\\ttangent = tangent * faceDirection;\\n\\t\\t\\tbitangent = bitangent * faceDirection;\\n\\t\\t#endif\\n\\t\\t#if defined( TANGENTSPACE_NORMALMAP ) || defined( USE_CLEARCOAT_NORMALMAP )\\n\\t\\t\\tmat3 vTBN = mat3( tangent, bitangent, normal );\\n\\t\\t#endif\\n\\t#endif\\n#endif\\nvec3 geometryNormal = normal;",normal_fragment_maps:"#ifdef OBJECTSPACE_NORMALMAP\\n\\tnormal = texture2D( normalMap, vUv ).xyz * 2.0 - 1.0;\\n\\t#ifdef FLIP_SIDED\\n\\t\\tnormal = - normal;\\n\\t#endif\\n\\t#ifdef DOUBLE_SIDED\\n\\t\\tnormal = normal * faceDirection;\\n\\t#endif\\n\\tnormal = normalize( normalMatrix * normal );\\n#elif defined( TANGENTSPACE_NORMALMAP )\\n\\tvec3 mapN = texture2D( normalMap, vUv ).xyz * 2.0 - 1.0;\\n\\tmapN.xy *= normalScale;\\n\\t#ifdef USE_TANGENT\\n\\t\\tnormal = normalize( vTBN * mapN );\\n\\t#else\\n\\t\\tnormal = perturbNormal2Arb( - vViewPosition, normal, mapN, faceDirection );\\n\\t#endif\\n#elif defined( USE_BUMPMAP )\\n\\tnormal = perturbNormalArb( - vViewPosition, normal, dHdxy_fwd(), faceDirection );\\n#endif",normal_pars_fragment:"#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n\\t#ifdef USE_TANGENT\\n\\t\\tvarying vec3 vTangent;\\n\\t\\tvarying vec3 vBitangent;\\n\\t#endif\\n#endif",normal_pars_vertex:"#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n\\t#ifdef USE_TANGENT\\n\\t\\tvarying vec3 vTangent;\\n\\t\\tvarying vec3 vBitangent;\\n\\t#endif\\n#endif",normal_vertex:"#ifndef FLAT_SHADED\\n\\tvNormal = normalize( transformedNormal );\\n\\t#ifdef USE_TANGENT\\n\\t\\tvTangent = normalize( transformedTangent );\\n\\t\\tvBitangent = normalize( cross( vNormal, vTangent ) * tangent.w );\\n\\t#endif\\n#endif",normalmap_pars_fragment:"#ifdef USE_NORMALMAP\\n\\tuniform sampler2D normalMap;\\n\\tuniform vec2 normalScale;\\n#endif\\n#ifdef OBJECTSPACE_NORMALMAP\\n\\tuniform mat3 normalMatrix;\\n#endif\\n#if ! defined ( USE_TANGENT ) && ( defined ( TANGENTSPACE_NORMALMAP ) || defined ( USE_CLEARCOAT_NORMALMAP ) )\\n\\tvec3 perturbNormal2Arb( vec3 eye_pos, vec3 surf_norm, vec3 mapN, float faceDirection ) {\\n\\t\\tvec3 q0 = vec3( dFdx( eye_pos.x ), dFdx( eye_pos.y ), dFdx( eye_pos.z ) );\\n\\t\\tvec3 q1 = vec3( dFdy( eye_pos.x ), dFdy( eye_pos.y ), dFdy( eye_pos.z ) );\\n\\t\\tvec2 st0 = dFdx( vUv.st );\\n\\t\\tvec2 st1 = dFdy( vUv.st );\\n\\t\\tvec3 N = surf_norm;\\n\\t\\tvec3 q1perp = cross( q1, N );\\n\\t\\tvec3 q0perp = cross( N, q0 );\\n\\t\\tvec3 T = q1perp * st0.x + q0perp * st1.x;\\n\\t\\tvec3 B = q1perp * st0.y + q0perp * st1.y;\\n\\t\\tfloat det = max( dot( T, T ), dot( B, B ) );\\n\\t\\tfloat scale = ( det == 0.0 ) ? 0.0 : faceDirection * inversesqrt( det );\\n\\t\\treturn normalize( T * ( mapN.x * scale ) + B * ( mapN.y * scale ) + N * mapN.z );\\n\\t}\\n#endif",clearcoat_normal_fragment_begin:"#ifdef USE_CLEARCOAT\\n\\tvec3 clearcoatNormal = geometryNormal;\\n#endif",clearcoat_normal_fragment_maps:"#ifdef USE_CLEARCOAT_NORMALMAP\\n\\tvec3 clearcoatMapN = texture2D( clearcoatNormalMap, vUv ).xyz * 2.0 - 1.0;\\n\\tclearcoatMapN.xy *= clearcoatNormalScale;\\n\\t#ifdef USE_TANGENT\\n\\t\\tclearcoatNormal = normalize( vTBN * clearcoatMapN );\\n\\t#else\\n\\t\\tclearcoatNormal = perturbNormal2Arb( - vViewPosition, clearcoatNormal, clearcoatMapN, faceDirection );\\n\\t#endif\\n#endif",clearcoat_pars_fragment:"#ifdef USE_CLEARCOATMAP\\n\\tuniform sampler2D clearcoatMap;\\n#endif\\n#ifdef USE_CLEARCOAT_ROUGHNESSMAP\\n\\tuniform sampler2D clearcoatRoughnessMap;\\n#endif\\n#ifdef USE_CLEARCOAT_NORMALMAP\\n\\tuniform sampler2D clearcoatNormalMap;\\n\\tuniform vec2 clearcoatNormalScale;\\n#endif",output_fragment:"#ifdef OPAQUE\\ndiffuseColor.a = 1.0;\\n#endif\\n#ifdef USE_TRANSMISSION\\ndiffuseColor.a *= transmissionAlpha + 0.1;\\n#endif\\ngl_FragColor = vec4( outgoingLight, diffuseColor.a );",packing:"vec3 packNormalToRGB( const in vec3 normal ) {\\n\\treturn normalize( normal ) * 0.5 + 0.5;\\n}\\nvec3 unpackRGBToNormal( const in vec3 rgb ) {\\n\\treturn 2.0 * rgb.xyz - 1.0;\\n}\\nconst float PackUpscale = 256. / 255.;const float UnpackDownscale = 255. / 256.;\\nconst vec3 PackFactors = vec3( 256. * 256. * 256., 256. * 256., 256. );\\nconst vec4 UnpackFactors = UnpackDownscale / vec4( PackFactors, 1. );\\nconst float ShiftRight8 = 1. / 256.;\\nvec4 packDepthToRGBA( const in float v ) {\\n\\tvec4 r = vec4( fract( v * PackFactors ), v );\\n\\tr.yzw -= r.xyz * ShiftRight8;\\treturn r * PackUpscale;\\n}\\nfloat unpackRGBAToDepth( const in vec4 v ) {\\n\\treturn dot( v, UnpackFactors );\\n}\\nvec4 pack2HalfToRGBA( vec2 v ) {\\n\\tvec4 r = vec4( v.x, fract( v.x * 255.0 ), v.y, fract( v.y * 255.0 ) );\\n\\treturn vec4( r.x - r.y / 255.0, r.y, r.z - r.w / 255.0, r.w );\\n}\\nvec2 unpackRGBATo2Half( vec4 v ) {\\n\\treturn vec2( v.x + ( v.y / 255.0 ), v.z + ( v.w / 255.0 ) );\\n}\\nfloat viewZToOrthographicDepth( const in float viewZ, const in float near, const in float far ) {\\n\\treturn ( viewZ + near ) / ( near - far );\\n}\\nfloat orthographicDepthToViewZ( const in float linearClipZ, const in float near, const in float far ) {\\n\\treturn linearClipZ * ( near - far ) - near;\\n}\\nfloat viewZToPerspectiveDepth( const in float viewZ, const in float near, const in float far ) {\\n\\treturn ( ( near + viewZ ) * far ) / ( ( far - near ) * viewZ );\\n}\\nfloat perspectiveDepthToViewZ( const in float invClipZ, const in float near, const in float far ) {\\n\\treturn ( near * far ) / ( ( far - near ) * invClipZ - far );\\n}",premultiplied_alpha_fragment:"#ifdef PREMULTIPLIED_ALPHA\\n\\tgl_FragColor.rgb *= gl_FragColor.a;\\n#endif",project_vertex:"vec4 mvPosition = vec4( transformed, 1.0 );\\n#ifdef USE_INSTANCING\\n\\tmvPosition = instanceMatrix * mvPosition;\\n#endif\\nmvPosition = modelViewMatrix * mvPosition;\\ngl_Position = projectionMatrix * mvPosition;",dithering_fragment:"#ifdef DITHERING\\n\\tgl_FragColor.rgb = dithering( gl_FragColor.rgb );\\n#endif",dithering_pars_fragment:"#ifdef DITHERING\\n\\tvec3 dithering( vec3 color ) {\\n\\t\\tfloat grid_position = rand( gl_FragCoord.xy );\\n\\t\\tvec3 dither_shift_RGB = vec3( 0.25 / 255.0, -0.25 / 255.0, 0.25 / 255.0 );\\n\\t\\tdither_shift_RGB = mix( 2.0 * dither_shift_RGB, -2.0 * dither_shift_RGB, grid_position );\\n\\t\\treturn color + dither_shift_RGB;\\n\\t}\\n#endif",roughnessmap_fragment:"float roughnessFactor = roughness;\\n#ifdef USE_ROUGHNESSMAP\\n\\tvec4 texelRoughness = texture2D( roughnessMap, vUv );\\n\\troughnessFactor *= texelRoughness.g;\\n#endif",roughnessmap_pars_fragment:"#ifdef USE_ROUGHNESSMAP\\n\\tuniform sampler2D roughnessMap;\\n#endif",shadowmap_pars_fragment:"#ifdef USE_SHADOWMAP\\n\\t#if NUM_DIR_LIGHT_SHADOWS > 0\\n\\t\\tuniform sampler2D directionalShadowMap[ NUM_DIR_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vDirectionalShadowCoord[ NUM_DIR_LIGHT_SHADOWS ];\\n\\t\\tstruct DirectionalLightShadow {\\n\\t\\t\\tfloat shadowBias;\\n\\t\\t\\tfloat shadowNormalBias;\\n\\t\\t\\tfloat shadowRadius;\\n\\t\\t\\tvec2 shadowMapSize;\\n\\t\\t};\\n\\t\\tuniform DirectionalLightShadow directionalLightShadows[ NUM_DIR_LIGHT_SHADOWS ];\\n\\t#endif\\n\\t#if NUM_SPOT_LIGHT_SHADOWS > 0\\n\\t\\tuniform sampler2D spotShadowMap[ NUM_SPOT_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vSpotShadowCoord[ NUM_SPOT_LIGHT_SHADOWS ];\\n\\t\\tstruct SpotLightShadow {\\n\\t\\t\\tfloat shadowBias;\\n\\t\\t\\tfloat shadowNormalBias;\\n\\t\\t\\tfloat shadowRadius;\\n\\t\\t\\tvec2 shadowMapSize;\\n\\t\\t};\\n\\t\\tuniform SpotLightShadow spotLightShadows[ NUM_SPOT_LIGHT_SHADOWS ];\\n\\t#endif\\n\\t#if NUM_POINT_LIGHT_SHADOWS > 0\\n\\t\\tuniform sampler2D pointShadowMap[ NUM_POINT_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vPointShadowCoord[ NUM_POINT_LIGHT_SHADOWS ];\\n\\t\\tstruct PointLightShadow {\\n\\t\\t\\tfloat shadowBias;\\n\\t\\t\\tfloat shadowNormalBias;\\n\\t\\t\\tfloat shadowRadius;\\n\\t\\t\\tvec2 shadowMapSize;\\n\\t\\t\\tfloat shadowCameraNear;\\n\\t\\t\\tfloat shadowCameraFar;\\n\\t\\t};\\n\\t\\tuniform PointLightShadow pointLightShadows[ NUM_POINT_LIGHT_SHADOWS ];\\n\\t#endif\\n\\tfloat texture2DCompare( sampler2D depths, vec2 uv, float compare ) {\\n\\t\\treturn step( compare, unpackRGBAToDepth( texture2D( depths, uv ) ) );\\n\\t}\\n\\tvec2 texture2DDistribution( sampler2D shadow, vec2 uv ) {\\n\\t\\treturn unpackRGBATo2Half( texture2D( shadow, uv ) );\\n\\t}\\n\\tfloat VSMShadow (sampler2D shadow, vec2 uv, float compare ){\\n\\t\\tfloat occlusion = 1.0;\\n\\t\\tvec2 distribution = texture2DDistribution( shadow, uv );\\n\\t\\tfloat hard_shadow = step( compare , distribution.x );\\n\\t\\tif (hard_shadow != 1.0 ) {\\n\\t\\t\\tfloat distance = compare - distribution.x ;\\n\\t\\t\\tfloat variance = max( 0.00000, distribution.y * distribution.y );\\n\\t\\t\\tfloat softness_probability = variance / (variance + distance * distance );\\t\\t\\tsoftness_probability = clamp( ( softness_probability - 0.3 ) / ( 0.95 - 0.3 ), 0.0, 1.0 );\\t\\t\\tocclusion = clamp( max( hard_shadow, softness_probability ), 0.0, 1.0 );\\n\\t\\t}\\n\\t\\treturn occlusion;\\n\\t}\\n\\tfloat getShadow( sampler2D shadowMap, vec2 shadowMapSize, float shadowBias, float shadowRadius, vec4 shadowCoord ) {\\n\\t\\tfloat shadow = 1.0;\\n\\t\\tshadowCoord.xyz /= shadowCoord.w;\\n\\t\\tshadowCoord.z += shadowBias;\\n\\t\\tbvec4 inFrustumVec = bvec4 ( shadowCoord.x >= 0.0, shadowCoord.x <= 1.0, shadowCoord.y >= 0.0, shadowCoord.y <= 1.0 );\\n\\t\\tbool inFrustum = all( inFrustumVec );\\n\\t\\tbvec2 frustumTestVec = bvec2( inFrustum, shadowCoord.z <= 1.0 );\\n\\t\\tbool frustumTest = all( frustumTestVec );\\n\\t\\tif ( frustumTest ) {\\n\\t\\t#if defined( SHADOWMAP_TYPE_PCF )\\n\\t\\t\\tvec2 texelSize = vec2( 1.0 ) / shadowMapSize;\\n\\t\\t\\tfloat dx0 = - texelSize.x * shadowRadius;\\n\\t\\t\\tfloat dy0 = - texelSize.y * shadowRadius;\\n\\t\\t\\tfloat dx1 = + texelSize.x * shadowRadius;\\n\\t\\t\\tfloat dy1 = + texelSize.y * shadowRadius;\\n\\t\\t\\tfloat dx2 = dx0 / 2.0;\\n\\t\\t\\tfloat dy2 = dy0 / 2.0;\\n\\t\\t\\tfloat dx3 = dx1 / 2.0;\\n\\t\\t\\tfloat dy3 = dy1 / 2.0;\\n\\t\\t\\tshadow = (\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, dy0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, dy0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx2, dy2 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy2 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx3, dy2 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx2, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy, shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx3, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx2, dy3 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy3 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx3, dy3 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, dy1 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy1 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, dy1 ), shadowCoord.z )\\n\\t\\t\\t) * ( 1.0 / 17.0 );\\n\\t\\t#elif defined( SHADOWMAP_TYPE_PCF_SOFT )\\n\\t\\t\\tvec2 texelSize = vec2( 1.0 ) / shadowMapSize;\\n\\t\\t\\tfloat dx = texelSize.x;\\n\\t\\t\\tfloat dy = texelSize.y;\\n\\t\\t\\tvec2 uv = shadowCoord.xy;\\n\\t\\t\\tvec2 f = fract( uv * shadowMapSize + 0.5 );\\n\\t\\t\\tuv -= f * texelSize;\\n\\t\\t\\tshadow = (\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, uv, shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, uv + vec2( dx, 0.0 ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, uv + vec2( 0.0, dy ), shadowCoord.z ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, uv + texelSize, shadowCoord.z ) +\\n\\t\\t\\t\\tmix( texture2DCompare( shadowMap, uv + vec2( -dx, 0.0 ), shadowCoord.z ), \\n\\t\\t\\t\\t\\t texture2DCompare( shadowMap, uv + vec2( 2.0 * dx, 0.0 ), shadowCoord.z ),\\n\\t\\t\\t\\t\\t f.x ) +\\n\\t\\t\\t\\tmix( texture2DCompare( shadowMap, uv + vec2( -dx, dy ), shadowCoord.z ), \\n\\t\\t\\t\\t\\t texture2DCompare( shadowMap, uv + vec2( 2.0 * dx, dy ), shadowCoord.z ),\\n\\t\\t\\t\\t\\t f.x ) +\\n\\t\\t\\t\\tmix( texture2DCompare( shadowMap, uv + vec2( 0.0, -dy ), shadowCoord.z ), \\n\\t\\t\\t\\t\\t texture2DCompare( shadowMap, uv + vec2( 0.0, 2.0 * dy ), shadowCoord.z ),\\n\\t\\t\\t\\t\\t f.y ) +\\n\\t\\t\\t\\tmix( texture2DCompare( shadowMap, uv + vec2( dx, -dy ), shadowCoord.z ), \\n\\t\\t\\t\\t\\t texture2DCompare( shadowMap, uv + vec2( dx, 2.0 * dy ), shadowCoord.z ),\\n\\t\\t\\t\\t\\t f.y ) +\\n\\t\\t\\t\\tmix( mix( texture2DCompare( shadowMap, uv + vec2( -dx, -dy ), shadowCoord.z ), \\n\\t\\t\\t\\t\\t\\t texture2DCompare( shadowMap, uv + vec2( 2.0 * dx, -dy ), shadowCoord.z ),\\n\\t\\t\\t\\t\\t\\t f.x ),\\n\\t\\t\\t\\t\\t mix( texture2DCompare( shadowMap, uv + vec2( -dx, 2.0 * dy ), shadowCoord.z ), \\n\\t\\t\\t\\t\\t\\t texture2DCompare( shadowMap, uv + vec2( 2.0 * dx, 2.0 * dy ), shadowCoord.z ),\\n\\t\\t\\t\\t\\t\\t f.x ),\\n\\t\\t\\t\\t\\t f.y )\\n\\t\\t\\t) * ( 1.0 / 9.0 );\\n\\t\\t#elif defined( SHADOWMAP_TYPE_VSM )\\n\\t\\t\\tshadow = VSMShadow( shadowMap, shadowCoord.xy, shadowCoord.z );\\n\\t\\t#else\\n\\t\\t\\tshadow = texture2DCompare( shadowMap, shadowCoord.xy, shadowCoord.z );\\n\\t\\t#endif\\n\\t\\t}\\n\\t\\treturn shadow;\\n\\t}\\n\\tvec2 cubeToUV( vec3 v, float texelSizeY ) {\\n\\t\\tvec3 absV = abs( v );\\n\\t\\tfloat scaleToCube = 1.0 / max( absV.x, max( absV.y, absV.z ) );\\n\\t\\tabsV *= scaleToCube;\\n\\t\\tv *= scaleToCube * ( 1.0 - 2.0 * texelSizeY );\\n\\t\\tvec2 planar = v.xy;\\n\\t\\tfloat almostATexel = 1.5 * texelSizeY;\\n\\t\\tfloat almostOne = 1.0 - almostATexel;\\n\\t\\tif ( absV.z >= almostOne ) {\\n\\t\\t\\tif ( v.z > 0.0 )\\n\\t\\t\\t\\tplanar.x = 4.0 - v.x;\\n\\t\\t} else if ( absV.x >= almostOne ) {\\n\\t\\t\\tfloat signX = sign( v.x );\\n\\t\\t\\tplanar.x = v.z * signX + 2.0 * signX;\\n\\t\\t} else if ( absV.y >= almostOne ) {\\n\\t\\t\\tfloat signY = sign( v.y );\\n\\t\\t\\tplanar.x = v.x + 2.0 * signY + 2.0;\\n\\t\\t\\tplanar.y = v.z * signY - 2.0;\\n\\t\\t}\\n\\t\\treturn vec2( 0.125, 0.25 ) * planar + vec2( 0.375, 0.75 );\\n\\t}\\n\\tfloat getPointShadow( sampler2D shadowMap, vec2 shadowMapSize, float shadowBias, float shadowRadius, vec4 shadowCoord, float shadowCameraNear, float shadowCameraFar ) {\\n\\t\\tvec2 texelSize = vec2( 1.0 ) / ( shadowMapSize * vec2( 4.0, 2.0 ) );\\n\\t\\tvec3 lightToPosition = shadowCoord.xyz;\\n\\t\\tfloat dp = ( length( lightToPosition ) - shadowCameraNear ) / ( shadowCameraFar - shadowCameraNear );\\t\\tdp += shadowBias;\\n\\t\\tvec3 bd3D = normalize( lightToPosition );\\n\\t\\t#if defined( SHADOWMAP_TYPE_PCF ) || defined( SHADOWMAP_TYPE_PCF_SOFT ) || defined( SHADOWMAP_TYPE_VSM )\\n\\t\\t\\tvec2 offset = vec2( - 1, 1 ) * shadowRadius * texelSize.y;\\n\\t\\t\\treturn (\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xyy, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yyy, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xyx, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yyx, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xxy, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yxy, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xxx, texelSize.y ), dp ) +\\n\\t\\t\\t\\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yxx, texelSize.y ), dp )\\n\\t\\t\\t) * ( 1.0 / 9.0 );\\n\\t\\t#else\\n\\t\\t\\treturn texture2DCompare( shadowMap, cubeToUV( bd3D, texelSize.y ), dp );\\n\\t\\t#endif\\n\\t}\\n#endif",shadowmap_pars_vertex:"#ifdef USE_SHADOWMAP\\n\\t#if NUM_DIR_LIGHT_SHADOWS > 0\\n\\t\\tuniform mat4 directionalShadowMatrix[ NUM_DIR_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vDirectionalShadowCoord[ NUM_DIR_LIGHT_SHADOWS ];\\n\\t\\tstruct DirectionalLightShadow {\\n\\t\\t\\tfloat shadowBias;\\n\\t\\t\\tfloat shadowNormalBias;\\n\\t\\t\\tfloat shadowRadius;\\n\\t\\t\\tvec2 shadowMapSize;\\n\\t\\t};\\n\\t\\tuniform DirectionalLightShadow directionalLightShadows[ NUM_DIR_LIGHT_SHADOWS ];\\n\\t#endif\\n\\t#if NUM_SPOT_LIGHT_SHADOWS > 0\\n\\t\\tuniform mat4 spotShadowMatrix[ NUM_SPOT_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vSpotShadowCoord[ NUM_SPOT_LIGHT_SHADOWS ];\\n\\t\\tstruct SpotLightShadow {\\n\\t\\t\\tfloat shadowBias;\\n\\t\\t\\tfloat shadowNormalBias;\\n\\t\\t\\tfloat shadowRadius;\\n\\t\\t\\tvec2 shadowMapSize;\\n\\t\\t};\\n\\t\\tuniform SpotLightShadow spotLightShadows[ NUM_SPOT_LIGHT_SHADOWS ];\\n\\t#endif\\n\\t#if NUM_POINT_LIGHT_SHADOWS > 0\\n\\t\\tuniform mat4 pointShadowMatrix[ NUM_POINT_LIGHT_SHADOWS ];\\n\\t\\tvarying vec4 vPointShadowCoord[ NUM_POINT_LIGHT_SHADOWS ];\\n\\t\\tstruct PointLightShadow {\\n\\t\\t\\tfloat shadowBias;\\n\\t\\t\\tfloat shadowNormalBias;\\n\\t\\t\\tfloat shadowRadius;\\n\\t\\t\\tvec2 shadowMapSize;\\n\\t\\t\\tfloat shadowCameraNear;\\n\\t\\t\\tfloat shadowCameraFar;\\n\\t\\t};\\n\\t\\tuniform PointLightShadow pointLightShadows[ NUM_POINT_LIGHT_SHADOWS ];\\n\\t#endif\\n#endif",shadowmap_vertex:"#ifdef USE_SHADOWMAP\\n\\t#if NUM_DIR_LIGHT_SHADOWS > 0 || NUM_SPOT_LIGHT_SHADOWS > 0 || NUM_POINT_LIGHT_SHADOWS > 0\\n\\t\\tvec3 shadowWorldNormal = inverseTransformDirection( transformedNormal, viewMatrix );\\n\\t\\tvec4 shadowWorldPosition;\\n\\t#endif\\n\\t#if NUM_DIR_LIGHT_SHADOWS > 0\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_DIR_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tshadowWorldPosition = worldPosition + vec4( shadowWorldNormal * directionalLightShadows[ i ].shadowNormalBias, 0 );\\n\\t\\tvDirectionalShadowCoord[ i ] = directionalShadowMatrix[ i ] * shadowWorldPosition;\\n\\t}\\n\\t#pragma unroll_loop_end\\n\\t#endif\\n\\t#if NUM_SPOT_LIGHT_SHADOWS > 0\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_SPOT_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tshadowWorldPosition = worldPosition + vec4( shadowWorldNormal * spotLightShadows[ i ].shadowNormalBias, 0 );\\n\\t\\tvSpotShadowCoord[ i ] = spotShadowMatrix[ i ] * shadowWorldPosition;\\n\\t}\\n\\t#pragma unroll_loop_end\\n\\t#endif\\n\\t#if NUM_POINT_LIGHT_SHADOWS > 0\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_POINT_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tshadowWorldPosition = worldPosition + vec4( shadowWorldNormal * pointLightShadows[ i ].shadowNormalBias, 0 );\\n\\t\\tvPointShadowCoord[ i ] = pointShadowMatrix[ i ] * shadowWorldPosition;\\n\\t}\\n\\t#pragma unroll_loop_end\\n\\t#endif\\n#endif",shadowmask_pars_fragment:"float getShadowMask() {\\n\\tfloat shadow = 1.0;\\n\\t#ifdef USE_SHADOWMAP\\n\\t#if NUM_DIR_LIGHT_SHADOWS > 0\\n\\tDirectionalLightShadow directionalLight;\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_DIR_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tdirectionalLight = directionalLightShadows[ i ];\\n\\t\\tshadow *= receiveShadow ? getShadow( directionalShadowMap[ i ], directionalLight.shadowMapSize, directionalLight.shadowBias, directionalLight.shadowRadius, vDirectionalShadowCoord[ i ] ) : 1.0;\\n\\t}\\n\\t#pragma unroll_loop_end\\n\\t#endif\\n\\t#if NUM_SPOT_LIGHT_SHADOWS > 0\\n\\tSpotLightShadow spotLight;\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_SPOT_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tspotLight = spotLightShadows[ i ];\\n\\t\\tshadow *= receiveShadow ? getShadow( spotShadowMap[ i ], spotLight.shadowMapSize, spotLight.shadowBias, spotLight.shadowRadius, vSpotShadowCoord[ i ] ) : 1.0;\\n\\t}\\n\\t#pragma unroll_loop_end\\n\\t#endif\\n\\t#if NUM_POINT_LIGHT_SHADOWS > 0\\n\\tPointLightShadow pointLight;\\n\\t#pragma unroll_loop_start\\n\\tfor ( int i = 0; i < NUM_POINT_LIGHT_SHADOWS; i ++ ) {\\n\\t\\tpointLight = pointLightShadows[ i ];\\n\\t\\tshadow *= receiveShadow ? getPointShadow( pointShadowMap[ i ], pointLight.shadowMapSize, pointLight.shadowBias, pointLight.shadowRadius, vPointShadowCoord[ i ], pointLight.shadowCameraNear, pointLight.shadowCameraFar ) : 1.0;\\n\\t}\\n\\t#pragma unroll_loop_end\\n\\t#endif\\n\\t#endif\\n\\treturn shadow;\\n}",skinbase_vertex:"#ifdef USE_SKINNING\\n\\tmat4 boneMatX = getBoneMatrix( skinIndex.x );\\n\\tmat4 boneMatY = getBoneMatrix( skinIndex.y );\\n\\tmat4 boneMatZ = getBoneMatrix( skinIndex.z );\\n\\tmat4 boneMatW = getBoneMatrix( skinIndex.w );\\n#endif",skinning_pars_vertex:"#ifdef USE_SKINNING\\n\\tuniform mat4 bindMatrix;\\n\\tuniform mat4 bindMatrixInverse;\\n\\t#ifdef BONE_TEXTURE\\n\\t\\tuniform highp sampler2D boneTexture;\\n\\t\\tuniform int boneTextureSize;\\n\\t\\tmat4 getBoneMatrix( const in float i ) {\\n\\t\\t\\tfloat j = i * 4.0;\\n\\t\\t\\tfloat x = mod( j, float( boneTextureSize ) );\\n\\t\\t\\tfloat y = floor( j / float( boneTextureSize ) );\\n\\t\\t\\tfloat dx = 1.0 / float( boneTextureSize );\\n\\t\\t\\tfloat dy = 1.0 / float( boneTextureSize );\\n\\t\\t\\ty = dy * ( y + 0.5 );\\n\\t\\t\\tvec4 v1 = texture2D( boneTexture, vec2( dx * ( x + 0.5 ), y ) );\\n\\t\\t\\tvec4 v2 = texture2D( boneTexture, vec2( dx * ( x + 1.5 ), y ) );\\n\\t\\t\\tvec4 v3 = texture2D( boneTexture, vec2( dx * ( x + 2.5 ), y ) );\\n\\t\\t\\tvec4 v4 = texture2D( boneTexture, vec2( dx * ( x + 3.5 ), y ) );\\n\\t\\t\\tmat4 bone = mat4( v1, v2, v3, v4 );\\n\\t\\t\\treturn bone;\\n\\t\\t}\\n\\t#else\\n\\t\\tuniform mat4 boneMatrices[ MAX_BONES ];\\n\\t\\tmat4 getBoneMatrix( const in float i ) {\\n\\t\\t\\tmat4 bone = boneMatrices[ int(i) ];\\n\\t\\t\\treturn bone;\\n\\t\\t}\\n\\t#endif\\n#endif",skinning_vertex:"#ifdef USE_SKINNING\\n\\tvec4 skinVertex = bindMatrix * vec4( transformed, 1.0 );\\n\\tvec4 skinned = vec4( 0.0 );\\n\\tskinned += boneMatX * skinVertex * skinWeight.x;\\n\\tskinned += boneMatY * skinVertex * skinWeight.y;\\n\\tskinned += boneMatZ * skinVertex * skinWeight.z;\\n\\tskinned += boneMatW * skinVertex * skinWeight.w;\\n\\ttransformed = ( bindMatrixInverse * skinned ).xyz;\\n#endif",skinnormal_vertex:"#ifdef USE_SKINNING\\n\\tmat4 skinMatrix = mat4( 0.0 );\\n\\tskinMatrix += skinWeight.x * boneMatX;\\n\\tskinMatrix += skinWeight.y * boneMatY;\\n\\tskinMatrix += skinWeight.z * boneMatZ;\\n\\tskinMatrix += skinWeight.w * boneMatW;\\n\\tskinMatrix = bindMatrixInverse * skinMatrix * bindMatrix;\\n\\tobjectNormal = vec4( skinMatrix * vec4( objectNormal, 0.0 ) ).xyz;\\n\\t#ifdef USE_TANGENT\\n\\t\\tobjectTangent = vec4( skinMatrix * vec4( objectTangent, 0.0 ) ).xyz;\\n\\t#endif\\n#endif",specularmap_fragment:"float specularStrength;\\n#ifdef USE_SPECULARMAP\\n\\tvec4 texelSpecular = texture2D( specularMap, vUv );\\n\\tspecularStrength = texelSpecular.r;\\n#else\\n\\tspecularStrength = 1.0;\\n#endif",specularmap_pars_fragment:"#ifdef USE_SPECULARMAP\\n\\tuniform sampler2D specularMap;\\n#endif",tonemapping_fragment:"#if defined( TONE_MAPPING )\\n\\tgl_FragColor.rgb = toneMapping( gl_FragColor.rgb );\\n#endif",tonemapping_pars_fragment:"#ifndef saturate\\n#define saturate( a ) clamp( a, 0.0, 1.0 )\\n#endif\\nuniform float toneMappingExposure;\\nvec3 LinearToneMapping( vec3 color ) {\\n\\treturn toneMappingExposure * color;\\n}\\nvec3 ReinhardToneMapping( vec3 color ) {\\n\\tcolor *= toneMappingExposure;\\n\\treturn saturate( color / ( vec3( 1.0 ) + color ) );\\n}\\nvec3 OptimizedCineonToneMapping( vec3 color ) {\\n\\tcolor *= toneMappingExposure;\\n\\tcolor = max( vec3( 0.0 ), color - 0.004 );\\n\\treturn pow( ( color * ( 6.2 * color + 0.5 ) ) / ( color * ( 6.2 * color + 1.7 ) + 0.06 ), vec3( 2.2 ) );\\n}\\nvec3 RRTAndODTFit( vec3 v ) {\\n\\tvec3 a = v * ( v + 0.0245786 ) - 0.000090537;\\n\\tvec3 b = v * ( 0.983729 * v + 0.4329510 ) + 0.238081;\\n\\treturn a / b;\\n}\\nvec3 ACESFilmicToneMapping( vec3 color ) {\\n\\tconst mat3 ACESInputMat = mat3(\\n\\t\\tvec3( 0.59719, 0.07600, 0.02840 ),\\t\\tvec3( 0.35458, 0.90834, 0.13383 ),\\n\\t\\tvec3( 0.04823, 0.01566, 0.83777 )\\n\\t);\\n\\tconst mat3 ACESOutputMat = mat3(\\n\\t\\tvec3( 1.60475, -0.10208, -0.00327 ),\\t\\tvec3( -0.53108, 1.10813, -0.07276 ),\\n\\t\\tvec3( -0.07367, -0.00605, 1.07602 )\\n\\t);\\n\\tcolor *= toneMappingExposure / 0.6;\\n\\tcolor = ACESInputMat * color;\\n\\tcolor = RRTAndODTFit( color );\\n\\tcolor = ACESOutputMat * color;\\n\\treturn saturate( color );\\n}\\nvec3 CustomToneMapping( vec3 color ) { return color; }",transmission_fragment:"#ifdef USE_TRANSMISSION\\n\\tfloat transmissionAlpha = 1.0;\\n\\tfloat transmissionFactor = transmission;\\n\\tfloat thicknessFactor = thickness;\\n\\t#ifdef USE_TRANSMISSIONMAP\\n\\t\\ttransmissionFactor *= texture2D( transmissionMap, vUv ).r;\\n\\t#endif\\n\\t#ifdef USE_THICKNESSMAP\\n\\t\\tthicknessFactor *= texture2D( thicknessMap, vUv ).g;\\n\\t#endif\\n\\tvec3 pos = vWorldPosition;\\n\\tvec3 v = normalize( cameraPosition - pos );\\n\\tvec3 n = inverseTransformDirection( normal, viewMatrix );\\n\\tvec4 transmission = getIBLVolumeRefraction(\\n\\t\\tn, v, roughnessFactor, material.diffuseColor, material.specularColor, material.specularF90,\\n\\t\\tpos, modelMatrix, viewMatrix, projectionMatrix, ior, thicknessFactor,\\n\\t\\tattenuationTint, attenuationDistance );\\n\\ttotalDiffuse = mix( totalDiffuse, transmission.rgb, transmissionFactor );\\n\\ttransmissionAlpha = transmission.a;\\n#endif",transmission_pars_fragment:"#ifdef USE_TRANSMISSION\\n\\tuniform float transmission;\\n\\tuniform float thickness;\\n\\tuniform float attenuationDistance;\\n\\tuniform vec3 attenuationTint;\\n\\t#ifdef USE_TRANSMISSIONMAP\\n\\t\\tuniform sampler2D transmissionMap;\\n\\t#endif\\n\\t#ifdef USE_THICKNESSMAP\\n\\t\\tuniform sampler2D thicknessMap;\\n\\t#endif\\n\\tuniform vec2 transmissionSamplerSize;\\n\\tuniform sampler2D transmissionSamplerMap;\\n\\tuniform mat4 modelMatrix;\\n\\tuniform mat4 projectionMatrix;\\n\\tvarying vec3 vWorldPosition;\\n\\tvec3 getVolumeTransmissionRay( vec3 n, vec3 v, float thickness, float ior, mat4 modelMatrix ) {\\n\\t\\tvec3 refractionVector = refract( - v, normalize( n ), 1.0 / ior );\\n\\t\\tvec3 modelScale;\\n\\t\\tmodelScale.x = length( vec3( modelMatrix[ 0 ].xyz ) );\\n\\t\\tmodelScale.y = length( vec3( modelMatrix[ 1 ].xyz ) );\\n\\t\\tmodelScale.z = length( vec3( modelMatrix[ 2 ].xyz ) );\\n\\t\\treturn normalize( refractionVector ) * thickness * modelScale;\\n\\t}\\n\\tfloat applyIorToRoughness( float roughness, float ior ) {\\n\\t\\treturn roughness * clamp( ior * 2.0 - 2.0, 0.0, 1.0 );\\n\\t}\\n\\tvec4 getTransmissionSample( vec2 fragCoord, float roughness, float ior ) {\\n\\t\\tfloat framebufferLod = log2( transmissionSamplerSize.x ) * applyIorToRoughness( roughness, ior );\\n\\t\\t#ifdef TEXTURE_LOD_EXT\\n\\t\\t\\treturn texture2DLodEXT( transmissionSamplerMap, fragCoord.xy, framebufferLod );\\n\\t\\t#else\\n\\t\\t\\treturn texture2D( transmissionSamplerMap, fragCoord.xy, framebufferLod );\\n\\t\\t#endif\\n\\t}\\n\\tvec3 applyVolumeAttenuation( vec3 radiance, float transmissionDistance, vec3 attenuationColor, float attenuationDistance ) {\\n\\t\\tif ( attenuationDistance == 0.0 ) {\\n\\t\\t\\treturn radiance;\\n\\t\\t} else {\\n\\t\\t\\tvec3 attenuationCoefficient = -log( attenuationColor ) / attenuationDistance;\\n\\t\\t\\tvec3 transmittance = exp( - attenuationCoefficient * transmissionDistance );\\t\\t\\treturn transmittance * radiance;\\n\\t\\t}\\n\\t}\\n\\tvec4 getIBLVolumeRefraction( vec3 n, vec3 v, float roughness, vec3 diffuseColor, vec3 specularColor, float specularF90,\\n\\t\\tvec3 position, mat4 modelMatrix, mat4 viewMatrix, mat4 projMatrix, float ior, float thickness,\\n\\t\\tvec3 attenuationColor, float attenuationDistance ) {\\n\\t\\tvec3 transmissionRay = getVolumeTransmissionRay( n, v, thickness, ior, modelMatrix );\\n\\t\\tvec3 refractedRayExit = position + transmissionRay;\\n\\t\\tvec4 ndcPos = projMatrix * viewMatrix * vec4( refractedRayExit, 1.0 );\\n\\t\\tvec2 refractionCoords = ndcPos.xy / ndcPos.w;\\n\\t\\trefractionCoords += 1.0;\\n\\t\\trefractionCoords /= 2.0;\\n\\t\\tvec4 transmittedLight = getTransmissionSample( refractionCoords, roughness, ior );\\n\\t\\tvec3 attenuatedColor = applyVolumeAttenuation( transmittedLight.rgb, length( transmissionRay ), attenuationColor, attenuationDistance );\\n\\t\\tvec3 F = EnvironmentBRDF( n, v, specularColor, specularF90, roughness );\\n\\t\\treturn vec4( ( 1.0 - F ) * attenuatedColor * diffuseColor, transmittedLight.a );\\n\\t}\\n#endif",uv_pars_fragment:"#if ( defined( USE_UV ) && ! defined( UVS_VERTEX_ONLY ) )\\n\\tvarying vec2 vUv;\\n#endif",uv_pars_vertex:"#ifdef USE_UV\\n\\t#ifdef UVS_VERTEX_ONLY\\n\\t\\tvec2 vUv;\\n\\t#else\\n\\t\\tvarying vec2 vUv;\\n\\t#endif\\n\\tuniform mat3 uvTransform;\\n#endif",uv_vertex:"#ifdef USE_UV\\n\\tvUv = ( uvTransform * vec3( uv, 1 ) ).xy;\\n#endif",uv2_pars_fragment:"#if defined( USE_LIGHTMAP ) || defined( USE_AOMAP )\\n\\tvarying vec2 vUv2;\\n#endif",uv2_pars_vertex:"#if defined( USE_LIGHTMAP ) || defined( USE_AOMAP )\\n\\tattribute vec2 uv2;\\n\\tvarying vec2 vUv2;\\n\\tuniform mat3 uv2Transform;\\n#endif",uv2_vertex:"#if defined( USE_LIGHTMAP ) || defined( USE_AOMAP )\\n\\tvUv2 = ( uv2Transform * vec3( uv2, 1 ) ).xy;\\n#endif",worldpos_vertex:"#if defined( USE_ENVMAP ) || defined( DISTANCE ) || defined ( USE_SHADOWMAP ) || defined ( USE_TRANSMISSION )\\n\\tvec4 worldPosition = vec4( transformed, 1.0 );\\n\\t#ifdef USE_INSTANCING\\n\\t\\tworldPosition = instanceMatrix * worldPosition;\\n\\t#endif\\n\\tworldPosition = modelMatrix * worldPosition;\\n#endif",background_frag:"uniform sampler2D t2D;\\nvarying vec2 vUv;\\nvoid main() {\\n\\tvec4 texColor = texture2D( t2D, vUv );\\n\\tgl_FragColor = mapTexelToLinear( texColor );\\n\\t#include \\n\\t#include \\n}",background_vert:"varying vec2 vUv;\\nuniform mat3 uvTransform;\\nvoid main() {\\n\\tvUv = ( uvTransform * vec3( uv, 1 ) ).xy;\\n\\tgl_Position = vec4( position.xy, 1.0, 1.0 );\\n}",cube_frag:"#include \\nuniform float opacity;\\nvarying vec3 vWorldDirection;\\n#include \\nvoid main() {\\n\\tvec3 vReflect = vWorldDirection;\\n\\t#include \\n\\tgl_FragColor = envColor;\\n\\tgl_FragColor.a *= opacity;\\n\\t#include \\n\\t#include \\n}",cube_vert:"varying vec3 vWorldDirection;\\n#include \\nvoid main() {\\n\\tvWorldDirection = transformDirection( position, modelMatrix );\\n\\t#include \\n\\t#include \\n\\tgl_Position.z = gl_Position.w;\\n}",depth_frag:"#if DEPTH_PACKING == 3200\\n\\tuniform float opacity;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvarying vec2 vHighPrecisionZW;\\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( 1.0 );\\n\\t#if DEPTH_PACKING == 3200\\n\\t\\tdiffuseColor.a = opacity;\\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tfloat fragCoordZ = 0.5 * vHighPrecisionZW[0] / vHighPrecisionZW[1] + 0.5;\\n\\t#if DEPTH_PACKING == 3200\\n\\t\\tgl_FragColor = vec4( vec3( 1.0 - fragCoordZ ), opacity );\\n\\t#elif DEPTH_PACKING == 3201\\n\\t\\tgl_FragColor = packDepthToRGBA( fragCoordZ );\\n\\t#endif\\n}",depth_vert:"#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvarying vec2 vHighPrecisionZW;\\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#ifdef USE_DISPLACEMENTMAP\\n\\t\\t#include \\n\\t\\t#include \\n\\t\\t#include \\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvHighPrecisionZW = gl_Position.zw;\\n}",distanceRGBA_frag:"#define DISTANCE\\nuniform vec3 referencePosition;\\nuniform float nearDistance;\\nuniform float farDistance;\\nvarying vec3 vWorldPosition;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main () {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( 1.0 );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\tfloat dist = length( vWorldPosition - referencePosition );\\n\\tdist = ( dist - nearDistance ) / ( farDistance - nearDistance );\\n\\tdist = saturate( dist );\\n\\tgl_FragColor = packDepthToRGBA( dist );\\n}",distanceRGBA_vert:"#define DISTANCE\\nvarying vec3 vWorldPosition;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#ifdef USE_DISPLACEMENTMAP\\n\\t\\t#include \\n\\t\\t#include \\n\\t\\t#include \\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvWorldPosition = worldPosition.xyz;\\n}",equirect_frag:"uniform sampler2D tEquirect;\\nvarying vec3 vWorldDirection;\\n#include \\nvoid main() {\\n\\tvec3 direction = normalize( vWorldDirection );\\n\\tvec2 sampleUV = equirectUv( direction );\\n\\tvec4 texColor = texture2D( tEquirect, sampleUV );\\n\\tgl_FragColor = mapTexelToLinear( texColor );\\n\\t#include \\n\\t#include \\n}",equirect_vert:"varying vec3 vWorldDirection;\\n#include \\nvoid main() {\\n\\tvWorldDirection = transformDirection( position, modelMatrix );\\n\\t#include \\n\\t#include \\n}",linedashed_frag:"uniform vec3 diffuse;\\nuniform float opacity;\\nuniform float dashSize;\\nuniform float totalSize;\\nvarying float vLineDistance;\\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tif ( mod( vLineDistance, totalSize ) > dashSize ) {\\n\\t\\tdiscard;\\n\\t}\\n\\tvec3 outgoingLight = vec3( 0.0 );\\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\t#include \\n\\t#include \\n\\toutgoingLight = diffuseColor.rgb;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",linedashed_vert:"uniform float scale;\\nattribute float lineDistance;\\nvarying float vLineDistance;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\tvLineDistance = scale * lineDistance;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshbasic_frag:"uniform vec3 diffuse;\\nuniform float opacity;\\n#ifndef FLAT_SHADED\\n\\tvarying vec3 vNormal;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\\n\\t#ifdef USE_LIGHTMAP\\n\\t\\tvec4 lightMapTexel= texture2D( lightMap, vUv2 );\\n\\t\\treflectedLight.indirectDiffuse += lightMapTexelToLinear( lightMapTexel ).rgb * lightMapIntensity;\\n\\t#else\\n\\t\\treflectedLight.indirectDiffuse += vec3( 1.0 );\\n\\t#endif\\n\\t#include \\n\\treflectedLight.indirectDiffuse *= diffuseColor.rgb;\\n\\tvec3 outgoingLight = reflectedLight.indirectDiffuse;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshbasic_vert:"#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#if defined ( USE_ENVMAP ) || defined ( USE_SKINNING )\\n\\t\\t#include \\n\\t\\t#include \\n\\t\\t#include \\n\\t\\t#include \\n\\t\\t#include \\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshlambert_frag:"uniform vec3 diffuse;\\nuniform vec3 emissive;\\nuniform float opacity;\\nvarying vec3 vLightFront;\\nvarying vec3 vIndirectFront;\\n#ifdef DOUBLE_SIDED\\n\\tvarying vec3 vLightBack;\\n\\tvarying vec3 vIndirectBack;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\\n\\tvec3 totalEmissiveRadiance = emissive;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#ifdef DOUBLE_SIDED\\n\\t\\treflectedLight.indirectDiffuse += ( gl_FrontFacing ) ? vIndirectFront : vIndirectBack;\\n\\t#else\\n\\t\\treflectedLight.indirectDiffuse += vIndirectFront;\\n\\t#endif\\n\\t#include \\n\\treflectedLight.indirectDiffuse *= BRDF_Lambert( diffuseColor.rgb );\\n\\t#ifdef DOUBLE_SIDED\\n\\t\\treflectedLight.directDiffuse = ( gl_FrontFacing ) ? vLightFront : vLightBack;\\n\\t#else\\n\\t\\treflectedLight.directDiffuse = vLightFront;\\n\\t#endif\\n\\treflectedLight.directDiffuse *= BRDF_Lambert( diffuseColor.rgb ) * getShadowMask();\\n\\t#include \\n\\tvec3 outgoingLight = reflectedLight.directDiffuse + reflectedLight.indirectDiffuse + totalEmissiveRadiance;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshlambert_vert:"#define LAMBERT\\nvarying vec3 vLightFront;\\nvarying vec3 vIndirectFront;\\n#ifdef DOUBLE_SIDED\\n\\tvarying vec3 vLightBack;\\n\\tvarying vec3 vIndirectBack;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshmatcap_frag:"#define MATCAP\\nuniform vec3 diffuse;\\nuniform float opacity;\\nuniform sampler2D matcap;\\nvarying vec3 vViewPosition;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvec3 viewDir = normalize( vViewPosition );\\n\\tvec3 x = normalize( vec3( viewDir.z, 0.0, - viewDir.x ) );\\n\\tvec3 y = cross( viewDir, x );\\n\\tvec2 uv = vec2( dot( x, normal ), dot( y, normal ) ) * 0.495 + 0.5;\\n\\t#ifdef USE_MATCAP\\n\\t\\tvec4 matcapColor = texture2D( matcap, uv );\\n\\t\\tmatcapColor = matcapTexelToLinear( matcapColor );\\n\\t#else\\n\\t\\tvec4 matcapColor = vec4( 1.0 );\\n\\t#endif\\n\\tvec3 outgoingLight = diffuseColor.rgb * matcapColor.rgb;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshmatcap_vert:"#define MATCAP\\nvarying vec3 vViewPosition;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvViewPosition = - mvPosition.xyz;\\n}",meshnormal_frag:"#define NORMAL\\nuniform float opacity;\\n#if defined( FLAT_SHADED ) || defined( USE_BUMPMAP ) || defined( TANGENTSPACE_NORMALMAP )\\n\\tvarying vec3 vViewPosition;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tgl_FragColor = vec4( packNormalToRGB( normal ), opacity );\\n}",meshnormal_vert:"#define NORMAL\\n#if defined( FLAT_SHADED ) || defined( USE_BUMPMAP ) || defined( TANGENTSPACE_NORMALMAP )\\n\\tvarying vec3 vViewPosition;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n#if defined( FLAT_SHADED ) || defined( USE_BUMPMAP ) || defined( TANGENTSPACE_NORMALMAP )\\n\\tvViewPosition = - mvPosition.xyz;\\n#endif\\n}",meshphong_frag:"#define PHONG\\nuniform vec3 diffuse;\\nuniform vec3 emissive;\\nuniform vec3 specular;\\nuniform float shininess;\\nuniform float opacity;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\\n\\tvec3 totalEmissiveRadiance = emissive;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvec3 outgoingLight = reflectedLight.directDiffuse + reflectedLight.indirectDiffuse + reflectedLight.directSpecular + reflectedLight.indirectSpecular + totalEmissiveRadiance;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshphong_vert:"#define PHONG\\nvarying vec3 vViewPosition;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvViewPosition = - mvPosition.xyz;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshphysical_frag:"#define STANDARD\\n#ifdef PHYSICAL\\n\\t#define IOR\\n\\t#define SPECULAR\\n#endif\\nuniform vec3 diffuse;\\nuniform vec3 emissive;\\nuniform float roughness;\\nuniform float metalness;\\nuniform float opacity;\\n#ifdef IOR\\n\\tuniform float ior;\\n#endif\\n#ifdef SPECULAR\\n\\tuniform float specularIntensity;\\n\\tuniform vec3 specularTint;\\n\\t#ifdef USE_SPECULARINTENSITYMAP\\n\\t\\tuniform sampler2D specularIntensityMap;\\n\\t#endif\\n\\t#ifdef USE_SPECULARTINTMAP\\n\\t\\tuniform sampler2D specularTintMap;\\n\\t#endif\\n#endif\\n#ifdef USE_CLEARCOAT\\n\\tuniform float clearcoat;\\n\\tuniform float clearcoatRoughness;\\n#endif\\n#ifdef USE_SHEEN\\n\\tuniform vec3 sheenTint;\\n#endif\\nvarying vec3 vViewPosition;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\\n\\tvec3 totalEmissiveRadiance = emissive;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvec3 totalDiffuse = reflectedLight.directDiffuse + reflectedLight.indirectDiffuse;\\n\\tvec3 totalSpecular = reflectedLight.directSpecular + reflectedLight.indirectSpecular;\\n\\t#include \\n\\tvec3 outgoingLight = totalDiffuse + totalSpecular + totalEmissiveRadiance;\\n\\t#ifdef USE_CLEARCOAT\\n\\t\\tfloat dotNVcc = saturate( dot( geometry.clearcoatNormal, geometry.viewDir ) );\\n\\t\\tvec3 Fcc = F_Schlick( material.clearcoatF0, material.clearcoatF90, dotNVcc );\\n\\t\\toutgoingLight = outgoingLight * ( 1.0 - clearcoat * Fcc ) + clearcoatSpecular * clearcoat;\\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshphysical_vert:"#define STANDARD\\nvarying vec3 vViewPosition;\\n#ifdef USE_TRANSMISSION\\n\\tvarying vec3 vWorldPosition;\\n#endif\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvViewPosition = - mvPosition.xyz;\\n\\t#include \\n\\t#include \\n\\t#include \\n#ifdef USE_TRANSMISSION\\n\\tvWorldPosition = worldPosition.xyz;\\n#endif\\n}",meshtoon_frag:"#define TOON\\nuniform vec3 diffuse;\\nuniform vec3 emissive;\\nuniform float opacity;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\\n\\tvec3 totalEmissiveRadiance = emissive;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvec3 outgoingLight = reflectedLight.directDiffuse + reflectedLight.indirectDiffuse + totalEmissiveRadiance;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",meshtoon_vert:"#define TOON\\nvarying vec3 vViewPosition;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tvViewPosition = - mvPosition.xyz;\\n\\t#include \\n\\t#include \\n\\t#include \\n}",points_frag:"uniform vec3 diffuse;\\nuniform float opacity;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec3 outgoingLight = vec3( 0.0 );\\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\toutgoingLight = diffuseColor.rgb;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",points_vert:"uniform float size;\\nuniform float scale;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\tgl_PointSize = size;\\n\\t#ifdef USE_SIZEATTENUATION\\n\\t\\tbool isPerspective = isPerspectiveMatrix( projectionMatrix );\\n\\t\\tif ( isPerspective ) gl_PointSize *= ( scale / - mvPosition.z );\\n\\t#endif\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",shadow_frag:"uniform vec3 color;\\nuniform float opacity;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\tgl_FragColor = vec4( color, opacity * ( 1.0 - getShadowMask() ) );\\n\\t#include \\n\\t#include \\n\\t#include \\n}",shadow_vert:"#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",sprite_frag:"uniform vec3 diffuse;\\nuniform float opacity;\\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec3 outgoingLight = vec3( 0.0 );\\n\\tvec4 diffuseColor = vec4( diffuse, opacity );\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n\\toutgoingLight = diffuseColor.rgb;\\n\\t#include \\n\\t#include \\n\\t#include \\n\\t#include \\n}",sprite_vert:"uniform float rotation;\\nuniform vec2 center;\\n#include \\n#include \\n#include \\n#include \\n#include \\nvoid main() {\\n\\t#include \\n\\tvec4 mvPosition = modelViewMatrix * vec4( 0.0, 0.0, 0.0, 1.0 );\\n\\tvec2 scale;\\n\\tscale.x = length( vec3( modelMatrix[ 0 ].x, modelMatrix[ 0 ].y, modelMatrix[ 0 ].z ) );\\n\\tscale.y = length( vec3( modelMatrix[ 1 ].x, modelMatrix[ 1 ].y, modelMatrix[ 1 ].z ) );\\n\\t#ifndef USE_SIZEATTENUATION\\n\\t\\tbool isPerspective = isPerspectiveMatrix( projectionMatrix );\\n\\t\\tif ( isPerspective ) scale *= - mvPosition.z;\\n\\t#endif\\n\\tvec2 alignedPosition = ( position.xy - ( center - vec2( 0.5 ) ) ) * scale;\\n\\tvec2 rotatedPosition;\\n\\trotatedPosition.x = cos( rotation ) * alignedPosition.x - sin( rotation ) * alignedPosition.y;\\n\\trotatedPosition.y = sin( rotation ) * alignedPosition.x + cos( rotation ) * alignedPosition.y;\\n\\tmvPosition.xy += rotatedPosition;\\n\\tgl_Position = projectionMatrix * mvPosition;\\n\\t#include \\n\\t#include \\n\\t#include \\n}"},Gs={common:{diffuse:{value:new Cr(16777215)},opacity:{value:1},map:{value:null},uvTransform:{value:new Zn},uv2Transform:{value:new Zn},alphaMap:{value:null},alphaTest:{value:0}},specularmap:{specularMap:{value:null}},envmap:{envMap:{value:null},flipEnvMap:{value:-1},reflectivity:{value:1},ior:{value:1.5},refractionRatio:{value:.98},maxMipLevel:{value:0}},aomap:{aoMap:{value:null},aoMapIntensity:{value:1}},lightmap:{lightMap:{value:null},lightMapIntensity:{value:1}},emissivemap:{emissiveMap:{value:null}},bumpmap:{bumpMap:{value:null},bumpScale:{value:1}},normalmap:{normalMap:{value:null},normalScale:{value:new Jn(1,1)}},displacementmap:{displacementMap:{value:null},displacementScale:{value:1},displacementBias:{value:0}},roughnessmap:{roughnessMap:{value:null}},metalnessmap:{metalnessMap:{value:null}},gradientmap:{gradientMap:{value:null}},fog:{fogDensity:{value:25e-5},fogNear:{value:1},fogFar:{value:2e3},fogColor:{value:new Cr(16777215)}},lights:{ambientLightColor:{value:[]},lightProbe:{value:[]},directionalLights:{value:[],properties:{direction:{},color:{}}},directionalLightShadows:{value:[],properties:{shadowBias:{},shadowNormalBias:{},shadowRadius:{},shadowMapSize:{}}},directionalShadowMap:{value:[]},directionalShadowMatrix:{value:[]},spotLights:{value:[],properties:{color:{},position:{},direction:{},distance:{},coneCos:{},penumbraCos:{},decay:{}}},spotLightShadows:{value:[],properties:{shadowBias:{},shadowNormalBias:{},shadowRadius:{},shadowMapSize:{}}},spotShadowMap:{value:[]},spotShadowMatrix:{value:[]},pointLights:{value:[],properties:{color:{},position:{},decay:{},distance:{}}},pointLightShadows:{value:[],properties:{shadowBias:{},shadowNormalBias:{},shadowRadius:{},shadowMapSize:{},shadowCameraNear:{},shadowCameraFar:{}}},pointShadowMap:{value:[]},pointShadowMatrix:{value:[]},hemisphereLights:{value:[],properties:{direction:{},skyColor:{},groundColor:{}}},rectAreaLights:{value:[],properties:{color:{},position:{},width:{},height:{}}},ltc_1:{value:null},ltc_2:{value:null}},points:{diffuse:{value:new Cr(16777215)},opacity:{value:1},size:{value:1},scale:{value:1},map:{value:null},alphaMap:{value:null},alphaTest:{value:0},uvTransform:{value:new Zn}},sprite:{diffuse:{value:new Cr(16777215)},opacity:{value:1},center:{value:new Jn(.5,.5)},rotation:{value:0},map:{value:null},alphaMap:{value:null},alphaTest:{value:0},uvTransform:{value:new Zn}}},Vs={basic:{uniforms:ws([Gs.common,Gs.specularmap,Gs.envmap,Gs.aomap,Gs.lightmap,Gs.fog]),vertexShader:Hs.meshbasic_vert,fragmentShader:Hs.meshbasic_frag},lambert:{uniforms:ws([Gs.common,Gs.specularmap,Gs.envmap,Gs.aomap,Gs.lightmap,Gs.emissivemap,Gs.fog,Gs.lights,{emissive:{value:new Cr(0)}}]),vertexShader:Hs.meshlambert_vert,fragmentShader:Hs.meshlambert_frag},phong:{uniforms:ws([Gs.common,Gs.specularmap,Gs.envmap,Gs.aomap,Gs.lightmap,Gs.emissivemap,Gs.bumpmap,Gs.normalmap,Gs.displacementmap,Gs.fog,Gs.lights,{emissive:{value:new Cr(0)},specular:{value:new Cr(1118481)},shininess:{value:30}}]),vertexShader:Hs.meshphong_vert,fragmentShader:Hs.meshphong_frag},standard:{uniforms:ws([Gs.common,Gs.envmap,Gs.aomap,Gs.lightmap,Gs.emissivemap,Gs.bumpmap,Gs.normalmap,Gs.displacementmap,Gs.roughnessmap,Gs.metalnessmap,Gs.fog,Gs.lights,{emissive:{value:new Cr(0)},roughness:{value:1},metalness:{value:0},envMapIntensity:{value:1}}]),vertexShader:Hs.meshphysical_vert,fragmentShader:Hs.meshphysical_frag},toon:{uniforms:ws([Gs.common,Gs.aomap,Gs.lightmap,Gs.emissivemap,Gs.bumpmap,Gs.normalmap,Gs.displacementmap,Gs.gradientmap,Gs.fog,Gs.lights,{emissive:{value:new Cr(0)}}]),vertexShader:Hs.meshtoon_vert,fragmentShader:Hs.meshtoon_frag},matcap:{uniforms:ws([Gs.common,Gs.bumpmap,Gs.normalmap,Gs.displacementmap,Gs.fog,{matcap:{value:null}}]),vertexShader:Hs.meshmatcap_vert,fragmentShader:Hs.meshmatcap_frag},points:{uniforms:ws([Gs.points,Gs.fog]),vertexShader:Hs.points_vert,fragmentShader:Hs.points_frag},dashed:{uniforms:ws([Gs.common,Gs.fog,{scale:{value:1},dashSize:{value:1},totalSize:{value:2}}]),vertexShader:Hs.linedashed_vert,fragmentShader:Hs.linedashed_frag},depth:{uniforms:ws([Gs.common,Gs.displacementmap]),vertexShader:Hs.depth_vert,fragmentShader:Hs.depth_frag},normal:{uniforms:ws([Gs.common,Gs.bumpmap,Gs.normalmap,Gs.displacementmap,{opacity:{value:1}}]),vertexShader:Hs.meshnormal_vert,fragmentShader:Hs.meshnormal_frag},sprite:{uniforms:ws([Gs.sprite,Gs.fog]),vertexShader:Hs.sprite_vert,fragmentShader:Hs.sprite_frag},background:{uniforms:{uvTransform:{value:new Zn},t2D:{value:null}},vertexShader:Hs.background_vert,fragmentShader:Hs.background_frag},cube:{uniforms:ws([Gs.envmap,{opacity:{value:1}}]),vertexShader:Hs.cube_vert,fragmentShader:Hs.cube_frag},equirect:{uniforms:{tEquirect:{value:null}},vertexShader:Hs.equirect_vert,fragmentShader:Hs.equirect_frag},distanceRGBA:{uniforms:ws([Gs.common,Gs.displacementmap,{referencePosition:{value:new oi},nearDistance:{value:1},farDistance:{value:1e3}}]),vertexShader:Hs.distanceRGBA_vert,fragmentShader:Hs.distanceRGBA_frag},shadow:{uniforms:ws([Gs.lights,Gs.fog,{color:{value:new Cr(0)},opacity:{value:1}}]),vertexShader:Hs.shadow_vert,fragmentShader:Hs.shadow_frag}};function Ws(e,t,n,i,r){const s=new Cr(0);let a,o,l=0,c=null,h=0,u=null;function d(e,t){n.buffers.color.setClear(e.r,e.g,e.b,t,r)}return{getClearColor:function(){return s},setClearColor:function(e,t=1){s.set(e),l=t,d(s,l)},getClearAlpha:function(){return l},setClearAlpha:function(e){l=e,d(s,l)},render:function(n,r){let p=!1,g=!0===r.isScene?r.background:null;g&&g.isTexture&&(g=t.get(g));const v=e.xr,y=v.getSession&&v.getSession();y&&"additive"===y.environmentBlendMode&&(g=null),null===g?d(s,l):g&&g.isColor&&(d(g,1),p=!0),(e.autoClear||p)&&e.clear(e.autoClearColor,e.autoClearDepth,e.autoClearStencil),g&&(g.isCubeTexture||g.mapping===ce)?(void 0===o&&(o=new ys(new xs(1,1,1),new Ts({name:"BackgroundCubeMaterial",uniforms:bs(Vs.cube.uniforms),vertexShader:Vs.cube.vertexShader,fragmentShader:Vs.cube.fragmentShader,side:m,depthTest:!1,depthWrite:!1,fog:!1})),o.geometry.deleteAttribute("normal"),o.geometry.deleteAttribute("uv"),o.onBeforeRender=function(e,t,n){this.matrixWorld.copyPosition(n.matrixWorld)},Object.defineProperty(o.material,"envMap",{get:function(){return this.uniforms.envMap.value}}),i.update(o)),o.material.uniforms.envMap.value=g,o.material.uniforms.flipEnvMap.value=g.isCubeTexture&&!1===g.isRenderTargetTexture?-1:1,c===g&&h===g.version&&u===e.toneMapping||(o.material.needsUpdate=!0,c=g,h=g.version,u=e.toneMapping),n.unshift(o,o.geometry,o.material,0,0,null)):g&&g.isTexture&&(void 0===a&&(a=new ys(new zs(2,2),new Ts({name:"BackgroundMaterial",uniforms:bs(Vs.background.uniforms),vertexShader:Vs.background.vertexShader,fragmentShader:Vs.background.fragmentShader,side:f,depthTest:!1,depthWrite:!1,fog:!1})),a.geometry.deleteAttribute("normal"),Object.defineProperty(a.material,"map",{get:function(){return this.uniforms.t2D.value}}),i.update(a)),a.material.uniforms.t2D.value=g,!0===g.matrixAutoUpdate&&g.updateMatrix(),a.material.uniforms.uvTransform.value.copy(g.matrix),c===g&&h===g.version&&u===e.toneMapping||(a.material.needsUpdate=!0,c=g,h=g.version,u=e.toneMapping),n.unshift(a,a.geometry,a.material,0,0,null))}}}function js(e,t,n,i){const r=e.getParameter(34921),s=i.isWebGL2?null:t.get("OES_vertex_array_object"),a=i.isWebGL2||null!==s,o={},l=d(null);let c=l;function h(t){return i.isWebGL2?e.bindVertexArray(t):s.bindVertexArrayOES(t)}function u(t){return i.isWebGL2?e.deleteVertexArray(t):s.deleteVertexArrayOES(t)}function d(e){const t=[],n=[],i=[];for(let e=0;e=0){let s=l[t];if(void 0===s&&("instanceMatrix"===t&&r.instanceMatrix&&(s=r.instanceMatrix),"instanceColor"===t&&r.instanceColor&&(s=r.instanceColor)),void 0!==s){const t=s.normalized,a=s.itemSize,l=n.get(s);if(void 0===l)continue;const c=l.buffer,h=l.type,u=l.bytesPerElement;if(s.isInterleavedBufferAttribute){const n=s.data,l=n.stride,d=s.offset;if(n&&n.isInstancedInterleavedBuffer){for(let e=0;e0&&e.getShaderPrecisionFormat(35632,36338).precision>0)return"highp";t="mediump"}return"mediump"===t&&e.getShaderPrecisionFormat(35633,36337).precision>0&&e.getShaderPrecisionFormat(35632,36337).precision>0?"mediump":"lowp"}const s="undefined"!=typeof WebGL2RenderingContext&&e instanceof WebGL2RenderingContext||"undefined"!=typeof WebGL2ComputeRenderingContext&&e instanceof WebGL2ComputeRenderingContext;let a=void 0!==n.precision?n.precision:"highp";const o=r(a);o!==a&&(console.warn("THREE.WebGLRenderer:",a,"not supported, using",o,"instead."),a=o);const l=s||t.has("WEBGL_draw_buffers"),c=!0===n.logarithmicDepthBuffer,h=e.getParameter(34930),u=e.getParameter(35660),d=e.getParameter(3379),p=e.getParameter(34076),f=e.getParameter(34921),m=e.getParameter(36347),g=e.getParameter(36348),v=e.getParameter(36349),y=u>0,_=s||t.has("OES_texture_float");return{isWebGL2:s,drawBuffers:l,getMaxAnisotropy:function(){if(void 0!==i)return i;if(!0===t.has("EXT_texture_filter_anisotropic")){const n=t.get("EXT_texture_filter_anisotropic");i=e.getParameter(n.MAX_TEXTURE_MAX_ANISOTROPY_EXT)}else i=0;return i},getMaxPrecision:r,precision:a,logarithmicDepthBuffer:c,maxTextures:h,maxVertexTextures:u,maxTextureSize:d,maxCubemapSize:p,maxAttributes:f,maxVertexUniforms:m,maxVaryings:g,maxFragmentUniforms:v,vertexTextures:y,floatFragmentTextures:_,floatVertexTextures:y&&_,maxSamples:s?e.getParameter(36183):0}}function Ys(e){const t=this;let n=null,i=0,r=!1,s=!1;const a=new Is,o=new Zn,l={value:null,needsUpdate:!1};function c(){l.value!==n&&(l.value=n,l.needsUpdate=i>0),t.numPlanes=i,t.numIntersection=0}function h(e,n,i,r){const s=null!==e?e.length:0;let c=null;if(0!==s){if(c=l.value,!0!==r||null===c){const t=i+4*s,r=n.matrixWorldInverse;o.getNormalMatrix(r),(null===c||c.length0){const a=e.getRenderTarget(),o=new Rs(s.height/2);return o.fromEquirectangularTexture(e,r),t.set(r,o),e.setRenderTarget(a),r.addEventListener("dispose",i),n(o.texture,r.mapping)}return null}}}return r},dispose:function(){t=new WeakMap}}}Vs.physical={uniforms:ws([Vs.standard.uniforms,{clearcoat:{value:0},clearcoatMap:{value:null},clearcoatRoughness:{value:0},clearcoatRoughnessMap:{value:null},clearcoatNormalScale:{value:new Jn(1,1)},clearcoatNormalMap:{value:null},sheenTint:{value:new Cr(0)},transmission:{value:0},transmissionMap:{value:null},transmissionSamplerSize:{value:new Jn},transmissionSamplerMap:{value:null},thickness:{value:0},thicknessMap:{value:null},attenuationDistance:{value:0},attenuationTint:{value:new Cr(0)},specularIntensity:{value:0},specularIntensityMap:{value:null},specularTint:{value:new Cr(1,1,1)},specularTintMap:{value:null}}]),vertexShader:Hs.meshphysical_vert,fragmentShader:Hs.meshphysical_frag};class Zs extends Es{constructor(e=-1,t=1,n=1,i=-1,r=.1,s=2e3){super(),this.type="OrthographicCamera",this.zoom=1,this.view=null,this.left=e,this.right=t,this.top=n,this.bottom=i,this.near=r,this.far=s,this.updateProjectionMatrix()}copy(e,t){return super.copy(e,t),this.left=e.left,this.right=e.right,this.top=e.top,this.bottom=e.bottom,this.near=e.near,this.far=e.far,this.zoom=e.zoom,this.view=null===e.view?null:Object.assign({},e.view),this}setViewOffset(e,t,n,i,r,s){null===this.view&&(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=t,this.view.offsetX=n,this.view.offsetY=i,this.view.width=r,this.view.height=s,this.updateProjectionMatrix()}clearViewOffset(){null!==this.view&&(this.view.enabled=!1),this.updateProjectionMatrix()}updateProjectionMatrix(){const e=(this.right-this.left)/(2*this.zoom),t=(this.top-this.bottom)/(2*this.zoom),n=(this.right+this.left)/2,i=(this.top+this.bottom)/2;let r=n-e,s=n+e,a=i+t,o=i-t;if(null!==this.view&&this.view.enabled){const e=(this.right-this.left)/this.view.fullWidth/this.zoom,t=(this.top-this.bottom)/this.view.fullHeight/this.zoom;r+=e*this.view.offsetX,s=r+e*this.view.width,a-=t*this.view.offsetY,o=a-t*this.view.height}this.projectionMatrix.makeOrthographic(r,s,a,o,this.near,this.far),this.projectionMatrixInverse.copy(this.projectionMatrix).invert()}toJSON(e){const t=super.toJSON(e);return t.object.zoom=this.zoom,t.object.left=this.left,t.object.right=this.right,t.object.top=this.top,t.object.bottom=this.bottom,t.object.near=this.near,t.object.far=this.far,null!==this.view&&(t.object.view=Object.assign({},this.view)),t}}Zs.prototype.isOrthographicCamera=!0;class Ks extends Ts{constructor(e){super(e),this.type="RawShaderMaterial"}}Ks.prototype.isRawShaderMaterial=!0;const Qs=Math.pow(2,8),$s=[.125,.215,.35,.446,.526,.582],ea=5+$s.length,ta={[Zt]:0,[Kt]:1,[$t]:2,[tn]:3,[nn]:4,[rn]:5,[Qt]:6},na=new Zs,{_lodPlanes:ia,_sizeLods:ra,_sigmas:sa}=pa(),aa=new Cr;let oa=null;const la=(1+Math.sqrt(5))/2,ca=1/la,ha=[new oi(1,1,1),new oi(-1,1,1),new oi(1,1,-1),new oi(-1,1,-1),new oi(0,la,ca),new oi(0,la,-ca),new oi(ca,0,la),new oi(-ca,0,la),new oi(la,ca,0),new oi(-la,ca,0)];class ua{constructor(e){this._renderer=e,this._pingPongRenderTarget=null,this._blurMaterial=function(e){const t=new Float32Array(20),n=new oi(0,1,0);return new Ks({name:"SphericalGaussianBlur",defines:{n:20},uniforms:{envMap:{value:null},samples:{value:1},weights:{value:t},latitudinal:{value:!1},dTheta:{value:0},mipInt:{value:0},poleAxis:{value:n},inputEncoding:{value:ta[Zt]},outputEncoding:{value:ta[Zt]}},vertexShader:"\\n\\n\\t\\tprecision mediump float;\\n\\t\\tprecision mediump int;\\n\\n\\t\\tattribute vec3 position;\\n\\t\\tattribute vec2 uv;\\n\\t\\tattribute float faceIndex;\\n\\n\\t\\tvarying vec3 vOutputDirection;\\n\\n\\t\\t// RH coordinate system; PMREM face-indexing convention\\n\\t\\tvec3 getDirection( vec2 uv, float face ) {\\n\\n\\t\\t\\tuv = 2.0 * uv - 1.0;\\n\\n\\t\\t\\tvec3 direction = vec3( uv, 1.0 );\\n\\n\\t\\t\\tif ( face == 0.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.zyx; // ( 1, v, u ) pos x\\n\\n\\t\\t\\t} else if ( face == 1.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.xzy;\\n\\t\\t\\t\\tdirection.xz *= -1.0; // ( -u, 1, -v ) pos y\\n\\n\\t\\t\\t} else if ( face == 2.0 ) {\\n\\n\\t\\t\\t\\tdirection.x *= -1.0; // ( -u, v, 1 ) pos z\\n\\n\\t\\t\\t} else if ( face == 3.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.zyx;\\n\\t\\t\\t\\tdirection.xz *= -1.0; // ( -1, v, -u ) neg x\\n\\n\\t\\t\\t} else if ( face == 4.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.xzy;\\n\\t\\t\\t\\tdirection.xy *= -1.0; // ( -u, -1, v ) neg y\\n\\n\\t\\t\\t} else if ( face == 5.0 ) {\\n\\n\\t\\t\\t\\tdirection.z *= -1.0; // ( u, v, -1 ) neg z\\n\\n\\t\\t\\t}\\n\\n\\t\\t\\treturn direction;\\n\\n\\t\\t}\\n\\n\\t\\tvoid main() {\\n\\n\\t\\t\\tvOutputDirection = getDirection( uv, faceIndex );\\n\\t\\t\\tgl_Position = vec4( position, 1.0 );\\n\\n\\t\\t}\\n\\t",fragmentShader:"\\n\\n\\t\\t\\tprecision mediump float;\\n\\t\\t\\tprecision mediump int;\\n\\n\\t\\t\\tvarying vec3 vOutputDirection;\\n\\n\\t\\t\\tuniform sampler2D envMap;\\n\\t\\t\\tuniform int samples;\\n\\t\\t\\tuniform float weights[ n ];\\n\\t\\t\\tuniform bool latitudinal;\\n\\t\\t\\tuniform float dTheta;\\n\\t\\t\\tuniform float mipInt;\\n\\t\\t\\tuniform vec3 poleAxis;\\n\\n\\t\\t\\t\\n\\n\\t\\tuniform int inputEncoding;\\n\\t\\tuniform int outputEncoding;\\n\\n\\t\\t#include \\n\\n\\t\\tvec4 inputTexelToLinear( vec4 value ) {\\n\\n\\t\\t\\tif ( inputEncoding == 0 ) {\\n\\n\\t\\t\\t\\treturn value;\\n\\n\\t\\t\\t} else if ( inputEncoding == 1 ) {\\n\\n\\t\\t\\t\\treturn sRGBToLinear( value );\\n\\n\\t\\t\\t} else if ( inputEncoding == 2 ) {\\n\\n\\t\\t\\t\\treturn RGBEToLinear( value );\\n\\n\\t\\t\\t} else if ( inputEncoding == 3 ) {\\n\\n\\t\\t\\t\\treturn RGBMToLinear( value, 7.0 );\\n\\n\\t\\t\\t} else if ( inputEncoding == 4 ) {\\n\\n\\t\\t\\t\\treturn RGBMToLinear( value, 16.0 );\\n\\n\\t\\t\\t} else if ( inputEncoding == 5 ) {\\n\\n\\t\\t\\t\\treturn RGBDToLinear( value, 256.0 );\\n\\n\\t\\t\\t} else {\\n\\n\\t\\t\\t\\treturn GammaToLinear( value, 2.2 );\\n\\n\\t\\t\\t}\\n\\n\\t\\t}\\n\\n\\t\\tvec4 linearToOutputTexel( vec4 value ) {\\n\\n\\t\\t\\tif ( outputEncoding == 0 ) {\\n\\n\\t\\t\\t\\treturn value;\\n\\n\\t\\t\\t} else if ( outputEncoding == 1 ) {\\n\\n\\t\\t\\t\\treturn LinearTosRGB( value );\\n\\n\\t\\t\\t} else if ( outputEncoding == 2 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBE( value );\\n\\n\\t\\t\\t} else if ( outputEncoding == 3 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBM( value, 7.0 );\\n\\n\\t\\t\\t} else if ( outputEncoding == 4 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBM( value, 16.0 );\\n\\n\\t\\t\\t} else if ( outputEncoding == 5 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBD( value, 256.0 );\\n\\n\\t\\t\\t} else {\\n\\n\\t\\t\\t\\treturn LinearToGamma( value, 2.2 );\\n\\n\\t\\t\\t}\\n\\n\\t\\t}\\n\\n\\t\\tvec4 envMapTexelToLinear( vec4 color ) {\\n\\n\\t\\t\\treturn inputTexelToLinear( color );\\n\\n\\t\\t}\\n\\t\\n\\n\\t\\t\\t#define ENVMAP_TYPE_CUBE_UV\\n\\t\\t\\t#include \\n\\n\\t\\t\\tvec3 getSample( float theta, vec3 axis ) {\\n\\n\\t\\t\\t\\tfloat cosTheta = cos( theta );\\n\\t\\t\\t\\t// Rodrigues' axis-angle rotation\\n\\t\\t\\t\\tvec3 sampleDirection = vOutputDirection * cosTheta\\n\\t\\t\\t\\t\\t+ cross( axis, vOutputDirection ) * sin( theta )\\n\\t\\t\\t\\t\\t+ axis * dot( axis, vOutputDirection ) * ( 1.0 - cosTheta );\\n\\n\\t\\t\\t\\treturn bilinearCubeUV( envMap, sampleDirection, mipInt );\\n\\n\\t\\t\\t}\\n\\n\\t\\t\\tvoid main() {\\n\\n\\t\\t\\t\\tvec3 axis = latitudinal ? poleAxis : cross( poleAxis, vOutputDirection );\\n\\n\\t\\t\\t\\tif ( all( equal( axis, vec3( 0.0 ) ) ) ) {\\n\\n\\t\\t\\t\\t\\taxis = vec3( vOutputDirection.z, 0.0, - vOutputDirection.x );\\n\\n\\t\\t\\t\\t}\\n\\n\\t\\t\\t\\taxis = normalize( axis );\\n\\n\\t\\t\\t\\tgl_FragColor = vec4( 0.0, 0.0, 0.0, 1.0 );\\n\\t\\t\\t\\tgl_FragColor.rgb += weights[ 0 ] * getSample( 0.0, axis );\\n\\n\\t\\t\\t\\tfor ( int i = 1; i < n; i++ ) {\\n\\n\\t\\t\\t\\t\\tif ( i >= samples ) {\\n\\n\\t\\t\\t\\t\\t\\tbreak;\\n\\n\\t\\t\\t\\t\\t}\\n\\n\\t\\t\\t\\t\\tfloat theta = dTheta * float( i );\\n\\t\\t\\t\\t\\tgl_FragColor.rgb += weights[ i ] * getSample( -1.0 * theta, axis );\\n\\t\\t\\t\\t\\tgl_FragColor.rgb += weights[ i ] * getSample( theta, axis );\\n\\n\\t\\t\\t\\t}\\n\\n\\t\\t\\t\\tgl_FragColor = linearToOutputTexel( gl_FragColor );\\n\\n\\t\\t\\t}\\n\\t\\t",blending:_,depthTest:!1,depthWrite:!1})}(),this._equirectShader=null,this._cubemapShader=null,this._compileMaterial(this._blurMaterial)}fromScene(e,t=0,n=.1,i=100){oa=this._renderer.getRenderTarget();const r=this._allocateTargets();return this._sceneToCubeUV(e,n,i,r),t>0&&this._blur(r,0,0,t),this._applyPMREM(r),this._cleanup(r),r}fromEquirectangular(e){return this._fromTexture(e)}fromCubemap(e){return this._fromTexture(e)}compileCubemapShader(){null===this._cubemapShader&&(this._cubemapShader=va(),this._compileMaterial(this._cubemapShader))}compileEquirectangularShader(){null===this._equirectShader&&(this._equirectShader=ga(),this._compileMaterial(this._equirectShader))}dispose(){this._blurMaterial.dispose(),null!==this._cubemapShader&&this._cubemapShader.dispose(),null!==this._equirectShader&&this._equirectShader.dispose();for(let e=0;e2?Qs:0,Qs,Qs),o.setRenderTarget(i),p&&o.render(d,r),o.render(e,r)}d.geometry.dispose(),d.material.dispose(),o.toneMapping=h,o.outputEncoding=c,o.autoClear=l,e.background=f}_textureToCubeUV(e,t){const n=this._renderer;e.isCubeTexture?null==this._cubemapShader&&(this._cubemapShader=va()):null==this._equirectShader&&(this._equirectShader=ga());const i=e.isCubeTexture?this._cubemapShader:this._equirectShader,r=new ys(ia[0],i),s=i.uniforms;s.envMap.value=e,e.isCubeTexture||s.texelSize.value.set(1/e.image.width,1/e.image.height),s.inputEncoding.value=ta[e.encoding],s.outputEncoding.value=ta[t.texture.encoding],ma(t,0,0,3*Qs,2*Qs),n.setRenderTarget(t),n.render(r,na)}_applyPMREM(e){const t=this._renderer,n=t.autoClear;t.autoClear=!1;for(let t=1;t20&&console.warn(`sigmaRadians, ${r}, is too large and will clip, as it requested ${f} samples when the maximum is set to 20`);const m=[];let g=0;for(let e=0;e<20;++e){const t=e/p,n=Math.exp(-t*t/2);m.push(n),0==e?g+=n:e4?i-8+4:0),3*v,2*v),o.setRenderTarget(t),o.render(c,na)}}function da(e){return void 0!==e&&e.type===Te&&(e.encoding===Zt||e.encoding===Kt||e.encoding===Qt)}function pa(){const e=[],t=[],n=[];let i=8;for(let r=0;r4?a=$s[r-8+4-1]:0==r&&(a=0),n.push(a);const o=1/(s-1),l=-o/2,c=1+o/2,h=[l,l,c,l,c,c,l,l,c,c,l,c],u=6,d=6,p=3,f=2,m=1,g=new Float32Array(p*d*u),v=new Float32Array(f*d*u),y=new Float32Array(m*d*u);for(let e=0;e2?0:-1,i=[t,n,0,t+2/3,n,0,t+2/3,n+1,0,t,n,0,t+2/3,n+1,0,t,n+1,0];g.set(i,p*d*e),v.set(h,f*d*e);const r=[e,e,e,e,e,e];y.set(r,m*d*e)}const _=new es;_.setAttribute("position",new Nr(g,p)),_.setAttribute("uv",new Nr(v,f)),_.setAttribute("faceIndex",new Nr(y,m)),e.push(_),i>4&&i--}return{_lodPlanes:e,_sizeLods:t,_sigmas:n}}function fa(e){const t=new ii(3*Qs,3*Qs,e);return t.texture.mapping=ce,t.texture.name="PMREM.cubeUv",t.scissorTest=!0,t}function ma(e,t,n,i,r){e.viewport.set(t,n,i,r),e.scissor.set(t,n,i,r)}function ga(){const e=new Jn(1,1);return new Ks({name:"EquirectangularToCubeUV",uniforms:{envMap:{value:null},texelSize:{value:e},inputEncoding:{value:ta[Zt]},outputEncoding:{value:ta[Zt]}},vertexShader:"\\n\\n\\t\\tprecision mediump float;\\n\\t\\tprecision mediump int;\\n\\n\\t\\tattribute vec3 position;\\n\\t\\tattribute vec2 uv;\\n\\t\\tattribute float faceIndex;\\n\\n\\t\\tvarying vec3 vOutputDirection;\\n\\n\\t\\t// RH coordinate system; PMREM face-indexing convention\\n\\t\\tvec3 getDirection( vec2 uv, float face ) {\\n\\n\\t\\t\\tuv = 2.0 * uv - 1.0;\\n\\n\\t\\t\\tvec3 direction = vec3( uv, 1.0 );\\n\\n\\t\\t\\tif ( face == 0.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.zyx; // ( 1, v, u ) pos x\\n\\n\\t\\t\\t} else if ( face == 1.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.xzy;\\n\\t\\t\\t\\tdirection.xz *= -1.0; // ( -u, 1, -v ) pos y\\n\\n\\t\\t\\t} else if ( face == 2.0 ) {\\n\\n\\t\\t\\t\\tdirection.x *= -1.0; // ( -u, v, 1 ) pos z\\n\\n\\t\\t\\t} else if ( face == 3.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.zyx;\\n\\t\\t\\t\\tdirection.xz *= -1.0; // ( -1, v, -u ) neg x\\n\\n\\t\\t\\t} else if ( face == 4.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.xzy;\\n\\t\\t\\t\\tdirection.xy *= -1.0; // ( -u, -1, v ) neg y\\n\\n\\t\\t\\t} else if ( face == 5.0 ) {\\n\\n\\t\\t\\t\\tdirection.z *= -1.0; // ( u, v, -1 ) neg z\\n\\n\\t\\t\\t}\\n\\n\\t\\t\\treturn direction;\\n\\n\\t\\t}\\n\\n\\t\\tvoid main() {\\n\\n\\t\\t\\tvOutputDirection = getDirection( uv, faceIndex );\\n\\t\\t\\tgl_Position = vec4( position, 1.0 );\\n\\n\\t\\t}\\n\\t",fragmentShader:"\\n\\n\\t\\t\\tprecision mediump float;\\n\\t\\t\\tprecision mediump int;\\n\\n\\t\\t\\tvarying vec3 vOutputDirection;\\n\\n\\t\\t\\tuniform sampler2D envMap;\\n\\t\\t\\tuniform vec2 texelSize;\\n\\n\\t\\t\\t\\n\\n\\t\\tuniform int inputEncoding;\\n\\t\\tuniform int outputEncoding;\\n\\n\\t\\t#include \\n\\n\\t\\tvec4 inputTexelToLinear( vec4 value ) {\\n\\n\\t\\t\\tif ( inputEncoding == 0 ) {\\n\\n\\t\\t\\t\\treturn value;\\n\\n\\t\\t\\t} else if ( inputEncoding == 1 ) {\\n\\n\\t\\t\\t\\treturn sRGBToLinear( value );\\n\\n\\t\\t\\t} else if ( inputEncoding == 2 ) {\\n\\n\\t\\t\\t\\treturn RGBEToLinear( value );\\n\\n\\t\\t\\t} else if ( inputEncoding == 3 ) {\\n\\n\\t\\t\\t\\treturn RGBMToLinear( value, 7.0 );\\n\\n\\t\\t\\t} else if ( inputEncoding == 4 ) {\\n\\n\\t\\t\\t\\treturn RGBMToLinear( value, 16.0 );\\n\\n\\t\\t\\t} else if ( inputEncoding == 5 ) {\\n\\n\\t\\t\\t\\treturn RGBDToLinear( value, 256.0 );\\n\\n\\t\\t\\t} else {\\n\\n\\t\\t\\t\\treturn GammaToLinear( value, 2.2 );\\n\\n\\t\\t\\t}\\n\\n\\t\\t}\\n\\n\\t\\tvec4 linearToOutputTexel( vec4 value ) {\\n\\n\\t\\t\\tif ( outputEncoding == 0 ) {\\n\\n\\t\\t\\t\\treturn value;\\n\\n\\t\\t\\t} else if ( outputEncoding == 1 ) {\\n\\n\\t\\t\\t\\treturn LinearTosRGB( value );\\n\\n\\t\\t\\t} else if ( outputEncoding == 2 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBE( value );\\n\\n\\t\\t\\t} else if ( outputEncoding == 3 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBM( value, 7.0 );\\n\\n\\t\\t\\t} else if ( outputEncoding == 4 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBM( value, 16.0 );\\n\\n\\t\\t\\t} else if ( outputEncoding == 5 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBD( value, 256.0 );\\n\\n\\t\\t\\t} else {\\n\\n\\t\\t\\t\\treturn LinearToGamma( value, 2.2 );\\n\\n\\t\\t\\t}\\n\\n\\t\\t}\\n\\n\\t\\tvec4 envMapTexelToLinear( vec4 color ) {\\n\\n\\t\\t\\treturn inputTexelToLinear( color );\\n\\n\\t\\t}\\n\\t\\n\\n\\t\\t\\t#include \\n\\n\\t\\t\\tvoid main() {\\n\\n\\t\\t\\t\\tgl_FragColor = vec4( 0.0, 0.0, 0.0, 1.0 );\\n\\n\\t\\t\\t\\tvec3 outputDirection = normalize( vOutputDirection );\\n\\t\\t\\t\\tvec2 uv = equirectUv( outputDirection );\\n\\n\\t\\t\\t\\tvec2 f = fract( uv / texelSize - 0.5 );\\n\\t\\t\\t\\tuv -= f * texelSize;\\n\\t\\t\\t\\tvec3 tl = envMapTexelToLinear( texture2D ( envMap, uv ) ).rgb;\\n\\t\\t\\t\\tuv.x += texelSize.x;\\n\\t\\t\\t\\tvec3 tr = envMapTexelToLinear( texture2D ( envMap, uv ) ).rgb;\\n\\t\\t\\t\\tuv.y += texelSize.y;\\n\\t\\t\\t\\tvec3 br = envMapTexelToLinear( texture2D ( envMap, uv ) ).rgb;\\n\\t\\t\\t\\tuv.x -= texelSize.x;\\n\\t\\t\\t\\tvec3 bl = envMapTexelToLinear( texture2D ( envMap, uv ) ).rgb;\\n\\n\\t\\t\\t\\tvec3 tm = mix( tl, tr, f.x );\\n\\t\\t\\t\\tvec3 bm = mix( bl, br, f.x );\\n\\t\\t\\t\\tgl_FragColor.rgb = mix( tm, bm, f.y );\\n\\n\\t\\t\\t\\tgl_FragColor = linearToOutputTexel( gl_FragColor );\\n\\n\\t\\t\\t}\\n\\t\\t",blending:_,depthTest:!1,depthWrite:!1})}function va(){return new Ks({name:"CubemapToCubeUV",uniforms:{envMap:{value:null},inputEncoding:{value:ta[Zt]},outputEncoding:{value:ta[Zt]}},vertexShader:"\\n\\n\\t\\tprecision mediump float;\\n\\t\\tprecision mediump int;\\n\\n\\t\\tattribute vec3 position;\\n\\t\\tattribute vec2 uv;\\n\\t\\tattribute float faceIndex;\\n\\n\\t\\tvarying vec3 vOutputDirection;\\n\\n\\t\\t// RH coordinate system; PMREM face-indexing convention\\n\\t\\tvec3 getDirection( vec2 uv, float face ) {\\n\\n\\t\\t\\tuv = 2.0 * uv - 1.0;\\n\\n\\t\\t\\tvec3 direction = vec3( uv, 1.0 );\\n\\n\\t\\t\\tif ( face == 0.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.zyx; // ( 1, v, u ) pos x\\n\\n\\t\\t\\t} else if ( face == 1.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.xzy;\\n\\t\\t\\t\\tdirection.xz *= -1.0; // ( -u, 1, -v ) pos y\\n\\n\\t\\t\\t} else if ( face == 2.0 ) {\\n\\n\\t\\t\\t\\tdirection.x *= -1.0; // ( -u, v, 1 ) pos z\\n\\n\\t\\t\\t} else if ( face == 3.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.zyx;\\n\\t\\t\\t\\tdirection.xz *= -1.0; // ( -1, v, -u ) neg x\\n\\n\\t\\t\\t} else if ( face == 4.0 ) {\\n\\n\\t\\t\\t\\tdirection = direction.xzy;\\n\\t\\t\\t\\tdirection.xy *= -1.0; // ( -u, -1, v ) neg y\\n\\n\\t\\t\\t} else if ( face == 5.0 ) {\\n\\n\\t\\t\\t\\tdirection.z *= -1.0; // ( u, v, -1 ) neg z\\n\\n\\t\\t\\t}\\n\\n\\t\\t\\treturn direction;\\n\\n\\t\\t}\\n\\n\\t\\tvoid main() {\\n\\n\\t\\t\\tvOutputDirection = getDirection( uv, faceIndex );\\n\\t\\t\\tgl_Position = vec4( position, 1.0 );\\n\\n\\t\\t}\\n\\t",fragmentShader:"\\n\\n\\t\\t\\tprecision mediump float;\\n\\t\\t\\tprecision mediump int;\\n\\n\\t\\t\\tvarying vec3 vOutputDirection;\\n\\n\\t\\t\\tuniform samplerCube envMap;\\n\\n\\t\\t\\t\\n\\n\\t\\tuniform int inputEncoding;\\n\\t\\tuniform int outputEncoding;\\n\\n\\t\\t#include \\n\\n\\t\\tvec4 inputTexelToLinear( vec4 value ) {\\n\\n\\t\\t\\tif ( inputEncoding == 0 ) {\\n\\n\\t\\t\\t\\treturn value;\\n\\n\\t\\t\\t} else if ( inputEncoding == 1 ) {\\n\\n\\t\\t\\t\\treturn sRGBToLinear( value );\\n\\n\\t\\t\\t} else if ( inputEncoding == 2 ) {\\n\\n\\t\\t\\t\\treturn RGBEToLinear( value );\\n\\n\\t\\t\\t} else if ( inputEncoding == 3 ) {\\n\\n\\t\\t\\t\\treturn RGBMToLinear( value, 7.0 );\\n\\n\\t\\t\\t} else if ( inputEncoding == 4 ) {\\n\\n\\t\\t\\t\\treturn RGBMToLinear( value, 16.0 );\\n\\n\\t\\t\\t} else if ( inputEncoding == 5 ) {\\n\\n\\t\\t\\t\\treturn RGBDToLinear( value, 256.0 );\\n\\n\\t\\t\\t} else {\\n\\n\\t\\t\\t\\treturn GammaToLinear( value, 2.2 );\\n\\n\\t\\t\\t}\\n\\n\\t\\t}\\n\\n\\t\\tvec4 linearToOutputTexel( vec4 value ) {\\n\\n\\t\\t\\tif ( outputEncoding == 0 ) {\\n\\n\\t\\t\\t\\treturn value;\\n\\n\\t\\t\\t} else if ( outputEncoding == 1 ) {\\n\\n\\t\\t\\t\\treturn LinearTosRGB( value );\\n\\n\\t\\t\\t} else if ( outputEncoding == 2 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBE( value );\\n\\n\\t\\t\\t} else if ( outputEncoding == 3 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBM( value, 7.0 );\\n\\n\\t\\t\\t} else if ( outputEncoding == 4 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBM( value, 16.0 );\\n\\n\\t\\t\\t} else if ( outputEncoding == 5 ) {\\n\\n\\t\\t\\t\\treturn LinearToRGBD( value, 256.0 );\\n\\n\\t\\t\\t} else {\\n\\n\\t\\t\\t\\treturn LinearToGamma( value, 2.2 );\\n\\n\\t\\t\\t}\\n\\n\\t\\t}\\n\\n\\t\\tvec4 envMapTexelToLinear( vec4 color ) {\\n\\n\\t\\t\\treturn inputTexelToLinear( color );\\n\\n\\t\\t}\\n\\t\\n\\n\\t\\t\\tvoid main() {\\n\\n\\t\\t\\t\\tgl_FragColor = vec4( 0.0, 0.0, 0.0, 1.0 );\\n\\t\\t\\t\\tgl_FragColor.rgb = envMapTexelToLinear( textureCube( envMap, vec3( - vOutputDirection.x, vOutputDirection.yz ) ) ).rgb;\\n\\t\\t\\t\\tgl_FragColor = linearToOutputTexel( gl_FragColor );\\n\\n\\t\\t\\t}\\n\\t\\t",blending:_,depthTest:!1,depthWrite:!1})}function ya(e){let t=new WeakMap,n=null;function i(e){const n=e.target;n.removeEventListener("dispose",i);const r=t.get(n);void 0!==r&&(t.delete(n),r.dispose())}return{get:function(r){if(r&&r.isTexture&&!1===r.isRenderTargetTexture){const s=r.mapping,a=s===oe||s===le,o=s===se||s===ae;if(a||o){if(t.has(r))return t.get(r).texture;{const s=r.image;if(a&&s&&s.height>0||o&&s&&function(e){let t=0;for(let n=0;n<6;n++)void 0!==e[n]&&t++;return 6===t}(s)){const s=e.getRenderTarget();null===n&&(n=new ua(e));const o=a?n.fromEquirectangular(r):n.fromCubemap(r);return t.set(r,o),e.setRenderTarget(s),r.addEventListener("dispose",i),o.texture}return null}}}return r},dispose:function(){t=new WeakMap,null!==n&&(n.dispose(),n=null)}}}function _a(e){const t={};function n(n){if(void 0!==t[n])return t[n];let i;switch(n){case"WEBGL_depth_texture":i=e.getExtension("WEBGL_depth_texture")||e.getExtension("MOZ_WEBGL_depth_texture")||e.getExtension("WEBKIT_WEBGL_depth_texture");break;case"EXT_texture_filter_anisotropic":i=e.getExtension("EXT_texture_filter_anisotropic")||e.getExtension("MOZ_EXT_texture_filter_anisotropic")||e.getExtension("WEBKIT_EXT_texture_filter_anisotropic");break;case"WEBGL_compressed_texture_s3tc":i=e.getExtension("WEBGL_compressed_texture_s3tc")||e.getExtension("MOZ_WEBGL_compressed_texture_s3tc")||e.getExtension("WEBKIT_WEBGL_compressed_texture_s3tc");break;case"WEBGL_compressed_texture_pvrtc":i=e.getExtension("WEBGL_compressed_texture_pvrtc")||e.getExtension("WEBKIT_WEBGL_compressed_texture_pvrtc");break;default:i=e.getExtension(n)}return t[n]=i,i}return{has:function(e){return null!==n(e)},init:function(e){e.isWebGL2?n("EXT_color_buffer_float"):(n("WEBGL_depth_texture"),n("OES_texture_float"),n("OES_texture_half_float"),n("OES_texture_half_float_linear"),n("OES_standard_derivatives"),n("OES_element_index_uint"),n("OES_vertex_array_object"),n("ANGLE_instanced_arrays")),n("OES_texture_float_linear"),n("EXT_color_buffer_half_float")},get:function(e){const t=n(e);return null===t&&console.warn("THREE.WebGLRenderer: "+e+" extension not supported."),t}}}function xa(e,t,n,i){const r={},s=new WeakMap;function a(e){const o=e.target;null!==o.index&&t.remove(o.index);for(const e in o.attributes)t.remove(o.attributes[e]);o.removeEventListener("dispose",a),delete r[o.id];const l=s.get(o);l&&(t.remove(l),s.delete(o)),i.releaseStatesOfGeometry(o),!0===o.isInstancedBufferGeometry&&delete o._maxInstanceCount,n.memory.geometries--}function o(e){const n=[],i=e.index,r=e.attributes.position;let a=0;if(null!==i){const e=i.array;a=i.version;for(let t=0,i=e.length;t65535?zr:Fr)(n,1);o.version=a;const l=s.get(e);l&&t.remove(l),s.set(e,o)}return{get:function(e,t){return!0===r[t.id]||(t.addEventListener("dispose",a),r[t.id]=!0,n.memory.geometries++),t},update:function(e){const n=e.attributes;for(const e in n)t.update(n[e],34962);const i=e.morphAttributes;for(const e in i){const n=i[e];for(let e=0,i=n.length;e0)return e;const r=t*n;let s=Na[r];if(void 0===s&&(s=new Float32Array(r),Na[r]=s),0!==t){i.toArray(s,0);for(let i=1,r=0;i!==t;++i)r+=n,e[i].toArray(s,r)}return s}function Ua(e,t){if(e.length!==t.length)return!1;for(let n=0,i=e.length;n/gm;function Vo(e){return e.replace(Go,Wo)}function Wo(e,t){const n=Hs[t];if(void 0===n)throw new Error("Can not resolve #include <"+t+">");return Vo(n)}const jo=/#pragma unroll_loop[\\s]+?for \\( int i \\= (\\d+)\\; i < (\\d+)\\; i \\+\\+ \\) \\{([\\s\\S]+?)(?=\\})\\}/g,qo=/#pragma unroll_loop_start\\s+for\\s*\\(\\s*int\\s+i\\s*=\\s*(\\d+)\\s*;\\s*i\\s*<\\s*(\\d+)\\s*;\\s*i\\s*\\+\\+\\s*\\)\\s*{([\\s\\S]+?)}\\s+#pragma unroll_loop_end/g;function Xo(e){return e.replace(qo,Jo).replace(jo,Yo)}function Yo(e,t,n,i){return console.warn("WebGLProgram: #pragma unroll_loop shader syntax is deprecated. Please use #pragma unroll_loop_start syntax instead."),Jo(0,t,n,i)}function Jo(e,t,n,i){let r="";for(let e=parseInt(t);e0?e.gammaFactor:1,g=n.isWebGL2?"":function(e){return[e.extensionDerivatives||e.envMapCubeUV||e.bumpMap||e.tangentSpaceNormalMap||e.clearcoatNormalMap||e.flatShading||"physical"===e.shaderID?"#extension GL_OES_standard_derivatives : enable":"",(e.extensionFragDepth||e.logarithmicDepthBuffer)&&e.rendererExtensionFragDepth?"#extension GL_EXT_frag_depth : enable":"",e.extensionDrawBuffers&&e.rendererExtensionDrawBuffers?"#extension GL_EXT_draw_buffers : require":"",(e.extensionShaderTextureLOD||e.envMap||e.transmission)&&e.rendererExtensionShaderTextureLod?"#extension GL_EXT_shader_texture_lod : enable":""].filter(Uo).join("\\n")}(n),v=function(e){const t=[];for(const n in e){const i=e[n];!1!==i&&t.push("#define "+n+" "+i)}return t.join("\\n")}(s),y=r.createProgram();let _,x,b=n.glslVersion?"#version "+n.glslVersion+"\\n":"";n.isRawShaderMaterial?(_=[v].filter(Uo).join("\\n"),_.length>0&&(_+="\\n"),x=[g,v].filter(Uo).join("\\n"),x.length>0&&(x+="\\n")):(_=[Zo(n),"#define SHADER_NAME "+n.shaderName,v,n.instancing?"#define USE_INSTANCING":"",n.instancingColor?"#define USE_INSTANCING_COLOR":"",n.supportsVertexTextures?"#define VERTEX_TEXTURES":"","#define GAMMA_FACTOR "+m,"#define MAX_BONES "+n.maxBones,n.useFog&&n.fog?"#define USE_FOG":"",n.useFog&&n.fogExp2?"#define FOG_EXP2":"",n.map?"#define USE_MAP":"",n.envMap?"#define USE_ENVMAP":"",n.envMap?"#define "+h:"",n.lightMap?"#define USE_LIGHTMAP":"",n.aoMap?"#define USE_AOMAP":"",n.emissiveMap?"#define USE_EMISSIVEMAP":"",n.bumpMap?"#define USE_BUMPMAP":"",n.normalMap?"#define USE_NORMALMAP":"",n.normalMap&&n.objectSpaceNormalMap?"#define OBJECTSPACE_NORMALMAP":"",n.normalMap&&n.tangentSpaceNormalMap?"#define TANGENTSPACE_NORMALMAP":"",n.clearcoatMap?"#define USE_CLEARCOATMAP":"",n.clearcoatRoughnessMap?"#define USE_CLEARCOAT_ROUGHNESSMAP":"",n.clearcoatNormalMap?"#define USE_CLEARCOAT_NORMALMAP":"",n.displacementMap&&n.supportsVertexTextures?"#define USE_DISPLACEMENTMAP":"",n.specularMap?"#define USE_SPECULARMAP":"",n.specularIntensityMap?"#define USE_SPECULARINTENSITYMAP":"",n.specularTintMap?"#define USE_SPECULARTINTMAP":"",n.roughnessMap?"#define USE_ROUGHNESSMAP":"",n.metalnessMap?"#define USE_METALNESSMAP":"",n.alphaMap?"#define USE_ALPHAMAP":"",n.transmission?"#define USE_TRANSMISSION":"",n.transmissionMap?"#define USE_TRANSMISSIONMAP":"",n.thicknessMap?"#define USE_THICKNESSMAP":"",n.vertexTangents?"#define USE_TANGENT":"",n.vertexColors?"#define USE_COLOR":"",n.vertexAlphas?"#define USE_COLOR_ALPHA":"",n.vertexUvs?"#define USE_UV":"",n.uvsVertexOnly?"#define UVS_VERTEX_ONLY":"",n.flatShading?"#define FLAT_SHADED":"",n.skinning?"#define USE_SKINNING":"",n.useVertexTexture?"#define BONE_TEXTURE":"",n.morphTargets?"#define USE_MORPHTARGETS":"",n.morphNormals&&!1===n.flatShading?"#define USE_MORPHNORMALS":"",n.doubleSided?"#define DOUBLE_SIDED":"",n.flipSided?"#define FLIP_SIDED":"",n.shadowMapEnabled?"#define USE_SHADOWMAP":"",n.shadowMapEnabled?"#define "+l:"",n.sizeAttenuation?"#define USE_SIZEATTENUATION":"",n.logarithmicDepthBuffer?"#define USE_LOGDEPTHBUF":"",n.logarithmicDepthBuffer&&n.rendererExtensionFragDepth?"#define USE_LOGDEPTHBUF_EXT":"","uniform mat4 modelMatrix;","uniform mat4 modelViewMatrix;","uniform mat4 projectionMatrix;","uniform mat4 viewMatrix;","uniform mat3 normalMatrix;","uniform vec3 cameraPosition;","uniform bool isOrthographic;","#ifdef USE_INSTANCING","\\tattribute mat4 instanceMatrix;","#endif","#ifdef USE_INSTANCING_COLOR","\\tattribute vec3 instanceColor;","#endif","attribute vec3 position;","attribute vec3 normal;","attribute vec2 uv;","#ifdef USE_TANGENT","\\tattribute vec4 tangent;","#endif","#if defined( USE_COLOR_ALPHA )","\\tattribute vec4 color;","#elif defined( USE_COLOR )","\\tattribute vec3 color;","#endif","#ifdef USE_MORPHTARGETS","\\tattribute vec3 morphTarget0;","\\tattribute vec3 morphTarget1;","\\tattribute vec3 morphTarget2;","\\tattribute vec3 morphTarget3;","\\t#ifdef USE_MORPHNORMALS","\\t\\tattribute vec3 morphNormal0;","\\t\\tattribute vec3 morphNormal1;","\\t\\tattribute vec3 morphNormal2;","\\t\\tattribute vec3 morphNormal3;","\\t#else","\\t\\tattribute vec3 morphTarget4;","\\t\\tattribute vec3 morphTarget5;","\\t\\tattribute vec3 morphTarget6;","\\t\\tattribute vec3 morphTarget7;","\\t#endif","#endif","#ifdef USE_SKINNING","\\tattribute vec4 skinIndex;","\\tattribute vec4 skinWeight;","#endif","\\n"].filter(Uo).join("\\n"),x=[g,Zo(n),"#define SHADER_NAME "+n.shaderName,v,"#define GAMMA_FACTOR "+m,n.useFog&&n.fog?"#define USE_FOG":"",n.useFog&&n.fogExp2?"#define FOG_EXP2":"",n.map?"#define USE_MAP":"",n.matcap?"#define USE_MATCAP":"",n.envMap?"#define USE_ENVMAP":"",n.envMap?"#define "+c:"",n.envMap?"#define "+h:"",n.envMap?"#define "+f:"",n.lightMap?"#define USE_LIGHTMAP":"",n.aoMap?"#define USE_AOMAP":"",n.emissiveMap?"#define USE_EMISSIVEMAP":"",n.bumpMap?"#define USE_BUMPMAP":"",n.normalMap?"#define USE_NORMALMAP":"",n.normalMap&&n.objectSpaceNormalMap?"#define OBJECTSPACE_NORMALMAP":"",n.normalMap&&n.tangentSpaceNormalMap?"#define TANGENTSPACE_NORMALMAP":"",n.clearcoat?"#define USE_CLEARCOAT":"",n.clearcoatMap?"#define USE_CLEARCOATMAP":"",n.clearcoatRoughnessMap?"#define USE_CLEARCOAT_ROUGHNESSMAP":"",n.clearcoatNormalMap?"#define USE_CLEARCOAT_NORMALMAP":"",n.specularMap?"#define USE_SPECULARMAP":"",n.specularIntensityMap?"#define USE_SPECULARINTENSITYMAP":"",n.specularTintMap?"#define USE_SPECULARTINTMAP":"",n.roughnessMap?"#define USE_ROUGHNESSMAP":"",n.metalnessMap?"#define USE_METALNESSMAP":"",n.alphaMap?"#define USE_ALPHAMAP":"",n.alphaTest?"#define USE_ALPHATEST":"",n.sheenTint?"#define USE_SHEEN":"",n.transmission?"#define USE_TRANSMISSION":"",n.transmissionMap?"#define USE_TRANSMISSIONMAP":"",n.thicknessMap?"#define USE_THICKNESSMAP":"",n.vertexTangents?"#define USE_TANGENT":"",n.vertexColors||n.instancingColor?"#define USE_COLOR":"",n.vertexAlphas?"#define USE_COLOR_ALPHA":"",n.vertexUvs?"#define USE_UV":"",n.uvsVertexOnly?"#define UVS_VERTEX_ONLY":"",n.gradientMap?"#define USE_GRADIENTMAP":"",n.flatShading?"#define FLAT_SHADED":"",n.doubleSided?"#define DOUBLE_SIDED":"",n.flipSided?"#define FLIP_SIDED":"",n.shadowMapEnabled?"#define USE_SHADOWMAP":"",n.shadowMapEnabled?"#define "+l:"",n.premultipliedAlpha?"#define PREMULTIPLIED_ALPHA":"",n.physicallyCorrectLights?"#define PHYSICALLY_CORRECT_LIGHTS":"",n.logarithmicDepthBuffer?"#define USE_LOGDEPTHBUF":"",n.logarithmicDepthBuffer&&n.rendererExtensionFragDepth?"#define USE_LOGDEPTHBUF_EXT":"",(n.extensionShaderTextureLOD||n.envMap)&&n.rendererExtensionShaderTextureLod?"#define TEXTURE_LOD_EXT":"","uniform mat4 viewMatrix;","uniform vec3 cameraPosition;","uniform bool isOrthographic;",n.toneMapping!==Q?"#define TONE_MAPPING":"",n.toneMapping!==Q?Hs.tonemapping_pars_fragment:"",n.toneMapping!==Q?Fo("toneMapping",n.toneMapping):"",n.dithering?"#define DITHERING":"",n.format===Be?"#define OPAQUE":"",Hs.encodings_pars_fragment,n.map?Oo("mapTexelToLinear",n.mapEncoding):"",n.matcap?Oo("matcapTexelToLinear",n.matcapEncoding):"",n.envMap?Oo("envMapTexelToLinear",n.envMapEncoding):"",n.emissiveMap?Oo("emissiveMapTexelToLinear",n.emissiveMapEncoding):"",n.specularTintMap?Oo("specularTintMapTexelToLinear",n.specularTintMapEncoding):"",n.lightMap?Oo("lightMapTexelToLinear",n.lightMapEncoding):"",Bo("linearToOutputTexel",n.outputEncoding),n.depthPacking?"#define DEPTH_PACKING "+n.depthPacking:"","\\n"].filter(Uo).join("\\n")),a=Vo(a),a=zo(a,n),a=Ho(a,n),o=Vo(o),o=zo(o,n),o=Ho(o,n),a=Xo(a),o=Xo(o),n.isWebGL2&&!0!==n.isRawShaderMaterial&&(b="#version 300 es\\n",_=["#define attribute in","#define varying out","#define texture2D texture"].join("\\n")+"\\n"+_,x=["#define varying in",n.glslVersion===Dn?"":"out highp vec4 pc_fragColor;",n.glslVersion===Dn?"":"#define gl_FragColor pc_fragColor","#define gl_FragDepthEXT gl_FragDepth","#define texture2D texture","#define textureCube texture","#define texture2DProj textureProj","#define texture2DLodEXT textureLod","#define texture2DProjLodEXT textureProjLod","#define textureCubeLodEXT textureLod","#define texture2DGradEXT textureGrad","#define texture2DProjGradEXT textureProjGrad","#define textureCubeGradEXT textureGrad"].join("\\n")+"\\n"+x);const w=b+x+o,M=ko(r,35633,b+_+a),T=ko(r,35632,w);if(r.attachShader(y,M),r.attachShader(y,T),void 0!==n.index0AttributeName?r.bindAttribLocation(y,0,n.index0AttributeName):!0===n.morphTargets&&r.bindAttribLocation(y,0,"position"),r.linkProgram(y),e.debug.checkShaderErrors){const e=r.getProgramInfoLog(y).trim(),t=r.getShaderInfoLog(M).trim(),n=r.getShaderInfoLog(T).trim();let i=!0,s=!0;if(!1===r.getProgramParameter(y,35714)){i=!1;const t=Do(r,M,"vertex"),n=Do(r,T,"fragment");console.error("THREE.WebGLProgram: Shader Error "+r.getError()+" - VALIDATE_STATUS "+r.getProgramParameter(y,35715)+"\\n\\nProgram Info Log: "+e+"\\n"+t+"\\n"+n)}else""!==e?console.warn("THREE.WebGLProgram: Program Info Log:",e):""!==t&&""!==n||(s=!1);s&&(this.diagnostics={runnable:i,programLog:e,vertexShader:{log:t,prefix:_},fragmentShader:{log:n,prefix:x}})}let E,S;return r.deleteShader(M),r.deleteShader(T),this.getUniforms=function(){return void 0===E&&(E=new Po(r,y)),E},this.getAttributes=function(){return void 0===S&&(S=function(e,t){const n={},i=e.getProgramParameter(t,35721);for(let r=0;r0,R=s.clearcoat>0;return{isWebGL2:l,shaderID:T,shaderName:s.type,vertexShader:S,fragmentShader:A,defines:s.defines,isRawShaderMaterial:!0===s.isRawShaderMaterial,glslVersion:s.glslVersion,precision:p,instancing:!0===x.isInstancedMesh,instancingColor:!0===x.isInstancedMesh&&null!==x.instanceColor,supportsVertexTextures:d,outputEncoding:null!==L?y(L.texture):e.outputEncoding,map:!!s.map,mapEncoding:y(s.map),matcap:!!s.matcap,matcapEncoding:y(s.matcap),envMap:!!M,envMapMode:M&&M.mapping,envMapEncoding:y(M),envMapCubeUV:!!M&&(M.mapping===ce||M.mapping===he),lightMap:!!s.lightMap,lightMapEncoding:y(s.lightMap),aoMap:!!s.aoMap,emissiveMap:!!s.emissiveMap,emissiveMapEncoding:y(s.emissiveMap),bumpMap:!!s.bumpMap,normalMap:!!s.normalMap,objectSpaceNormalMap:s.normalMapType===ln,tangentSpaceNormalMap:s.normalMapType===on,clearcoat:R,clearcoatMap:R&&!!s.clearcoatMap,clearcoatRoughnessMap:R&&!!s.clearcoatRoughnessMap,clearcoatNormalMap:R&&!!s.clearcoatNormalMap,displacementMap:!!s.displacementMap,roughnessMap:!!s.roughnessMap,metalnessMap:!!s.metalnessMap,specularMap:!!s.specularMap,specularIntensityMap:!!s.specularIntensityMap,specularTintMap:!!s.specularTintMap,specularTintMapEncoding:y(s.specularTintMap),alphaMap:!!s.alphaMap,alphaTest:C,gradientMap:!!s.gradientMap,sheenTint:!!s.sheenTint&&(s.sheenTint.r>0||s.sheenTint.g>0||s.sheenTint.b>0),transmission:s.transmission>0,transmissionMap:!!s.transmissionMap,thicknessMap:!!s.thicknessMap,combine:s.combine,vertexTangents:!!s.normalMap&&!!x.geometry&&!!x.geometry.attributes.tangent,vertexColors:s.vertexColors,vertexAlphas:!0===s.vertexColors&&!!x.geometry&&!!x.geometry.attributes.color&&4===x.geometry.attributes.color.itemSize,vertexUvs:!!(s.map||s.bumpMap||s.normalMap||s.specularMap||s.alphaMap||s.emissiveMap||s.roughnessMap||s.metalnessMap||s.clearcoatMap||s.clearcoatRoughnessMap||s.clearcoatNormalMap||s.displacementMap||s.transmissionMap||s.thicknessMap||s.specularIntensityMap||s.specularTintMap),uvsVertexOnly:!(s.map||s.bumpMap||s.normalMap||s.specularMap||s.alphaMap||s.emissiveMap||s.roughnessMap||s.metalnessMap||s.clearcoatNormalMap||s.transmission>0||s.transmissionMap||s.thicknessMap||s.specularIntensityMap||s.specularTintMap||!s.displacementMap),fog:!!b,useFog:s.fog,fogExp2:b&&b.isFogExp2,flatShading:!!s.flatShading,sizeAttenuation:s.sizeAttenuation,logarithmicDepthBuffer:c,skinning:!0===x.isSkinnedMesh&&E>0,maxBones:E,useVertexTexture:h,morphTargets:!!x.geometry&&!!x.geometry.morphAttributes.position,morphNormals:!!x.geometry&&!!x.geometry.morphAttributes.normal,numDirLights:o.directional.length,numPointLights:o.point.length,numSpotLights:o.spot.length,numRectAreaLights:o.rectArea.length,numHemiLights:o.hemi.length,numDirLightShadows:o.directionalShadowMap.length,numPointLightShadows:o.pointShadowMap.length,numSpotLightShadows:o.spotShadowMap.length,numClippingPlanes:a.numPlanes,numClipIntersection:a.numIntersection,format:s.format,dithering:s.dithering,shadowMapEnabled:e.shadowMap.enabled&&v.length>0,shadowMapType:e.shadowMap.type,toneMapping:s.toneMapped?e.toneMapping:Q,physicallyCorrectLights:e.physicallyCorrectLights,premultipliedAlpha:s.premultipliedAlpha,doubleSided:s.side===g,flipSided:s.side===m,depthPacking:void 0!==s.depthPacking&&s.depthPacking,index0AttributeName:s.index0AttributeName,extensionDerivatives:s.extensions&&s.extensions.derivatives,extensionFragDepth:s.extensions&&s.extensions.fragDepth,extensionDrawBuffers:s.extensions&&s.extensions.drawBuffers,extensionShaderTextureLOD:s.extensions&&s.extensions.shaderTextureLOD,rendererExtensionFragDepth:l||i.has("EXT_frag_depth"),rendererExtensionDrawBuffers:l||i.has("WEBGL_draw_buffers"),rendererExtensionShaderTextureLod:l||i.has("EXT_shader_texture_lod"),customProgramCacheKey:s.customProgramCacheKey()}},getProgramCacheKey:function(t){const n=[];if(t.shaderID?n.push(t.shaderID):(n.push(t.fragmentShader),n.push(t.vertexShader)),void 0!==t.defines)for(const e in t.defines)n.push(e),n.push(t.defines[e]);if(!1===t.isRawShaderMaterial){for(let e=0;e0?r.push(h):!0===n.transparent?s.push(h):i.push(h)},unshift:function(e,t,n,a,l,c){const h=o(e,t,n,a,l,c);n.transmission>0?r.unshift(h):!0===n.transparent?s.unshift(h):i.unshift(h)},finish:function(){for(let e=n,i=t.length;e1&&i.sort(e||el),r.length>1&&r.sort(t||tl),s.length>1&&s.sort(t||tl)}}}function il(e){let t=new WeakMap;return{get:function(n,i){let r;return!1===t.has(n)?(r=new nl(e),t.set(n,[r])):i>=t.get(n).length?(r=new nl(e),t.get(n).push(r)):r=t.get(n)[i],r},dispose:function(){t=new WeakMap}}}function rl(){const e={};return{get:function(t){if(void 0!==e[t.id])return e[t.id];let n;switch(t.type){case"DirectionalLight":n={direction:new oi,color:new Cr};break;case"SpotLight":n={position:new oi,direction:new oi,color:new Cr,distance:0,coneCos:0,penumbraCos:0,decay:0};break;case"PointLight":n={position:new oi,color:new Cr,distance:0,decay:0};break;case"HemisphereLight":n={direction:new oi,skyColor:new Cr,groundColor:new Cr};break;case"RectAreaLight":n={color:new Cr,position:new oi,halfWidth:new oi,halfHeight:new oi}}return e[t.id]=n,n}}}let sl=0;function al(e,t){return(t.castShadow?1:0)-(e.castShadow?1:0)}function ol(e,t){const n=new rl,i=function(){const e={};return{get:function(t){if(void 0!==e[t.id])return e[t.id];let n;switch(t.type){case"DirectionalLight":case"SpotLight":n={shadowBias:0,shadowNormalBias:0,shadowRadius:1,shadowMapSize:new Jn};break;case"PointLight":n={shadowBias:0,shadowNormalBias:0,shadowRadius:1,shadowMapSize:new Jn,shadowCameraNear:1,shadowCameraFar:1e3}}return e[t.id]=n,n}}}(),r={version:0,hash:{directionalLength:-1,pointLength:-1,spotLength:-1,rectAreaLength:-1,hemiLength:-1,numDirectionalShadows:-1,numPointShadows:-1,numSpotShadows:-1},ambient:[0,0,0],probe:[],directional:[],directionalShadow:[],directionalShadowMap:[],directionalShadowMatrix:[],spot:[],spotShadow:[],spotShadowMap:[],spotShadowMatrix:[],rectArea:[],rectAreaLTC1:null,rectAreaLTC2:null,point:[],pointShadow:[],pointShadowMap:[],pointShadowMatrix:[],hemi:[]};for(let e=0;e<9;e++)r.probe.push(new oi);const s=new oi,a=new Fi,o=new Fi;return{setup:function(s,a){let o=0,l=0,c=0;for(let e=0;e<9;e++)r.probe[e].set(0,0,0);let h=0,u=0,d=0,p=0,f=0,m=0,g=0,v=0;s.sort(al);const y=!0!==a?Math.PI:1;for(let e=0,t=s.length;e0&&(t.isWebGL2||!0===e.has("OES_texture_float_linear")?(r.rectAreaLTC1=Gs.LTC_FLOAT_1,r.rectAreaLTC2=Gs.LTC_FLOAT_2):!0===e.has("OES_texture_half_float_linear")?(r.rectAreaLTC1=Gs.LTC_HALF_1,r.rectAreaLTC2=Gs.LTC_HALF_2):console.error("THREE.WebGLRenderer: Unable to use RectAreaLight. Missing WebGL extensions.")),r.ambient[0]=o,r.ambient[1]=l,r.ambient[2]=c;const _=r.hash;_.directionalLength===h&&_.pointLength===u&&_.spotLength===d&&_.rectAreaLength===p&&_.hemiLength===f&&_.numDirectionalShadows===m&&_.numPointShadows===g&&_.numSpotShadows===v||(r.directional.length=h,r.spot.length=d,r.rectArea.length=p,r.point.length=u,r.hemi.length=f,r.directionalShadow.length=m,r.directionalShadowMap.length=m,r.pointShadow.length=g,r.pointShadowMap.length=g,r.spotShadow.length=v,r.spotShadowMap.length=v,r.directionalShadowMatrix.length=m,r.pointShadowMatrix.length=g,r.spotShadowMatrix.length=v,_.directionalLength=h,_.pointLength=u,_.spotLength=d,_.rectAreaLength=p,_.hemiLength=f,_.numDirectionalShadows=m,_.numPointShadows=g,_.numSpotShadows=v,r.version=sl++)},setupView:function(e,t){let n=0,i=0,l=0,c=0,h=0;const u=t.matrixWorldInverse;for(let t=0,d=e.length;t=n.get(i).length?(s=new ll(e,t),n.get(i).push(s)):s=n.get(i)[r],s},dispose:function(){n=new WeakMap}}}class hl extends wr{constructor(e){super(),this.type="MeshDepthMaterial",this.depthPacking=sn,this.map=null,this.alphaMap=null,this.displacementMap=null,this.displacementScale=1,this.displacementBias=0,this.wireframe=!1,this.wireframeLinewidth=1,this.fog=!1,this.setValues(e)}copy(e){return super.copy(e),this.depthPacking=e.depthPacking,this.map=e.map,this.alphaMap=e.alphaMap,this.displacementMap=e.displacementMap,this.displacementScale=e.displacementScale,this.displacementBias=e.displacementBias,this.wireframe=e.wireframe,this.wireframeLinewidth=e.wireframeLinewidth,this}}hl.prototype.isMeshDepthMaterial=!0;class ul extends wr{constructor(e){super(),this.type="MeshDistanceMaterial",this.referencePosition=new oi,this.nearDistance=1,this.farDistance=1e3,this.map=null,this.alphaMap=null,this.displacementMap=null,this.displacementScale=1,this.displacementBias=0,this.fog=!1,this.setValues(e)}copy(e){return super.copy(e),this.referencePosition.copy(e.referencePosition),this.nearDistance=e.nearDistance,this.farDistance=e.farDistance,this.map=e.map,this.alphaMap=e.alphaMap,this.displacementMap=e.displacementMap,this.displacementScale=e.displacementScale,this.displacementBias=e.displacementBias,this}}function dl(e,t,n){let i=new Bs;const r=new Jn,s=new Jn,a=new ni,o=new hl({depthPacking:an}),l=new ul,c={},h=n.maxTextureSize,d={0:m,1:f,2:g},v=new Ts({uniforms:{shadow_pass:{value:null},resolution:{value:new Jn},radius:{value:4},samples:{value:8}},vertexShader:"void main() {\\n\\tgl_Position = vec4( position, 1.0 );\\n}",fragmentShader:"uniform sampler2D shadow_pass;\\nuniform vec2 resolution;\\nuniform float radius;\\nuniform float samples;\\n#include \\nvoid main() {\\n\\tfloat mean = 0.0;\\n\\tfloat squared_mean = 0.0;\\n\\tfloat uvStride = samples <= 1.0 ? 0.0 : 2.0 / ( samples - 1.0 );\\n\\tfloat uvStart = samples <= 1.0 ? 0.0 : - 1.0;\\n\\tfor ( float i = 0.0; i < samples; i ++ ) {\\n\\t\\tfloat uvOffset = uvStart + i * uvStride;\\n\\t\\t#ifdef HORIZONTAL_PASS\\n\\t\\t\\tvec2 distribution = unpackRGBATo2Half( texture2D( shadow_pass, ( gl_FragCoord.xy + vec2( uvOffset, 0.0 ) * radius ) / resolution ) );\\n\\t\\t\\tmean += distribution.x;\\n\\t\\t\\tsquared_mean += distribution.y * distribution.y + distribution.x * distribution.x;\\n\\t\\t#else\\n\\t\\t\\tfloat depth = unpackRGBAToDepth( texture2D( shadow_pass, ( gl_FragCoord.xy + vec2( 0.0, uvOffset ) * radius ) / resolution ) );\\n\\t\\t\\tmean += depth;\\n\\t\\t\\tsquared_mean += depth * depth;\\n\\t\\t#endif\\n\\t}\\n\\tmean = mean / samples;\\n\\tsquared_mean = squared_mean / samples;\\n\\tfloat std_dev = sqrt( squared_mean - mean * mean );\\n\\tgl_FragColor = pack2HalfToRGBA( vec2( mean, std_dev ) );\\n}"}),y=v.clone();y.defines.HORIZONTAL_PASS=1;const x=new es;x.setAttribute("position",new Nr(new Float32Array([-1,-1,.5,3,-1,.5,-1,3,.5]),3));const b=new ys(x,v),w=this;function M(n,i){const r=t.update(b);v.uniforms.shadow_pass.value=n.map.texture,v.uniforms.resolution.value=n.mapSize,v.uniforms.radius.value=n.radius,v.uniforms.samples.value=n.blurSamples,e.setRenderTarget(n.mapPass),e.clear(),e.renderBufferDirect(i,null,r,v,b,null),y.uniforms.shadow_pass.value=n.mapPass.texture,y.uniforms.resolution.value=n.mapSize,y.uniforms.radius.value=n.radius,y.uniforms.samples.value=n.blurSamples,e.setRenderTarget(n.map),e.clear(),e.renderBufferDirect(i,null,r,y,b,null)}function T(t,n,i,r,s,a,h){let u=null;const f=!0===r.isPointLight?t.customDistanceMaterial:t.customDepthMaterial;if(u=void 0!==f?f:!0===r.isPointLight?l:o,e.localClippingEnabled&&!0===i.clipShadows&&0!==i.clippingPlanes.length||i.displacementMap&&0!==i.displacementScale||i.alphaMap&&i.alphaTest>0){const e=u.uuid,t=i.uuid;let n=c[e];void 0===n&&(n={},c[e]=n);let r=n[t];void 0===r&&(r=u.clone(),n[t]=r),u=r}return u.visible=i.visible,u.wireframe=i.wireframe,u.side=h===p?null!==i.shadowSide?i.shadowSide:i.side:null!==i.shadowSide?i.shadowSide:d[i.side],u.alphaMap=i.alphaMap,u.alphaTest=i.alphaTest,u.clipShadows=i.clipShadows,u.clippingPlanes=i.clippingPlanes,u.clipIntersection=i.clipIntersection,u.displacementMap=i.displacementMap,u.displacementScale=i.displacementScale,u.displacementBias=i.displacementBias,u.wireframeLinewidth=i.wireframeLinewidth,u.linewidth=i.linewidth,!0===r.isPointLight&&!0===u.isMeshDistanceMaterial&&(u.referencePosition.setFromMatrixPosition(r.matrixWorld),u.nearDistance=s,u.farDistance=a),u}function E(n,r,s,a,o){if(!1===n.visible)return;if(n.layers.test(r.layers)&&(n.isMesh||n.isLine||n.isPoints)&&(n.castShadow||n.receiveShadow&&o===p)&&(!n.frustumCulled||i.intersectsObject(n))){n.modelViewMatrix.multiplyMatrices(s.matrixWorldInverse,n.matrixWorld);const i=t.update(n),r=n.material;if(Array.isArray(r)){const t=i.groups;for(let l=0,c=t.length;lh||r.y>h)&&(r.x>h&&(s.x=Math.floor(h/f.x),r.x=s.x*f.x,u.mapSize.x=s.x),r.y>h&&(s.y=Math.floor(h/f.y),r.y=s.y*f.y,u.mapSize.y=s.y)),null===u.map&&!u.isPointLightShadow&&this.type===p){const e={minFilter:_e,magFilter:_e,format:Fe};u.map=new ii(r.x,r.y,e),u.map.texture.name=c.name+".shadowMap",u.mapPass=new ii(r.x,r.y,e),u.camera.updateProjectionMatrix()}if(null===u.map){const e={minFilter:fe,magFilter:fe,format:Fe};u.map=new ii(r.x,r.y,e),u.map.texture.name=c.name+".shadowMap",u.camera.updateProjectionMatrix()}e.setRenderTarget(u.map),e.clear();const m=u.getViewportCount();for(let e=0;e=1):-1!==ce.indexOf("OpenGL ES")&&(le=parseFloat(/^OpenGL ES (\\d)/.exec(ce)[1]),oe=le>=2);let he=null,ue={};const de=e.getParameter(3088),pe=e.getParameter(2978),fe=(new ni).fromArray(de),me=(new ni).fromArray(pe);function ge(t,n,i){const r=new Uint8Array(4),s=e.createTexture();e.bindTexture(t,s),e.texParameteri(t,10241,9728),e.texParameteri(t,10240,9728);for(let t=0;ti||e.height>i)&&(r=i/Math.max(e.width,e.height)),r<1||!0===t){if("undefined"!=typeof HTMLImageElement&&e instanceof HTMLImageElement||"undefined"!=typeof HTMLCanvasElement&&e instanceof HTMLCanvasElement||"undefined"!=typeof ImageBitmap&&e instanceof ImageBitmap){const i=t?Xn:Math.floor,s=i(r*e.width),a=i(r*e.height);void 0===p&&(p=m(s,a));const o=n?m(s,a):p;return o.width=s,o.height=a,o.getContext("2d").drawImage(e,0,0,s,a),console.warn("THREE.WebGLRenderer: Texture has been resized from ("+e.width+"x"+e.height+") to ("+s+"x"+a+")."),o}return"data"in e&&console.warn("THREE.WebGLRenderer: Image in DataTexture is too big ("+e.width+"x"+e.height+")."),e}return e}function v(e){return jn(e.width)&&jn(e.height)}function y(e,t){return e.generateMipmaps&&t&&e.minFilter!==fe&&e.minFilter!==_e}function _(t,n,r,s,a=1){e.generateMipmap(t),i.get(n).__maxMipLevel=Math.log2(Math.max(r,s,a))}function x(n,i,r){if(!1===o)return i;if(null!==n){if(void 0!==e[n])return e[n];console.warn("THREE.WebGLRenderer: Attempt to use non-existing WebGL internal format '"+n+"'")}let s=i;return 6403===i&&(5126===r&&(s=33326),5131===r&&(s=33325),5121===r&&(s=33321)),6407===i&&(5126===r&&(s=34837),5131===r&&(s=34843),5121===r&&(s=32849)),6408===i&&(5126===r&&(s=34836),5131===r&&(s=34842),5121===r&&(s=32856)),33325!==s&&33326!==s&&34842!==s&&34836!==s||t.get("EXT_color_buffer_float"),s}function b(e){return e===fe||e===me||e===ve?9728:9729}function w(t){const n=t.target;n.removeEventListener("dispose",w),function(t){const n=i.get(t);void 0!==n.__webglInit&&(e.deleteTexture(n.__webglTexture),i.remove(t))}(n),n.isVideoTexture&&d.delete(n),a.memory.textures--}function M(t){const n=t.target;n.removeEventListener("dispose",M),function(t){const n=t.texture,r=i.get(t),s=i.get(n);if(t){if(void 0!==s.__webglTexture&&(e.deleteTexture(s.__webglTexture),a.memory.textures--),t.depthTexture&&t.depthTexture.dispose(),t.isWebGLCubeRenderTarget)for(let t=0;t<6;t++)e.deleteFramebuffer(r.__webglFramebuffer[t]),r.__webglDepthbuffer&&e.deleteRenderbuffer(r.__webglDepthbuffer[t]);else e.deleteFramebuffer(r.__webglFramebuffer),r.__webglDepthbuffer&&e.deleteRenderbuffer(r.__webglDepthbuffer),r.__webglMultisampledFramebuffer&&e.deleteFramebuffer(r.__webglMultisampledFramebuffer),r.__webglColorRenderbuffer&&e.deleteRenderbuffer(r.__webglColorRenderbuffer),r.__webglDepthRenderbuffer&&e.deleteRenderbuffer(r.__webglDepthRenderbuffer);if(t.isWebGLMultipleRenderTargets)for(let t=0,r=n.length;t0&&r.__version!==e.version){const n=e.image;if(void 0===n)console.warn("THREE.WebGLRenderer: Texture marked for update but image is undefined");else{if(!1!==n.complete)return void P(r,e,t);console.warn("THREE.WebGLRenderer: Texture marked for update but image is incomplete")}}n.activeTexture(33984+t),n.bindTexture(3553,r.__webglTexture)}function S(t,r){const a=i.get(t);t.version>0&&a.__version!==t.version?function(t,i,r){if(6!==i.image.length)return;R(t,i),n.activeTexture(33984+r),n.bindTexture(34067,t.__webglTexture),e.pixelStorei(37440,i.flipY),e.pixelStorei(37441,i.premultiplyAlpha),e.pixelStorei(3317,i.unpackAlignment),e.pixelStorei(37443,0);const a=i&&(i.isCompressedTexture||i.image[0].isCompressedTexture),l=i.image[0]&&i.image[0].isDataTexture,h=[];for(let e=0;e<6;e++)h[e]=a||l?l?i.image[e].image:i.image[e]:g(i.image[e],!1,!0,c);const u=h[0],d=v(u)||o,p=s.convert(i.format),f=s.convert(i.type),m=x(i.internalFormat,p,f);let b;if(C(34067,i,d),a){for(let e=0;e<6;e++){b=h[e].mipmaps;for(let t=0;t1||i.get(s).__currentAnisotropy)&&(e.texParameterf(n,a.TEXTURE_MAX_ANISOTROPY_EXT,Math.min(s.anisotropy,r.getMaxAnisotropy())),i.get(s).__currentAnisotropy=s.anisotropy)}}function R(t,n){void 0===t.__webglInit&&(t.__webglInit=!0,n.addEventListener("dispose",w),t.__webglTexture=e.createTexture(),a.memory.textures++)}function P(t,i,r){let a=3553;i.isDataTexture2DArray&&(a=35866),i.isDataTexture3D&&(a=32879),R(t,i),n.activeTexture(33984+r),n.bindTexture(a,t.__webglTexture),e.pixelStorei(37440,i.flipY),e.pixelStorei(37441,i.premultiplyAlpha),e.pixelStorei(3317,i.unpackAlignment),e.pixelStorei(37443,0);const l=function(e){return!o&&(e.wrapS!==de||e.wrapT!==de||e.minFilter!==fe&&e.minFilter!==_e)}(i)&&!1===v(i.image),c=g(i.image,l,!1,h),u=v(c)||o,d=s.convert(i.format);let p,f=s.convert(i.type),m=x(i.internalFormat,d,f);C(a,i,u);const b=i.mipmaps;if(i.isDepthTexture)m=6402,o?m=i.type===Re?36012:i.type===Ce?33190:i.type===De?35056:33189:i.type===Re&&console.error("WebGLRenderer: Floating point depth texture requires WebGL2."),i.format===Ge&&6402===m&&i.type!==Ae&&i.type!==Ce&&(console.warn("THREE.WebGLRenderer: Use UnsignedShortType or UnsignedIntType for DepthFormat DepthTexture."),i.type=Ae,f=s.convert(i.type)),i.format===Ve&&6402===m&&(m=34041,i.type!==De&&(console.warn("THREE.WebGLRenderer: Use UnsignedInt248Type for DepthStencilFormat DepthTexture."),i.type=De,f=s.convert(i.type))),n.texImage2D(3553,0,m,c.width,c.height,0,d,f,null);else if(i.isDataTexture)if(b.length>0&&u){for(let e=0,t=b.length;e0&&u){for(let e=0,t=b.length;e=l&&console.warn("THREE.WebGLTextures: Trying to use "+e+" texture units while this GPU supports only "+l),T+=1,e},this.resetTextureUnits=function(){T=0},this.setTexture2D=E,this.setTexture2DArray=function(e,t){const r=i.get(e);e.version>0&&r.__version!==e.version?P(r,e,t):(n.activeTexture(33984+t),n.bindTexture(35866,r.__webglTexture))},this.setTexture3D=function(e,t){const r=i.get(e);e.version>0&&r.__version!==e.version?P(r,e,t):(n.activeTexture(33984+t),n.bindTexture(32879,r.__webglTexture))},this.setTextureCube=S,this.setupRenderTarget=function(t){const l=t.texture,c=i.get(t),h=i.get(l);t.addEventListener("dispose",M),!0!==t.isWebGLMultipleRenderTargets&&(h.__webglTexture=e.createTexture(),h.__version=l.version,a.memory.textures++);const u=!0===t.isWebGLCubeRenderTarget,d=!0===t.isWebGLMultipleRenderTargets,p=!0===t.isWebGLMultisampleRenderTarget,f=l.isDataTexture3D||l.isDataTexture2DArray,m=v(t)||o;if(!o||l.format!==Be||l.type!==Re&&l.type!==Pe||(l.format=Fe,console.warn("THREE.WebGLRenderer: Rendering to textures with RGB format is not supported. Using RGBA format instead.")),u){c.__webglFramebuffer=[];for(let t=0;t<6;t++)c.__webglFramebuffer[t]=e.createFramebuffer()}else if(c.__webglFramebuffer=e.createFramebuffer(),d)if(r.drawBuffers){const n=t.texture;for(let t=0,r=n.length;to+c?(l.inputState.pinching=!1,this.dispatchEvent({type:"pinchend",handedness:e.handedness,target:this})):!l.inputState.pinching&&a<=o-c&&(l.inputState.pinching=!0,this.dispatchEvent({type:"pinchstart",handedness:e.handedness,target:this}))}else null!==o&&e.gripSpace&&(r=t.getPose(e.gripSpace,n),null!==r&&(o.matrix.fromArray(r.transform.matrix),o.matrix.decompose(o.position,o.rotation,o.scale),r.linearVelocity?(o.hasLinearVelocity=!0,o.linearVelocity.copy(r.linearVelocity)):o.hasLinearVelocity=!1,r.angularVelocity?(o.hasAngularVelocity=!0,o.angularVelocity.copy(r.angularVelocity)):o.hasAngularVelocity=!1));return null!==a&&(a.visible=null!==i),null!==o&&(o.visible=null!==r),null!==l&&(l.visible=null!==s),this}}class xl extends On{constructor(e,t){super();const n=this,i=e.state;let r=null,s=1,a=null,o="local-floor",l=null,c=null,h=null,u=null,d=null,p=!1,f=null,m=null,g=null,v=null,y=null,_=null;const x=[],b=new Map,w=new Ss;w.layers.enable(1),w.viewport=new ni;const M=new Ss;M.layers.enable(2),M.viewport=new ni;const T=[w,M],E=new gl;E.layers.enable(1),E.layers.enable(2);let S=null,A=null;function L(e){const t=b.get(e.inputSource);t&&t.dispatchEvent({type:e.type,data:e.inputSource})}function C(){b.forEach((function(e,t){e.disconnect(t)})),b.clear(),S=null,A=null,i.bindXRFramebuffer(null),e.setRenderTarget(e.getRenderTarget()),h&&t.deleteFramebuffer(h),f&&t.deleteFramebuffer(f),m&&t.deleteRenderbuffer(m),g&&t.deleteRenderbuffer(g),h=null,f=null,m=null,g=null,d=null,u=null,c=null,r=null,D.stop(),n.isPresenting=!1,n.dispatchEvent({type:"sessionend"})}function R(e){const t=r.inputSources;for(let e=0;e0&&(t.alphaTest.value=n.alphaTest);const i=e.get(n).envMap;if(i){t.envMap.value=i,t.flipEnvMap.value=i.isCubeTexture&&!1===i.isRenderTargetTexture?-1:1,t.reflectivity.value=n.reflectivity,t.ior.value=n.ior,t.refractionRatio.value=n.refractionRatio;const r=e.get(i).__maxMipLevel;void 0!==r&&(t.maxMipLevel.value=r)}let r,s;n.lightMap&&(t.lightMap.value=n.lightMap,t.lightMapIntensity.value=n.lightMapIntensity),n.aoMap&&(t.aoMap.value=n.aoMap,t.aoMapIntensity.value=n.aoMapIntensity),n.map?r=n.map:n.specularMap?r=n.specularMap:n.displacementMap?r=n.displacementMap:n.normalMap?r=n.normalMap:n.bumpMap?r=n.bumpMap:n.roughnessMap?r=n.roughnessMap:n.metalnessMap?r=n.metalnessMap:n.alphaMap?r=n.alphaMap:n.emissiveMap?r=n.emissiveMap:n.clearcoatMap?r=n.clearcoatMap:n.clearcoatNormalMap?r=n.clearcoatNormalMap:n.clearcoatRoughnessMap?r=n.clearcoatRoughnessMap:n.specularIntensityMap?r=n.specularIntensityMap:n.specularTintMap?r=n.specularTintMap:n.transmissionMap?r=n.transmissionMap:n.thicknessMap&&(r=n.thicknessMap),void 0!==r&&(r.isWebGLRenderTarget&&(r=r.texture),!0===r.matrixAutoUpdate&&r.updateMatrix(),t.uvTransform.value.copy(r.matrix)),n.aoMap?s=n.aoMap:n.lightMap&&(s=n.lightMap),void 0!==s&&(s.isWebGLRenderTarget&&(s=s.texture),!0===s.matrixAutoUpdate&&s.updateMatrix(),t.uv2Transform.value.copy(s.matrix))}function n(t,n){t.roughness.value=n.roughness,t.metalness.value=n.metalness,n.roughnessMap&&(t.roughnessMap.value=n.roughnessMap),n.metalnessMap&&(t.metalnessMap.value=n.metalnessMap),n.emissiveMap&&(t.emissiveMap.value=n.emissiveMap),n.bumpMap&&(t.bumpMap.value=n.bumpMap,t.bumpScale.value=n.bumpScale,n.side===m&&(t.bumpScale.value*=-1)),n.normalMap&&(t.normalMap.value=n.normalMap,t.normalScale.value.copy(n.normalScale),n.side===m&&t.normalScale.value.negate()),n.displacementMap&&(t.displacementMap.value=n.displacementMap,t.displacementScale.value=n.displacementScale,t.displacementBias.value=n.displacementBias),e.get(n).envMap&&(t.envMapIntensity.value=n.envMapIntensity)}return{refreshFogUniforms:function(e,t){e.fogColor.value.copy(t.color),t.isFog?(e.fogNear.value=t.near,e.fogFar.value=t.far):t.isFogExp2&&(e.fogDensity.value=t.density)},refreshMaterialUniforms:function(e,i,r,s,a){i.isMeshBasicMaterial?t(e,i):i.isMeshLambertMaterial?(t(e,i),function(e,t){t.emissiveMap&&(e.emissiveMap.value=t.emissiveMap)}(e,i)):i.isMeshToonMaterial?(t(e,i),function(e,t){t.gradientMap&&(e.gradientMap.value=t.gradientMap),t.emissiveMap&&(e.emissiveMap.value=t.emissiveMap),t.bumpMap&&(e.bumpMap.value=t.bumpMap,e.bumpScale.value=t.bumpScale,t.side===m&&(e.bumpScale.value*=-1)),t.normalMap&&(e.normalMap.value=t.normalMap,e.normalScale.value.copy(t.normalScale),t.side===m&&e.normalScale.value.negate()),t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias)}(e,i)):i.isMeshPhongMaterial?(t(e,i),function(e,t){e.specular.value.copy(t.specular),e.shininess.value=Math.max(t.shininess,1e-4),t.emissiveMap&&(e.emissiveMap.value=t.emissiveMap),t.bumpMap&&(e.bumpMap.value=t.bumpMap,e.bumpScale.value=t.bumpScale,t.side===m&&(e.bumpScale.value*=-1)),t.normalMap&&(e.normalMap.value=t.normalMap,e.normalScale.value.copy(t.normalScale),t.side===m&&e.normalScale.value.negate()),t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias)}(e,i)):i.isMeshStandardMaterial?(t(e,i),i.isMeshPhysicalMaterial?function(e,t,i){n(e,t),e.ior.value=t.ior,t.sheenTint&&e.sheenTint.value.copy(t.sheenTint),t.clearcoat>0&&(e.clearcoat.value=t.clearcoat,e.clearcoatRoughness.value=t.clearcoatRoughness,t.clearcoatMap&&(e.clearcoatMap.value=t.clearcoatMap),t.clearcoatRoughnessMap&&(e.clearcoatRoughnessMap.value=t.clearcoatRoughnessMap),t.clearcoatNormalMap&&(e.clearcoatNormalScale.value.copy(t.clearcoatNormalScale),e.clearcoatNormalMap.value=t.clearcoatNormalMap,t.side===m&&e.clearcoatNormalScale.value.negate())),t.transmission>0&&(e.transmission.value=t.transmission,e.transmissionSamplerMap.value=i.texture,e.transmissionSamplerSize.value.set(i.width,i.height),t.transmissionMap&&(e.transmissionMap.value=t.transmissionMap),e.thickness.value=t.thickness,t.thicknessMap&&(e.thicknessMap.value=t.thicknessMap),e.attenuationDistance.value=t.attenuationDistance,e.attenuationTint.value.copy(t.attenuationTint)),e.specularIntensity.value=t.specularIntensity,e.specularTint.value.copy(t.specularTint),t.specularIntensityMap&&(e.specularIntensityMap.value=t.specularIntensityMap),t.specularTintMap&&(e.specularTintMap.value=t.specularTintMap)}(e,i,a):n(e,i)):i.isMeshMatcapMaterial?(t(e,i),function(e,t){t.matcap&&(e.matcap.value=t.matcap),t.bumpMap&&(e.bumpMap.value=t.bumpMap,e.bumpScale.value=t.bumpScale,t.side===m&&(e.bumpScale.value*=-1)),t.normalMap&&(e.normalMap.value=t.normalMap,e.normalScale.value.copy(t.normalScale),t.side===m&&e.normalScale.value.negate()),t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias)}(e,i)):i.isMeshDepthMaterial?(t(e,i),function(e,t){t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias)}(e,i)):i.isMeshDistanceMaterial?(t(e,i),function(e,t){t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias),e.referencePosition.value.copy(t.referencePosition),e.nearDistance.value=t.nearDistance,e.farDistance.value=t.farDistance}(e,i)):i.isMeshNormalMaterial?(t(e,i),function(e,t){t.bumpMap&&(e.bumpMap.value=t.bumpMap,e.bumpScale.value=t.bumpScale,t.side===m&&(e.bumpScale.value*=-1)),t.normalMap&&(e.normalMap.value=t.normalMap,e.normalScale.value.copy(t.normalScale),t.side===m&&e.normalScale.value.negate()),t.displacementMap&&(e.displacementMap.value=t.displacementMap,e.displacementScale.value=t.displacementScale,e.displacementBias.value=t.displacementBias)}(e,i)):i.isLineBasicMaterial?(function(e,t){e.diffuse.value.copy(t.color),e.opacity.value=t.opacity}(e,i),i.isLineDashedMaterial&&function(e,t){e.dashSize.value=t.dashSize,e.totalSize.value=t.dashSize+t.gapSize,e.scale.value=t.scale}(e,i)):i.isPointsMaterial?function(e,t,n,i){let r;e.diffuse.value.copy(t.color),e.opacity.value=t.opacity,e.size.value=t.size*n,e.scale.value=.5*i,t.map&&(e.map.value=t.map),t.alphaMap&&(e.alphaMap.value=t.alphaMap),t.alphaTest>0&&(e.alphaTest.value=t.alphaTest),t.map?r=t.map:t.alphaMap&&(r=t.alphaMap),void 0!==r&&(!0===r.matrixAutoUpdate&&r.updateMatrix(),e.uvTransform.value.copy(r.matrix))}(e,i,r,s):i.isSpriteMaterial?function(e,t){let n;e.diffuse.value.copy(t.color),e.opacity.value=t.opacity,e.rotation.value=t.rotation,t.map&&(e.map.value=t.map),t.alphaMap&&(e.alphaMap.value=t.alphaMap),t.alphaTest>0&&(e.alphaTest.value=t.alphaTest),t.map?n=t.map:t.alphaMap&&(n=t.alphaMap),void 0!==n&&(!0===n.matrixAutoUpdate&&n.updateMatrix(),e.uvTransform.value.copy(n.matrix))}(e,i):i.isShadowMaterial?(e.color.value.copy(i.color),e.opacity.value=i.opacity):i.isShaderMaterial&&(i.uniformsNeedUpdate=!1)}}}function wl(e={}){const t=void 0!==e.canvas?e.canvas:function(){const e=document.createElementNS("http://www.w3.org/1999/xhtml","canvas");return e.style.display="block",e}(),n=void 0!==e.context?e.context:null,i=void 0!==e.alpha&&e.alpha,r=void 0===e.depth||e.depth,s=void 0===e.stencil||e.stencil,a=void 0!==e.antialias&&e.antialias,o=void 0===e.premultipliedAlpha||e.premultipliedAlpha,l=void 0!==e.preserveDrawingBuffer&&e.preserveDrawingBuffer,c=void 0!==e.powerPreference?e.powerPreference:"default",h=void 0!==e.failIfMajorPerformanceCaveat&&e.failIfMajorPerformanceCaveat;let u=null,d=null;const p=[],v=[];this.domElement=t,this.debug={checkShaderErrors:!0},this.autoClear=!0,this.autoClearColor=!0,this.autoClearDepth=!0,this.autoClearStencil=!0,this.sortObjects=!0,this.clippingPlanes=[],this.localClippingEnabled=!1,this.gammaFactor=2,this.outputEncoding=Zt,this.physicallyCorrectLights=!1,this.toneMapping=Q,this.toneMappingExposure=1;const y=this;let _=!1,x=0,b=0,w=null,M=-1,T=null;const E=new ni,S=new ni;let A=null,L=t.width,C=t.height,R=1,P=null,k=null;const N=new ni(0,0,L,C),I=new ni(0,0,L,C);let D=!1;const O=[],B=new Bs;let F=!1,U=!1,z=null;const H=new Fi,G=new oi,V={background:null,fog:null,environment:null,overrideMaterial:null,isScene:!0};function W(){return null===w?R:1}let j,q,X,Y,J,Z,K,$,ee,te,ne,ie,re,se,ae,oe,le,ce,he,ue,pe,me,ge,ve=n;function ye(e,n){for(let i=0;i0&&function(e,t,n){if(null===z){const e=!0===a&&!0===q.isWebGL2;z=new(e?si:ii)(1024,1024,{generateMipmaps:!0,type:null!==me.convert(Pe)?Pe:Te,minFilter:we,magFilter:fe,wrapS:de,wrapT:de})}const i=y.getRenderTarget();y.setRenderTarget(z),y.clear();const r=y.toneMapping;y.toneMapping=Q,Ie(e,t,n),y.toneMapping=r,Z.updateMultisampleRenderTarget(z),Z.updateRenderTargetMipmap(z),y.setRenderTarget(i)}(r,t,n),i&&X.viewport(E.copy(i)),r.length>0&&Ie(r,t,n),s.length>0&&Ie(s,t,n),o.length>0&&Ie(o,t,n)}function Ie(e,t,n){const i=!0===t.isScene?t.overrideMaterial:null;for(let r=0,s=e.length;r0?v[v.length-1]:null,p.pop(),u=p.length>0?p[p.length-1]:null},this.getActiveCubeFace=function(){return x},this.getActiveMipmapLevel=function(){return b},this.getRenderTarget=function(){return w},this.setRenderTarget=function(e,t=0,n=0){w=e,x=t,b=n,e&&void 0===J.get(e).__webglFramebuffer&&Z.setupRenderTarget(e);let i=null,r=!1,s=!1;if(e){const n=e.texture;(n.isDataTexture3D||n.isDataTexture2DArray)&&(s=!0);const a=J.get(e).__webglFramebuffer;e.isWebGLCubeRenderTarget?(i=a[t],r=!0):i=e.isWebGLMultisampleRenderTarget?J.get(e).__webglMultisampledFramebuffer:a,E.copy(e.viewport),S.copy(e.scissor),A=e.scissorTest}else E.copy(N).multiplyScalar(R).floor(),S.copy(I).multiplyScalar(R).floor(),A=D;if(X.bindFramebuffer(36160,i)&&q.drawBuffers){let t=!1;if(e)if(e.isWebGLMultipleRenderTargets){const n=e.texture;if(O.length!==n.length||36064!==O[0]){for(let e=0,t=n.length;e=0&&t<=e.width-i&&n>=0&&n<=e.height-r&&ve.readPixels(t,n,i,r,me.convert(o),me.convert(l),s):console.error("THREE.WebGLRenderer.readRenderTargetPixels: readPixels from renderTarget failed. Framebuffer not complete.")}finally{const e=null!==w?J.get(w).__webglFramebuffer:null;X.bindFramebuffer(36160,e)}}},this.copyFramebufferToTexture=function(e,t,n=0){const i=Math.pow(2,-n),r=Math.floor(t.image.width*i),s=Math.floor(t.image.height*i);let a=me.convert(t.format);q.isWebGL2&&(6407===a&&(a=32849),6408===a&&(a=32856)),Z.setTexture2D(t,0),ve.copyTexImage2D(3553,n,a,e.x,e.y,r,s,0),X.unbindTexture()},this.copyTextureToTexture=function(e,t,n,i=0){const r=t.image.width,s=t.image.height,a=me.convert(n.format),o=me.convert(n.type);Z.setTexture2D(n,0),ve.pixelStorei(37440,n.flipY),ve.pixelStorei(37441,n.premultiplyAlpha),ve.pixelStorei(3317,n.unpackAlignment),t.isDataTexture?ve.texSubImage2D(3553,i,e.x,e.y,r,s,a,o,t.image.data):t.isCompressedTexture?ve.compressedTexSubImage2D(3553,i,e.x,e.y,t.mipmaps[0].width,t.mipmaps[0].height,a,t.mipmaps[0].data):ve.texSubImage2D(3553,i,e.x,e.y,a,o,t.image),0===i&&n.generateMipmaps&&ve.generateMipmap(3553),X.unbindTexture()},this.copyTextureToTexture3D=function(e,t,n,i,r=0){if(y.isWebGL1Renderer)return void console.warn("THREE.WebGLRenderer.copyTextureToTexture3D: can only be used with WebGL2.");const s=e.max.x-e.min.x+1,a=e.max.y-e.min.y+1,o=e.max.z-e.min.z+1,l=me.convert(i.format),c=me.convert(i.type);let h;if(i.isDataTexture3D)Z.setTexture3D(i,0),h=32879;else{if(!i.isDataTexture2DArray)return void console.warn("THREE.WebGLRenderer.copyTextureToTexture3D: only supports THREE.DataTexture3D and THREE.DataTexture2DArray.");Z.setTexture2DArray(i,0),h=35866}ve.pixelStorei(37440,i.flipY),ve.pixelStorei(37441,i.premultiplyAlpha),ve.pixelStorei(3317,i.unpackAlignment);const u=ve.getParameter(3314),d=ve.getParameter(32878),p=ve.getParameter(3316),f=ve.getParameter(3315),m=ve.getParameter(32877),g=n.isCompressedTexture?n.mipmaps[0]:n.image;ve.pixelStorei(3314,g.width),ve.pixelStorei(32878,g.height),ve.pixelStorei(3316,e.min.x),ve.pixelStorei(3315,e.min.y),ve.pixelStorei(32877,e.min.z),n.isDataTexture||n.isDataTexture3D?ve.texSubImage3D(h,r,t.x,t.y,t.z,s,a,o,l,c,g.data):n.isCompressedTexture?(console.warn("THREE.WebGLRenderer.copyTextureToTexture3D: untested support for compressed srcTexture."),ve.compressedTexSubImage3D(h,r,t.x,t.y,t.z,s,a,o,l,g.data)):ve.texSubImage3D(h,r,t.x,t.y,t.z,s,a,o,l,c,g),ve.pixelStorei(3314,u),ve.pixelStorei(32878,d),ve.pixelStorei(3316,p),ve.pixelStorei(3315,f),ve.pixelStorei(32877,m),0===r&&i.generateMipmaps&&ve.generateMipmap(h),X.unbindTexture()},this.initTexture=function(e){Z.setTexture2D(e,0),X.unbindTexture()},this.resetState=function(){x=0,b=0,w=null,X.reset(),ge.reset()},"undefined"!=typeof __THREE_DEVTOOLS__&&__THREE_DEVTOOLS__.dispatchEvent(new CustomEvent("observe",{detail:this}))}class Ml extends wl{}Ml.prototype.isWebGL1Renderer=!0;class Tl{constructor(e,t=25e-5){this.name="",this.color=new Cr(e),this.density=t}clone(){return new Tl(this.color,this.density)}toJSON(){return{type:"FogExp2",color:this.color.getHex(),density:this.density}}}Tl.prototype.isFogExp2=!0;class El{constructor(e,t=1,n=1e3){this.name="",this.color=new Cr(e),this.near=t,this.far=n}clone(){return new El(this.color,this.near,this.far)}toJSON(){return{type:"Fog",color:this.color.getHex(),near:this.near,far:this.far}}}El.prototype.isFog=!0;class Sl extends cr{constructor(){super(),this.type="Scene",this.background=null,this.environment=null,this.fog=null,this.overrideMaterial=null,this.autoUpdate=!0,"undefined"!=typeof __THREE_DEVTOOLS__&&__THREE_DEVTOOLS__.dispatchEvent(new CustomEvent("observe",{detail:this}))}copy(e,t){return super.copy(e,t),null!==e.background&&(this.background=e.background.clone()),null!==e.environment&&(this.environment=e.environment.clone()),null!==e.fog&&(this.fog=e.fog.clone()),null!==e.overrideMaterial&&(this.overrideMaterial=e.overrideMaterial.clone()),this.autoUpdate=e.autoUpdate,this.matrixAutoUpdate=e.matrixAutoUpdate,this}toJSON(e){const t=super.toJSON(e);return null!==this.fog&&(t.object.fog=this.fog.toJSON()),t}}Sl.prototype.isScene=!0;class Al{constructor(e,t){this.array=e,this.stride=t,this.count=void 0!==e?e.length/t:0,this.usage=En,this.updateRange={offset:0,count:-1},this.version=0,this.uuid=Hn()}onUploadCallback(){}set needsUpdate(e){!0===e&&this.version++}setUsage(e){return this.usage=e,this}copy(e){return this.array=new e.array.constructor(e.array),this.count=e.count,this.stride=e.stride,this.usage=e.usage,this}copyAt(e,t,n){e*=this.stride,n*=t.stride;for(let i=0,r=this.stride;ie.far||t.push({distance:o,point:kl.clone(),uv:xr.getUV(kl,Fl,Ul,zl,Hl,Gl,Vl,new Jn),face:null,object:this})}copy(e){return super.copy(e),void 0!==e.center&&this.center.copy(e.center),this.material=e.material,this}}function jl(e,t,n,i,r,s){Dl.subVectors(e,n).addScalar(.5).multiply(i),void 0!==r?(Ol.x=s*Dl.x-r*Dl.y,Ol.y=r*Dl.x+s*Dl.y):Ol.copy(Dl),e.copy(t),e.x+=Ol.x,e.y+=Ol.y,e.applyMatrix4(Bl)}Wl.prototype.isSprite=!0;const ql=new oi,Xl=new oi;class Yl extends cr{constructor(){super(),this._currentLevel=0,this.type="LOD",Object.defineProperties(this,{levels:{enumerable:!0,value:[]},isLOD:{value:!0}}),this.autoUpdate=!0}copy(e){super.copy(e,!1);const t=e.levels;for(let e=0,n=t.length;e0){let n,i;for(n=1,i=t.length;n0){ql.setFromMatrixPosition(this.matrixWorld);const n=e.ray.origin.distanceTo(ql);this.getObjectForDistance(n).raycast(e,t)}}update(e){const t=this.levels;if(t.length>1){ql.setFromMatrixPosition(e.matrixWorld),Xl.setFromMatrixPosition(this.matrixWorld);const n=ql.distanceTo(Xl)/e.zoom;let i,r;for(t[0].object.visible=!0,i=1,r=t.length;i=t[i].distance;i++)t[i-1].object.visible=!1,t[i].object.visible=!0;for(this._currentLevel=i-1;io)continue;u.applyMatrix4(this.matrixWorld);const d=e.ray.origin.distanceTo(u);de.far||t.push({distance:d,point:h.clone().applyMatrix4(this.matrixWorld),index:n,face:null,faceIndex:null,object:this})}else for(let n=Math.max(0,s.start),i=Math.min(r.count,s.start+s.count)-1;no)continue;u.applyMatrix4(this.matrixWorld);const i=e.ray.origin.distanceTo(u);ie.far||t.push({distance:i,point:h.clone().applyMatrix4(this.matrixWorld),index:n,face:null,faceIndex:null,object:this})}}else n.isGeometry&&console.error("THREE.Line.raycast() no longer supports THREE.Geometry. Use THREE.BufferGeometry instead.")}updateMorphTargets(){const e=this.geometry;if(e.isBufferGeometry){const t=e.morphAttributes,n=Object.keys(t);if(n.length>0){const e=t[n[0]];if(void 0!==e){this.morphTargetInfluences=[],this.morphTargetDictionary={};for(let t=0,n=e.length;t0&&console.error("THREE.Line.updateMorphTargets() does not support THREE.Geometry. Use THREE.BufferGeometry instead.")}}}yc.prototype.isLine=!0;const _c=new oi,xc=new oi;class bc extends yc{constructor(e,t){super(e,t),this.type="LineSegments"}computeLineDistances(){const e=this.geometry;if(e.isBufferGeometry)if(null===e.index){const t=e.attributes.position,n=[];for(let e=0,i=t.count;e0){const e=t[n[0]];if(void 0!==e){this.morphTargetInfluences=[],this.morphTargetDictionary={};for(let t=0,n=e.length;t0&&console.error("THREE.Points.updateMorphTargets() does not support THREE.Geometry. Use THREE.BufferGeometry instead.")}}}function Cc(e,t,n,i,r,s,a){const o=Ec.distanceSqToPoint(e);if(or.far)return;s.push({distance:l,distanceToRay:Math.sqrt(o),point:n,index:t,face:null,object:a})}}Lc.prototype.isPoints=!0;class Rc extends ei{constructor(e,t,n,i,r,s,a,o,l){super(e,t,n,i,r,s,a,o,l),this.format=void 0!==a?a:Be,this.minFilter=void 0!==s?s:_e,this.magFilter=void 0!==r?r:_e,this.generateMipmaps=!1;const c=this;"requestVideoFrameCallback"in e&&e.requestVideoFrameCallback((function t(){c.needsUpdate=!0,e.requestVideoFrameCallback(t)}))}clone(){return new this.constructor(this.image).copy(this)}update(){const e=this.image;!1=="requestVideoFrameCallback"in e&&e.readyState>=e.HAVE_CURRENT_DATA&&(this.needsUpdate=!0)}}Rc.prototype.isVideoTexture=!0;class Pc extends ei{constructor(e,t,n,i,r,s,a,o,l,c,h,u){super(null,s,a,o,l,c,i,r,h,u),this.image={width:t,height:n},this.mipmaps=e,this.flipY=!1,this.generateMipmaps=!1}}Pc.prototype.isCompressedTexture=!0;class kc extends ei{constructor(e,t,n,i,r,s,a,o,l){super(e,t,n,i,r,s,a,o,l),this.needsUpdate=!0}}kc.prototype.isCanvasTexture=!0;class Nc extends ei{constructor(e,t,n,i,r,s,a,o,l,c){if((c=void 0!==c?c:Ge)!==Ge&&c!==Ve)throw new Error("DepthTexture format must be either THREE.DepthFormat or THREE.DepthStencilFormat");void 0===n&&c===Ge&&(n=Ae),void 0===n&&c===Ve&&(n=De),super(null,i,r,s,a,o,c,n,l),this.image={width:e,height:t},this.magFilter=void 0!==a?a:fe,this.minFilter=void 0!==o?o:fe,this.flipY=!1,this.generateMipmaps=!1}}Nc.prototype.isDepthTexture=!0;class Ic extends es{constructor(e=1,t=8,n=0,i=2*Math.PI){super(),this.type="CircleGeometry",this.parameters={radius:e,segments:t,thetaStart:n,thetaLength:i},t=Math.max(3,t);const r=[],s=[],a=[],o=[],l=new oi,c=new Jn;s.push(0,0,0),a.push(0,0,1),o.push(.5,.5);for(let r=0,h=3;r<=t;r++,h+=3){const u=n+r/t*i;l.x=e*Math.cos(u),l.y=e*Math.sin(u),s.push(l.x,l.y,l.z),a.push(0,0,1),c.x=(s[h]/e+1)/2,c.y=(s[h+1]/e+1)/2,o.push(c.x,c.y)}for(let e=1;e<=t;e++)r.push(e,e+1,0);this.setIndex(r),this.setAttribute("position",new Gr(s,3)),this.setAttribute("normal",new Gr(a,3)),this.setAttribute("uv",new Gr(o,2))}static fromJSON(e){return new Ic(e.radius,e.segments,e.thetaStart,e.thetaLength)}}class Dc extends es{constructor(e=1,t=1,n=1,i=8,r=1,s=!1,a=0,o=2*Math.PI){super(),this.type="CylinderGeometry",this.parameters={radiusTop:e,radiusBottom:t,height:n,radialSegments:i,heightSegments:r,openEnded:s,thetaStart:a,thetaLength:o};const l=this;i=Math.floor(i),r=Math.floor(r);const c=[],h=[],u=[],d=[];let p=0;const f=[],m=n/2;let g=0;function v(n){const r=p,s=new Jn,f=new oi;let v=0;const y=!0===n?e:t,_=!0===n?1:-1;for(let e=1;e<=i;e++)h.push(0,m*_,0),u.push(0,_,0),d.push(.5,.5),p++;const x=p;for(let e=0;e<=i;e++){const t=e/i*o+a,n=Math.cos(t),r=Math.sin(t);f.x=y*r,f.y=m*_,f.z=y*n,h.push(f.x,f.y,f.z),u.push(0,_,0),s.x=.5*n+.5,s.y=.5*r*_+.5,d.push(s.x,s.y),p++}for(let e=0;e0&&v(!0),t>0&&v(!1)),this.setIndex(c),this.setAttribute("position",new Gr(h,3)),this.setAttribute("normal",new Gr(u,3)),this.setAttribute("uv",new Gr(d,2))}static fromJSON(e){return new Dc(e.radiusTop,e.radiusBottom,e.height,e.radialSegments,e.heightSegments,e.openEnded,e.thetaStart,e.thetaLength)}}class Oc extends Dc{constructor(e=1,t=1,n=8,i=1,r=!1,s=0,a=2*Math.PI){super(0,e,t,n,i,r,s,a),this.type="ConeGeometry",this.parameters={radius:e,height:t,radialSegments:n,heightSegments:i,openEnded:r,thetaStart:s,thetaLength:a}}static fromJSON(e){return new Oc(e.radius,e.height,e.radialSegments,e.heightSegments,e.openEnded,e.thetaStart,e.thetaLength)}}class Bc extends es{constructor(e,t,n=1,i=0){super(),this.type="PolyhedronGeometry",this.parameters={vertices:e,indices:t,radius:n,detail:i};const r=[],s=[];function a(e,t,n,i){const r=i+1,s=[];for(let i=0;i<=r;i++){s[i]=[];const a=e.clone().lerp(n,i/r),o=t.clone().lerp(n,i/r),l=r-i;for(let e=0;e<=l;e++)s[i][e]=0===e&&i===r?a:a.clone().lerp(o,e/l)}for(let e=0;e.9&&a<.1&&(t<.2&&(s[e+0]+=1),n<.2&&(s[e+2]+=1),i<.2&&(s[e+4]+=1))}}()}(),this.setAttribute("position",new Gr(r,3)),this.setAttribute("normal",new Gr(r.slice(),3)),this.setAttribute("uv",new Gr(s,2)),0===i?this.computeVertexNormals():this.normalizeNormals()}static fromJSON(e){return new Bc(e.vertices,e.indices,e.radius,e.details)}}class Fc extends Bc{constructor(e=1,t=0){const n=(1+Math.sqrt(5))/2,i=1/n;super([-1,-1,-1,-1,-1,1,-1,1,-1,-1,1,1,1,-1,-1,1,-1,1,1,1,-1,1,1,1,0,-i,-n,0,-i,n,0,i,-n,0,i,n,-i,-n,0,-i,n,0,i,-n,0,i,n,0,-n,0,-i,n,0,-i,-n,0,i,n,0,i],[3,11,7,3,7,15,3,15,13,7,19,17,7,17,6,7,6,15,17,4,8,17,8,10,17,10,6,8,0,16,8,16,2,8,2,10,0,12,1,0,1,18,0,18,16,6,10,2,6,2,13,6,13,15,2,16,18,2,18,3,2,3,13,18,1,9,18,9,11,18,11,3,4,14,12,4,12,0,4,0,8,11,9,5,11,5,19,11,19,7,19,5,14,19,14,4,19,4,17,1,12,14,1,14,5,1,5,9],e,t),this.type="DodecahedronGeometry",this.parameters={radius:e,detail:t}}static fromJSON(e){return new Fc(e.radius,e.detail)}}const Uc=new oi,zc=new oi,Hc=new oi,Gc=new xr;class Vc extends es{constructor(e,t){if(super(),this.type="EdgesGeometry",this.parameters={thresholdAngle:t},t=void 0!==t?t:1,!0===e.isGeometry)return void console.error("THREE.EdgesGeometry no longer supports THREE.Geometry. Use THREE.BufferGeometry instead.");const n=Math.pow(10,4),i=Math.cos(Un*t),r=e.getIndex(),s=e.getAttribute("position"),a=r?r.count:s.count,o=[0,0,0],l=["a","b","c"],c=new Array(3),h={},u=[];for(let e=0;e0)){l=i;break}l=i-1}if(i=l,n[i]===s)return i/(r-1);const c=n[i];return(i+(s-c)/(n[i+1]-c))/(r-1)}getTangent(e,t){const n=1e-4;let i=e-n,r=e+n;i<0&&(i=0),r>1&&(r=1);const s=this.getPoint(i),a=this.getPoint(r),o=t||(s.isVector2?new Jn:new oi);return o.copy(a).sub(s).normalize(),o}getTangentAt(e,t){const n=this.getUtoTmapping(e);return this.getTangent(n,t)}computeFrenetFrames(e,t){const n=new oi,i=[],r=[],s=[],a=new oi,o=new Fi;for(let t=0;t<=e;t++){const n=t/e;i[t]=this.getTangentAt(n,new oi),i[t].normalize()}r[0]=new oi,s[0]=new oi;let l=Number.MAX_VALUE;const c=Math.abs(i[0].x),h=Math.abs(i[0].y),u=Math.abs(i[0].z);c<=l&&(l=c,n.set(1,0,0)),h<=l&&(l=h,n.set(0,1,0)),u<=l&&n.set(0,0,1),a.crossVectors(i[0],n).normalize(),r[0].crossVectors(i[0],a),s[0].crossVectors(i[0],r[0]);for(let t=1;t<=e;t++){if(r[t]=r[t-1].clone(),s[t]=s[t-1].clone(),a.crossVectors(i[t-1],i[t]),a.length()>Number.EPSILON){a.normalize();const e=Math.acos(Gn(i[t-1].dot(i[t]),-1,1));r[t].applyMatrix4(o.makeRotationAxis(a,e))}s[t].crossVectors(i[t],r[t])}if(!0===t){let t=Math.acos(Gn(r[0].dot(r[e]),-1,1));t/=e,i[0].dot(a.crossVectors(r[0],r[e]))>0&&(t=-t);for(let n=1;n<=e;n++)r[n].applyMatrix4(o.makeRotationAxis(i[n],t*n)),s[n].crossVectors(i[n],r[n])}return{tangents:i,normals:r,binormals:s}}clone(){return(new this.constructor).copy(this)}copy(e){return this.arcLengthDivisions=e.arcLengthDivisions,this}toJSON(){const e={metadata:{version:4.5,type:"Curve",generator:"Curve.toJSON"}};return e.arcLengthDivisions=this.arcLengthDivisions,e.type=this.type,e}fromJSON(e){return this.arcLengthDivisions=e.arcLengthDivisions,this}}class jc extends Wc{constructor(e=0,t=0,n=1,i=1,r=0,s=2*Math.PI,a=!1,o=0){super(),this.type="EllipseCurve",this.aX=e,this.aY=t,this.xRadius=n,this.yRadius=i,this.aStartAngle=r,this.aEndAngle=s,this.aClockwise=a,this.aRotation=o}getPoint(e,t){const n=t||new Jn,i=2*Math.PI;let r=this.aEndAngle-this.aStartAngle;const s=Math.abs(r)i;)r-=i;r0?0:(Math.floor(Math.abs(l)/r)+1)*r:0===c&&l===r-1&&(l=r-2,c=1),this.closed||l>0?a=i[(l-1)%r]:(Yc.subVectors(i[0],i[1]).add(i[0]),a=Yc);const h=i[l%r],u=i[(l+1)%r];if(this.closed||l+2i.length-2?i.length-1:s+1],h=i[s>i.length-3?i.length-1:s+2];return n.set($c(a,o.x,l.x,c.x,h.x),$c(a,o.y,l.y,c.y,h.y)),n}copy(e){super.copy(e),this.points=[];for(let t=0,n=e.points.length;t0)for(s=t;s=t;s-=i)a=Ph(s,e[s],e[s+1],a);return a&&Eh(a,a.next)&&(kh(a),a=a.next),a}function uh(e,t){if(!e)return e;t||(t=e);let n,i=e;do{if(n=!1,i.steiner||!Eh(i,i.next)&&0!==Th(i.prev,i,i.next))i=i.next;else{if(kh(i),i=t=i.prev,i===i.next)break;n=!0}}while(n||i!==t);return t}function dh(e,t,n,i,r,s,a){if(!e)return;!a&&s&&function(e,t,n,i){let r=e;do{null===r.z&&(r.z=xh(r.x,r.y,t,n,i)),r.prevZ=r.prev,r.nextZ=r.next,r=r.next}while(r!==e);r.prevZ.nextZ=null,r.prevZ=null,function(e){let t,n,i,r,s,a,o,l,c=1;do{for(n=e,e=null,s=null,a=0;n;){for(a++,i=n,o=0,t=0;t0||l>0&&i;)0!==o&&(0===l||!i||n.z<=i.z)?(r=n,n=n.nextZ,o--):(r=i,i=i.nextZ,l--),s?s.nextZ=r:e=r,r.prevZ=s,s=r;n=i}s.nextZ=null,c*=2}while(a>1)}(r)}(e,i,r,s);let o,l,c=e;for(;e.prev!==e.next;)if(o=e.prev,l=e.next,s?fh(e,i,r,s):ph(e))t.push(o.i/n),t.push(e.i/n),t.push(l.i/n),kh(e),e=l.next,c=l.next;else if((e=l)===c){a?1===a?dh(e=mh(uh(e),t,n),t,n,i,r,s,2):2===a&&gh(e,t,n,i,r,s):dh(uh(e),t,n,i,r,s,1);break}}function ph(e){const t=e.prev,n=e,i=e.next;if(Th(t,n,i)>=0)return!1;let r=e.next.next;for(;r!==e.prev;){if(wh(t.x,t.y,n.x,n.y,i.x,i.y,r.x,r.y)&&Th(r.prev,r,r.next)>=0)return!1;r=r.next}return!0}function fh(e,t,n,i){const r=e.prev,s=e,a=e.next;if(Th(r,s,a)>=0)return!1;const o=r.xs.x?r.x>a.x?r.x:a.x:s.x>a.x?s.x:a.x,h=r.y>s.y?r.y>a.y?r.y:a.y:s.y>a.y?s.y:a.y,u=xh(o,l,t,n,i),d=xh(c,h,t,n,i);let p=e.prevZ,f=e.nextZ;for(;p&&p.z>=u&&f&&f.z<=d;){if(p!==e.prev&&p!==e.next&&wh(r.x,r.y,s.x,s.y,a.x,a.y,p.x,p.y)&&Th(p.prev,p,p.next)>=0)return!1;if(p=p.prevZ,f!==e.prev&&f!==e.next&&wh(r.x,r.y,s.x,s.y,a.x,a.y,f.x,f.y)&&Th(f.prev,f,f.next)>=0)return!1;f=f.nextZ}for(;p&&p.z>=u;){if(p!==e.prev&&p!==e.next&&wh(r.x,r.y,s.x,s.y,a.x,a.y,p.x,p.y)&&Th(p.prev,p,p.next)>=0)return!1;p=p.prevZ}for(;f&&f.z<=d;){if(f!==e.prev&&f!==e.next&&wh(r.x,r.y,s.x,s.y,a.x,a.y,f.x,f.y)&&Th(f.prev,f,f.next)>=0)return!1;f=f.nextZ}return!0}function mh(e,t,n){let i=e;do{const r=i.prev,s=i.next.next;!Eh(r,s)&&Sh(r,i,i.next,s)&&Ch(r,s)&&Ch(s,r)&&(t.push(r.i/n),t.push(i.i/n),t.push(s.i/n),kh(i),kh(i.next),i=e=s),i=i.next}while(i!==e);return uh(i)}function gh(e,t,n,i,r,s){let a=e;do{let e=a.next.next;for(;e!==a.prev;){if(a.i!==e.i&&Mh(a,e)){let o=Rh(a,e);return a=uh(a,a.next),o=uh(o,o.next),dh(a,t,n,i,r,s),void dh(o,t,n,i,r,s)}e=e.next}a=a.next}while(a!==e)}function vh(e,t){return e.x-t.x}function yh(e,t){if(t=function(e,t){let n=t;const i=e.x,r=e.y;let s,a=-1/0;do{if(r<=n.y&&r>=n.next.y&&n.next.y!==n.y){const e=n.x+(r-n.y)*(n.next.x-n.x)/(n.next.y-n.y);if(e<=i&&e>a){if(a=e,e===i){if(r===n.y)return n;if(r===n.next.y)return n.next}s=n.x=n.x&&n.x>=l&&i!==n.x&&wh(rs.x||n.x===s.x&&_h(s,n)))&&(s=n,u=h)),n=n.next}while(n!==o);return s}(e,t)){const n=Rh(t,e);uh(t,t.next),uh(n,n.next)}}function _h(e,t){return Th(e.prev,e,t.prev)<0&&Th(t.next,e,e.next)<0}function xh(e,t,n,i,r){return(e=1431655765&((e=858993459&((e=252645135&((e=16711935&((e=32767*(e-n)*r)|e<<8))|e<<4))|e<<2))|e<<1))|(t=1431655765&((t=858993459&((t=252645135&((t=16711935&((t=32767*(t-i)*r)|t<<8))|t<<4))|t<<2))|t<<1))<<1}function bh(e){let t=e,n=e;do{(t.x=0&&(e-a)*(i-o)-(n-a)*(t-o)>=0&&(n-a)*(s-o)-(r-a)*(i-o)>=0}function Mh(e,t){return e.next.i!==t.i&&e.prev.i!==t.i&&!function(e,t){let n=e;do{if(n.i!==e.i&&n.next.i!==e.i&&n.i!==t.i&&n.next.i!==t.i&&Sh(n,n.next,e,t))return!0;n=n.next}while(n!==e);return!1}(e,t)&&(Ch(e,t)&&Ch(t,e)&&function(e,t){let n=e,i=!1;const r=(e.x+t.x)/2,s=(e.y+t.y)/2;do{n.y>s!=n.next.y>s&&n.next.y!==n.y&&r<(n.next.x-n.x)*(s-n.y)/(n.next.y-n.y)+n.x&&(i=!i),n=n.next}while(n!==e);return i}(e,t)&&(Th(e.prev,e,t.prev)||Th(e,t.prev,t))||Eh(e,t)&&Th(e.prev,e,e.next)>0&&Th(t.prev,t,t.next)>0)}function Th(e,t,n){return(t.y-e.y)*(n.x-t.x)-(t.x-e.x)*(n.y-t.y)}function Eh(e,t){return e.x===t.x&&e.y===t.y}function Sh(e,t,n,i){const r=Lh(Th(e,t,n)),s=Lh(Th(e,t,i)),a=Lh(Th(n,i,e)),o=Lh(Th(n,i,t));return r!==s&&a!==o||!(0!==r||!Ah(e,n,t))||!(0!==s||!Ah(e,i,t))||!(0!==a||!Ah(n,e,i))||!(0!==o||!Ah(n,t,i))}function Ah(e,t,n){return t.x<=Math.max(e.x,n.x)&&t.x>=Math.min(e.x,n.x)&&t.y<=Math.max(e.y,n.y)&&t.y>=Math.min(e.y,n.y)}function Lh(e){return e>0?1:e<0?-1:0}function Ch(e,t){return Th(e.prev,e,e.next)<0?Th(e,t,e.next)>=0&&Th(e,e.prev,t)>=0:Th(e,t,e.prev)<0||Th(e,e.next,t)<0}function Rh(e,t){const n=new Nh(e.i,e.x,e.y),i=new Nh(t.i,t.x,t.y),r=e.next,s=t.prev;return e.next=t,t.prev=e,n.next=r,r.prev=n,i.next=n,n.prev=i,s.next=i,i.prev=s,i}function Ph(e,t,n,i){const r=new Nh(e,t,n);return i?(r.next=i.next,r.prev=i,i.next.prev=r,i.next=r):(r.prev=r,r.next=r),r}function kh(e){e.next.prev=e.prev,e.prev.next=e.next,e.prevZ&&(e.prevZ.nextZ=e.nextZ),e.nextZ&&(e.nextZ.prevZ=e.prevZ)}function Nh(e,t,n){this.i=e,this.x=t,this.y=n,this.prev=null,this.next=null,this.z=null,this.prevZ=null,this.nextZ=null,this.steiner=!1}class Ih{static area(e){const t=e.length;let n=0;for(let i=t-1,r=0;r80*n){o=c=e[0],l=h=e[1];for(let t=n;tc&&(c=u),d>h&&(h=d);p=Math.max(c-o,h-l),p=0!==p?1/p:0}return dh(s,a,n,o,l,p),a}(n,i);for(let e=0;e2&&e[t-1].equals(e[0])&&e.pop()}function Oh(e,t){for(let n=0;nNumber.EPSILON){const u=Math.sqrt(h),d=Math.sqrt(l*l+c*c),p=t.x-o/u,f=t.y+a/u,m=((n.x-c/d-p)*c-(n.y+l/d-f)*l)/(a*c-o*l);i=p+a*m-e.x,r=f+o*m-e.y;const g=i*i+r*r;if(g<=2)return new Jn(i,r);s=Math.sqrt(g/2)}else{let e=!1;a>Number.EPSILON?l>Number.EPSILON&&(e=!0):a<-Number.EPSILON?l<-Number.EPSILON&&(e=!0):Math.sign(o)===Math.sign(c)&&(e=!0),e?(i=-o,r=a,s=Math.sqrt(h)):(i=a,r=o,s=Math.sqrt(h/2))}return new Jn(i/s,r/s)}const P=[];for(let e=0,t=S.length,n=t-1,i=e+1;e=0;e--){const t=e/p,n=h*Math.cos(t*Math.PI/2),i=u*Math.sin(t*Math.PI/2)+d;for(let e=0,t=S.length;e=0;){const i=n;let r=n-1;r<0&&(r=e.length-1);for(let e=0,n=o+2*p;e=0?(e(i-o,p,h),u.subVectors(c,h)):(e(i+o,p,h),u.subVectors(h,c)),p-o>=0?(e(i,p-o,h),d.subVectors(c,h)):(e(i,p+o,h),d.subVectors(h,c)),l.crossVectors(u,d).normalize(),s.push(l.x,l.y,l.z),a.push(i,p)}}for(let e=0;e0)&&d.push(t,r,l),(e!==n-1||o0!=e>0&&this.version++,this._clearcoat=e}get transmission(){return this._transmission}set transmission(e){this._transmission>0!=e>0&&this.version++,this._transmission=e}copy(e){return super.copy(e),this.defines={STANDARD:"",PHYSICAL:""},this.clearcoat=e.clearcoat,this.clearcoatMap=e.clearcoatMap,this.clearcoatRoughness=e.clearcoatRoughness,this.clearcoatRoughnessMap=e.clearcoatRoughnessMap,this.clearcoatNormalMap=e.clearcoatNormalMap,this.clearcoatNormalScale.copy(e.clearcoatNormalScale),this.ior=e.ior,this.sheenTint.copy(e.sheenTint),this.transmission=e.transmission,this.transmissionMap=e.transmissionMap,this.thickness=e.thickness,this.thicknessMap=e.thicknessMap,this.attenuationDistance=e.attenuationDistance,this.attenuationTint.copy(e.attenuationTint),this.specularIntensity=e.specularIntensity,this.specularIntensityMap=e.specularIntensityMap,this.specularTint.copy(e.specularTint),this.specularTintMap=e.specularTintMap,this}}nu.prototype.isMeshPhysicalMaterial=!0;class iu extends wr{constructor(e){super(),this.type="MeshPhongMaterial",this.color=new Cr(16777215),this.specular=new Cr(1118481),this.shininess=30,this.map=null,this.lightMap=null,this.lightMapIntensity=1,this.aoMap=null,this.aoMapIntensity=1,this.emissive=new Cr(0),this.emissiveIntensity=1,this.emissiveMap=null,this.bumpMap=null,this.bumpScale=1,this.normalMap=null,this.normalMapType=on,this.normalScale=new Jn(1,1),this.displacementMap=null,this.displacementScale=1,this.displacementBias=0,this.specularMap=null,this.alphaMap=null,this.envMap=null,this.combine=J,this.reflectivity=1,this.refractionRatio=.98,this.wireframe=!1,this.wireframeLinewidth=1,this.wireframeLinecap="round",this.wireframeLinejoin="round",this.flatShading=!1,this.setValues(e)}copy(e){return super.copy(e),this.color.copy(e.color),this.specular.copy(e.specular),this.shininess=e.shininess,this.map=e.map,this.lightMap=e.lightMap,this.lightMapIntensity=e.lightMapIntensity,this.aoMap=e.aoMap,this.aoMapIntensity=e.aoMapIntensity,this.emissive.copy(e.emissive),this.emissiveMap=e.emissiveMap,this.emissiveIntensity=e.emissiveIntensity,this.bumpMap=e.bumpMap,this.bumpScale=e.bumpScale,this.normalMap=e.normalMap,this.normalMapType=e.normalMapType,this.normalScale.copy(e.normalScale),this.displacementMap=e.displacementMap,this.displacementScale=e.displacementScale,this.displacementBias=e.displacementBias,this.specularMap=e.specularMap,this.alphaMap=e.alphaMap,this.envMap=e.envMap,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.flatShading=e.flatShading,this}}iu.prototype.isMeshPhongMaterial=!0;class ru extends wr{constructor(e){super(),this.defines={TOON:""},this.type="MeshToonMaterial",this.color=new Cr(16777215),this.map=null,this.gradientMap=null,this.lightMap=null,this.lightMapIntensity=1,this.aoMap=null,this.aoMapIntensity=1,this.emissive=new Cr(0),this.emissiveIntensity=1,this.emissiveMap=null,this.bumpMap=null,this.bumpScale=1,this.normalMap=null,this.normalMapType=on,this.normalScale=new Jn(1,1),this.displacementMap=null,this.displacementScale=1,this.displacementBias=0,this.alphaMap=null,this.wireframe=!1,this.wireframeLinewidth=1,this.wireframeLinecap="round",this.wireframeLinejoin="round",this.setValues(e)}copy(e){return super.copy(e),this.color.copy(e.color),this.map=e.map,this.gradientMap=e.gradientMap,this.lightMap=e.lightMap,this.lightMapIntensity=e.lightMapIntensity,this.aoMap=e.aoMap,this.aoMapIntensity=e.aoMapIntensity,this.emissive.copy(e.emissive),this.emissiveMap=e.emissiveMap,this.emissiveIntensity=e.emissiveIntensity,this.bumpMap=e.bumpMap,this.bumpScale=e.bumpScale,this.normalMap=e.normalMap,this.normalMapType=e.normalMapType,this.normalScale.copy(e.normalScale),this.displacementMap=e.displacementMap,this.displacementScale=e.displacementScale,this.displacementBias=e.displacementBias,this.alphaMap=e.alphaMap,this.wireframe=e.wireframe,this.wireframeLinewidth=e.wireframeLinewidth,this.wireframeLinecap=e.wireframeLinecap,this.wireframeLinejoin=e.wireframeLinejoin,this}}ru.prototype.isMeshToonMaterial=!0;class su extends wr{constructor(e){super(),this.type="MeshNormalMaterial",this.bumpMap=null,this.bumpScale=1,this.normalMap=null,this.normalMapType=on,this.normalScale=new Jn(1,1),this.displacementMap=null,this.displacementScale=1,this.displacementBias=0,this.wireframe=!1,this.wireframeLinewidth=1,this.fog=!1,this.flatShading=!1,this.setValues(e)}copy(e){return super.copy(e),this.bumpMap=e.bumpMap,this.bumpScale=e.bumpScale,this.normalMap=e.normalMap,this.normalMapType=e.normalMapType,this.normalScale.copy(e.normalScale),this.displacementMap=e.displacementMap,this.displacementScale=e.displacementScale,this.displacementBias=e.displacementBias,this.wireframe=e.wireframe,this.wireframeLinewidth=e.wireframeLinewidth,this.flatShading=e.flatShading,this}}su.prototype.isMeshNormalMaterial=!0;class au extends wr{constructor(e){super(),this.type="MeshLambertMaterial",this.color=new Cr(16777215),this.map=null,this.lightMap=null,this.lightMapIntensity=1,this.aoMap=null,this.aoMapIntensity=1,this.emissive=new Cr(0),this.emissiveIntensity=1,this.emissiveMap=null,this.specularMap=null,this.alphaMap=null,this.envMap=null,this.combine=J,this.reflectivity=1,this.refractionRatio=.98,this.wireframe=!1,this.wireframeLinewidth=1,this.wireframeLinecap="round",this.wireframeLinejoin="round",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.emissive.copy(e.emissive),this.emissiveMap=e.emissiveMap,this.emissiveIntensity=e.emissiveIntensity,this.specularMap=e.specularMap,this.alphaMap=e.alphaMap,this.envMap=e.envMap,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}}au.prototype.isMeshLambertMaterial=!0;class ou extends wr{constructor(e){super(),this.defines={MATCAP:""},this.type="MeshMatcapMaterial",this.color=new Cr(16777215),this.matcap=null,this.map=null,this.bumpMap=null,this.bumpScale=1,this.normalMap=null,this.normalMapType=on,this.normalScale=new Jn(1,1),this.displacementMap=null,this.displacementScale=1,this.displacementBias=0,this.alphaMap=null,this.flatShading=!1,this.setValues(e)}copy(e){return super.copy(e),this.defines={MATCAP:""},this.color.copy(e.color),this.matcap=e.matcap,this.map=e.map,this.bumpMap=e.bumpMap,this.bumpScale=e.bumpScale,this.normalMap=e.normalMap,this.normalMapType=e.normalMapType,this.normalScale.copy(e.normalScale),this.displacementMap=e.displacementMap,this.displacementScale=e.displacementScale,this.displacementBias=e.displacementBias,this.alphaMap=e.alphaMap,this.flatShading=e.flatShading,this}}ou.prototype.isMeshMatcapMaterial=!0;class lu extends dc{constructor(e){super(),this.type="LineDashedMaterial",this.scale=1,this.dashSize=3,this.gapSize=1,this.setValues(e)}copy(e){return super.copy(e),this.scale=e.scale,this.dashSize=e.dashSize,this.gapSize=e.gapSize,this}}lu.prototype.isLineDashedMaterial=!0;var cu=Object.freeze({__proto__:null,ShadowMaterial:eu,SpriteMaterial:Rl,RawShaderMaterial:Ks,ShaderMaterial:Ts,PointsMaterial:Mc,MeshPhysicalMaterial:nu,MeshStandardMaterial:tu,MeshPhongMaterial:iu,MeshToonMaterial:ru,MeshNormalMaterial:su,MeshLambertMaterial:au,MeshDepthMaterial:hl,MeshDistanceMaterial:ul,MeshBasicMaterial:Rr,MeshMatcapMaterial:ou,LineDashedMaterial:lu,LineBasicMaterial:dc,Material:wr});const hu={arraySlice:function(e,t,n){return hu.isTypedArray(e)?new e.constructor(e.subarray(t,void 0!==n?n:e.length)):e.slice(t,n)},convertArray:function(e,t,n){return!e||!n&&e.constructor===t?e:"number"==typeof t.BYTES_PER_ELEMENT?new t(e):Array.prototype.slice.call(e)},isTypedArray:function(e){return ArrayBuffer.isView(e)&&!(e instanceof DataView)},getKeyframeOrder:function(e){const t=e.length,n=new Array(t);for(let e=0;e!==t;++e)n[e]=e;return n.sort((function(t,n){return e[t]-e[n]})),n},sortedArray:function(e,t,n){const i=e.length,r=new e.constructor(i);for(let s=0,a=0;a!==i;++s){const i=n[s]*t;for(let n=0;n!==t;++n)r[a++]=e[i+n]}return r},flattenJSON:function(e,t,n,i){let r=1,s=e[0];for(;void 0!==s&&void 0===s[i];)s=e[r++];if(void 0===s)return;let a=s[i];if(void 0!==a)if(Array.isArray(a))do{a=s[i],void 0!==a&&(t.push(s.time),n.push.apply(n,a)),s=e[r++]}while(void 0!==s);else if(void 0!==a.toArray)do{a=s[i],void 0!==a&&(t.push(s.time),a.toArray(n,n.length)),s=e[r++]}while(void 0!==s);else do{a=s[i],void 0!==a&&(t.push(s.time),n.push(a)),s=e[r++]}while(void 0!==s)},subclip:function(e,t,n,i,r=30){const s=e.clone();s.name=t;const a=[];for(let e=0;e=i)){l.push(t.times[e]);for(let n=0;ns.tracks[e].times[0]&&(o=s.tracks[e].times[0]);for(let e=0;e=i.times[u]){const e=u*l+o,t=e+l-o;d=hu.arraySlice(i.values,e,t)}else{const e=i.createInterpolant(),t=o,n=l-o;e.evaluate(s),d=hu.arraySlice(e.resultBuffer,t,n)}"quaternion"===r&&(new ai).fromArray(d).normalize().conjugate().toArray(d);const p=a.times.length;for(let e=0;e=r)break e;{const a=t[1];e=r)break t}s=n,n=0}}for(;n>>1;et;)--s;if(++s,0!==r||s!==i){r>=s&&(s=Math.max(s,1),r=s-1);const e=this.getValueSize();this.times=hu.arraySlice(n,r,s),this.values=hu.arraySlice(this.values,r*e,s*e)}return this}validate(){let e=!0;const t=this.getValueSize();t-Math.floor(t)!=0&&(console.error("THREE.KeyframeTrack: Invalid value size in track.",this),e=!1);const n=this.times,i=this.values,r=n.length;0===r&&(console.error("THREE.KeyframeTrack: Track is empty.",this),e=!1);let s=null;for(let t=0;t!==r;t++){const i=n[t];if("number"==typeof i&&isNaN(i)){console.error("THREE.KeyframeTrack: Time is not a valid number.",this,t,i),e=!1;break}if(null!==s&&s>i){console.error("THREE.KeyframeTrack: Out of order keys.",this,t,i,s),e=!1;break}s=i}if(void 0!==i&&hu.isTypedArray(i))for(let t=0,n=i.length;t!==n;++t){const n=i[t];if(isNaN(n)){console.error("THREE.KeyframeTrack: Value is not a valid number.",this,t,n),e=!1;break}}return e}optimize(){const e=hu.arraySlice(this.times),t=hu.arraySlice(this.values),n=this.getValueSize(),i=this.getInterpolation()===Ht,r=e.length-1;let s=1;for(let a=1;a0){e[s]=e[r];for(let e=r*n,i=s*n,a=0;a!==n;++a)t[i+a]=t[e+a];++s}return s!==e.length?(this.times=hu.arraySlice(e,0,s),this.values=hu.arraySlice(t,0,s*n)):(this.times=e,this.values=t),this}clone(){const e=hu.arraySlice(this.times,0),t=hu.arraySlice(this.values,0),n=new(0,this.constructor)(this.name,e,t);return n.createInterpolant=this.createInterpolant,n}}mu.prototype.TimeBufferType=Float32Array,mu.prototype.ValueBufferType=Float32Array,mu.prototype.DefaultInterpolation=zt;class gu extends mu{}gu.prototype.ValueTypeName="bool",gu.prototype.ValueBufferType=Array,gu.prototype.DefaultInterpolation=Ut,gu.prototype.InterpolantFactoryMethodLinear=void 0,gu.prototype.InterpolantFactoryMethodSmooth=void 0;class vu extends mu{}vu.prototype.ValueTypeName="color";class yu extends mu{}yu.prototype.ValueTypeName="number";class _u extends uu{constructor(e,t,n,i){super(e,t,n,i)}interpolate_(e,t,n,i){const r=this.resultBuffer,s=this.sampleValues,a=this.valueSize,o=(n-t)/(i-t);let l=e*a;for(let e=l+a;l!==e;l+=4)ai.slerpFlat(r,0,s,l-a,s,l,o);return r}}class xu extends mu{InterpolantFactoryMethodLinear(e){return new _u(this.times,this.values,this.getValueSize(),e)}}xu.prototype.ValueTypeName="quaternion",xu.prototype.DefaultInterpolation=zt,xu.prototype.InterpolantFactoryMethodSmooth=void 0;class bu extends mu{}bu.prototype.ValueTypeName="string",bu.prototype.ValueBufferType=Array,bu.prototype.DefaultInterpolation=Ut,bu.prototype.InterpolantFactoryMethodLinear=void 0,bu.prototype.InterpolantFactoryMethodSmooth=void 0;class wu extends mu{}wu.prototype.ValueTypeName="vector";class Mu{constructor(e,t=-1,n,i=jt){this.name=e,this.tracks=n,this.duration=t,this.blendMode=i,this.uuid=Hn(),this.duration<0&&this.resetDuration()}static parse(e){const t=[],n=e.tracks,i=1/(e.fps||1);for(let e=0,r=n.length;e!==r;++e)t.push(Tu(n[e]).scale(i));const r=new this(e.name,e.duration,t,e.blendMode);return r.uuid=e.uuid,r}static toJSON(e){const t=[],n=e.tracks,i={name:e.name,duration:e.duration,tracks:t,uuid:e.uuid,blendMode:e.blendMode};for(let e=0,i=n.length;e!==i;++e)t.push(mu.toJSON(n[e]));return i}static CreateFromMorphTargetSequence(e,t,n,i){const r=t.length,s=[];for(let e=0;e1){const e=s[1];let t=i[e];t||(i[e]=t=[]),t.push(n)}}const s=[];for(const e in i)s.push(this.CreateFromMorphTargetSequence(e,i[e],t,n));return s}static parseAnimation(e,t){if(!e)return console.error("THREE.AnimationClip: No animation in JSONLoader data."),null;const n=function(e,t,n,i,r){if(0!==n.length){const s=[],a=[];hu.flattenJSON(n,s,a,i),0!==s.length&&r.push(new e(t,s,a))}},i=[],r=e.name||"default",s=e.fps||30,a=e.blendMode;let o=e.length||-1;const l=e.hierarchy||[];for(let e=0;e0||0===e.search(/^data\\:image\\/jpeg/);r.format=i?Be:Fe,r.needsUpdate=!0,void 0!==t&&t(r)}),n,i),r}}class Bu extends Wc{constructor(){super(),this.type="CurvePath",this.curves=[],this.autoClose=!1}add(e){this.curves.push(e)}closePath(){const e=this.curves[0].getPoint(0),t=this.curves[this.curves.length-1].getPoint(1);e.equals(t)||this.curves.push(new rh(t,e))}getPoint(e){const t=e*this.getLength(),n=this.getCurveLengths();let i=0;for(;i=t){const e=n[i]-t,r=this.curves[i],s=r.getLength(),a=0===s?0:1-e/s;return r.getPointAt(a)}i++}return null}getLength(){const e=this.getCurveLengths();return e[e.length-1]}updateArcLengths(){this.needsUpdate=!0,this.cacheLengths=null,this.getCurveLengths()}getCurveLengths(){if(this.cacheLengths&&this.cacheLengths.length===this.curves.length)return this.cacheLengths;const e=[];let t=0;for(let n=0,i=this.curves.length;n1&&!t[t.length-1].equals(t[0])&&t.push(t[0]),t}copy(e){super.copy(e),this.curves=[];for(let t=0,n=e.curves.length;t0){const e=l.getPoint(0);e.equals(this.currentPoint)||this.lineTo(e.x,e.y)}this.curves.push(l);const c=l.getPoint(1);return this.currentPoint.copy(c),this}copy(e){return super.copy(e),this.currentPoint.copy(e.currentPoint),this}toJSON(){const e=super.toJSON();return e.currentPoint=this.currentPoint.toArray(),e}fromJSON(e){return super.fromJSON(e),this.currentPoint.fromArray(e.currentPoint),this}}class Uu extends Fu{constructor(e){super(e),this.uuid=Hn(),this.type="Shape",this.holes=[]}getPointsHoles(e){const t=[];for(let n=0,i=this.holes.length;n0:i.vertexColors=e.vertexColors),void 0!==e.uniforms)for(const t in e.uniforms){const r=e.uniforms[t];switch(i.uniforms[t]={},r.type){case"t":i.uniforms[t].value=n(r.value);break;case"c":i.uniforms[t].value=(new Cr).setHex(r.value);break;case"v2":i.uniforms[t].value=(new Jn).fromArray(r.value);break;case"v3":i.uniforms[t].value=(new oi).fromArray(r.value);break;case"v4":i.uniforms[t].value=(new ni).fromArray(r.value);break;case"m3":i.uniforms[t].value=(new Zn).fromArray(r.value);break;case"m4":i.uniforms[t].value=(new Fi).fromArray(r.value);break;default:i.uniforms[t].value=r.value}}if(void 0!==e.defines&&(i.defines=e.defines),void 0!==e.vertexShader&&(i.vertexShader=e.vertexShader),void 0!==e.fragmentShader&&(i.fragmentShader=e.fragmentShader),void 0!==e.extensions)for(const t in e.extensions)i.extensions[t]=e.extensions[t];if(void 0!==e.shading&&(i.flatShading=1===e.shading),void 0!==e.size&&(i.size=e.size),void 0!==e.sizeAttenuation&&(i.sizeAttenuation=e.sizeAttenuation),void 0!==e.map&&(i.map=n(e.map)),void 0!==e.matcap&&(i.matcap=n(e.matcap)),void 0!==e.alphaMap&&(i.alphaMap=n(e.alphaMap)),void 0!==e.bumpMap&&(i.bumpMap=n(e.bumpMap)),void 0!==e.bumpScale&&(i.bumpScale=e.bumpScale),void 0!==e.normalMap&&(i.normalMap=n(e.normalMap)),void 0!==e.normalMapType&&(i.normalMapType=e.normalMapType),void 0!==e.normalScale){let t=e.normalScale;!1===Array.isArray(t)&&(t=[t,t]),i.normalScale=(new Jn).fromArray(t)}return void 0!==e.displacementMap&&(i.displacementMap=n(e.displacementMap)),void 0!==e.displacementScale&&(i.displacementScale=e.displacementScale),void 0!==e.displacementBias&&(i.displacementBias=e.displacementBias),void 0!==e.roughnessMap&&(i.roughnessMap=n(e.roughnessMap)),void 0!==e.metalnessMap&&(i.metalnessMap=n(e.metalnessMap)),void 0!==e.emissiveMap&&(i.emissiveMap=n(e.emissiveMap)),void 0!==e.emissiveIntensity&&(i.emissiveIntensity=e.emissiveIntensity),void 0!==e.specularMap&&(i.specularMap=n(e.specularMap)),void 0!==e.specularIntensityMap&&(i.specularIntensityMap=n(e.specularIntensityMap)),void 0!==e.specularTintMap&&(i.specularTintMap=n(e.specularTintMap)),void 0!==e.envMap&&(i.envMap=n(e.envMap)),void 0!==e.envMapIntensity&&(i.envMapIntensity=e.envMapIntensity),void 0!==e.reflectivity&&(i.reflectivity=e.reflectivity),void 0!==e.refractionRatio&&(i.refractionRatio=e.refractionRatio),void 0!==e.lightMap&&(i.lightMap=n(e.lightMap)),void 0!==e.lightMapIntensity&&(i.lightMapIntensity=e.lightMapIntensity),void 0!==e.aoMap&&(i.aoMap=n(e.aoMap)),void 0!==e.aoMapIntensity&&(i.aoMapIntensity=e.aoMapIntensity),void 0!==e.gradientMap&&(i.gradientMap=n(e.gradientMap)),void 0!==e.clearcoatMap&&(i.clearcoatMap=n(e.clearcoatMap)),void 0!==e.clearcoatRoughnessMap&&(i.clearcoatRoughnessMap=n(e.clearcoatRoughnessMap)),void 0!==e.clearcoatNormalMap&&(i.clearcoatNormalMap=n(e.clearcoatNormalMap)),void 0!==e.clearcoatNormalScale&&(i.clearcoatNormalScale=(new Jn).fromArray(e.clearcoatNormalScale)),void 0!==e.transmissionMap&&(i.transmissionMap=n(e.transmissionMap)),void 0!==e.thicknessMap&&(i.thicknessMap=n(e.thicknessMap)),i}setTextures(e){return this.textures=e,this}}class ad{static decodeText(e){if("undefined"!=typeof TextDecoder)return(new TextDecoder).decode(e);let t="";for(let n=0,i=e.length;n0){const n=new Su(t);r=new Nu(n),r.setCrossOrigin(this.crossOrigin);for(let t=0,n=e.length;t0){i=new Nu(this.manager),i.setCrossOrigin(this.crossOrigin);for(let t=0,i=e.length;tNumber.EPSILON){if(l<0&&(n=t[s],o=-o,a=t[r],l=-l),e.ya.y)continue;if(e.y===n.y){if(e.x===n.x)return!0}else{const t=l*(e.x-n.x)-o*(e.y-n.y);if(0===t)return!0;if(t<0)continue;i=!i}}else{if(e.y!==n.y)continue;if(a.x<=e.x&&e.x<=n.x||n.x<=e.x&&e.x<=a.x)return!0}}return i}const r=Ih.isClockWise,s=this.subPaths;if(0===s.length)return[];if(!0===t)return n(s);let a,o,l;const c=[];if(1===s.length)return o=s[0],l=new Uu,l.curves=o.curves,c.push(l),c;let h=!r(s[0].getPoints());h=e?!h:h;const u=[],d=[];let p,f,m=[],g=0;d[g]=void 0,m[g]=[];for(let t=0,n=s.length;t1){let e=!1;const t=[];for(let e=0,t=d.length;e0&&(e||(m=u))}for(let e=0,t=d.length;e0){this.source.connect(this.filters[0]);for(let e=1,t=this.filters.length;e0){this.source.disconnect(this.filters[0]);for(let e=1,t=this.filters.length;e0&&this._mixBufferRegionAdditive(n,i,this._addIndex*t,1,t);for(let e=t,r=t+t;e!==r;++e)if(n[e]!==n[e+t]){a.setValue(n,i);break}}saveOriginalState(){const e=this.binding,t=this.buffer,n=this.valueSize,i=n*this._origIndex;e.getValue(t,i);for(let e=n,r=i;e!==r;++e)t[e]=t[i+e%n];this._setIdentity(),this.cumulativeWeight=0,this.cumulativeWeightAdditive=0}restoreOriginalState(){const e=3*this.valueSize;this.binding.setValue(this.buffer,e)}_setAdditiveIdentityNumeric(){const e=this._addIndex*this.valueSize,t=e+this.valueSize;for(let n=e;n=.5)for(let i=0;i!==r;++i)e[t+i]=e[n+i]}_slerp(e,t,n,i){ai.slerpFlat(e,t,e,t,e,n,i)}_slerpAdditive(e,t,n,i,r){const s=this._workIndex*r;ai.multiplyQuaternionsFlat(e,s,e,t,e,n),ai.slerpFlat(e,t,e,t,e,s,i)}_lerp(e,t,n,i,r){const s=1-i;for(let a=0;a!==r;++a){const r=t+a;e[r]=e[r]*s+e[n+a]*i}}_lerpAdditive(e,t,n,i,r){for(let s=0;s!==r;++s){const r=t+s;e[r]=e[r]+e[n+s]*i}}}const Hd=new RegExp("[\\\\[\\\\]\\\\.:\\\\/]","g"),Gd="[^\\\\[\\\\]\\\\.:\\\\/]",Vd="[^"+"\\\\[\\\\]\\\\.:\\\\/".replace("\\\\.","")+"]",Wd=/((?:WC+[\\/:])*)/.source.replace("WC",Gd),jd=/(WCOD+)?/.source.replace("WCOD",Vd),qd=/(?:\\.(WC+)(?:\\[(.+)\\])?)?/.source.replace("WC",Gd),Xd=/\\.(WC+)(?:\\[(.+)\\])?/.source.replace("WC",Gd),Yd=new RegExp("^"+Wd+jd+qd+Xd+"$"),Jd=["material","materials","bones"];class Zd{constructor(e,t,n){this.path=t,this.parsedPath=n||Zd.parseTrackName(t),this.node=Zd.findNode(e,this.parsedPath.nodeName)||e,this.rootNode=e,this.getValue=this._getValue_unbound,this.setValue=this._setValue_unbound}static create(e,t,n){return e&&e.isAnimationObjectGroup?new Zd.Composite(e,t,n):new Zd(e,t,n)}static sanitizeNodeName(e){return e.replace(/\\s/g,"_").replace(Hd,"")}static parseTrackName(e){const t=Yd.exec(e);if(!t)throw new Error("PropertyBinding: Cannot parse trackName: "+e);const n={nodeName:t[2],objectName:t[3],objectIndex:t[4],propertyName:t[5],propertyIndex:t[6]},i=n.nodeName&&n.nodeName.lastIndexOf(".");if(void 0!==i&&-1!==i){const e=n.nodeName.substring(i+1);-1!==Jd.indexOf(e)&&(n.nodeName=n.nodeName.substring(0,i),n.objectName=e)}if(null===n.propertyName||0===n.propertyName.length)throw new Error("PropertyBinding: can not parse propertyName from trackName: "+e);return n}static findNode(e,t){if(!t||""===t||"."===t||-1===t||t===e.name||t===e.uuid)return e;if(e.skeleton){const n=e.skeleton.getBoneByName(t);if(void 0!==n)return n}if(e.children){const n=function(e){for(let i=0;i=r){const s=r++,c=e[s];t[c.uuid]=l,e[l]=c,t[o]=s,e[s]=a;for(let e=0,t=i;e!==t;++e){const t=n[e],i=t[s],r=t[l];t[l]=i,t[s]=r}}}this.nCachedObjects_=r}uncache(){const e=this._objects,t=this._indicesByUUID,n=this._bindings,i=n.length;let r=this.nCachedObjects_,s=e.length;for(let a=0,o=arguments.length;a!==o;++a){const o=arguments[a].uuid,l=t[o];if(void 0!==l)if(delete t[o],l0&&(t[a.uuid]=l),e[l]=a,e.pop();for(let e=0,t=i;e!==t;++e){const t=n[e];t[l]=t[r],t.pop()}}}this.nCachedObjects_=r}subscribe_(e,t){const n=this._bindingsIndicesByPath;let i=n[e];const r=this._bindings;if(void 0!==i)return r[i];const s=this._paths,a=this._parsedPaths,o=this._objects,l=o.length,c=this.nCachedObjects_,h=new Array(l);i=r.length,n[e]=i,s.push(e),a.push(t),r.push(h);for(let n=c,i=o.length;n!==i;++n){const i=o[n];h[n]=new Zd(i,e,t)}return h}unsubscribe_(e){const t=this._bindingsIndicesByPath,n=t[e];if(void 0!==n){const i=this._paths,r=this._parsedPaths,s=this._bindings,a=s.length-1,o=s[a];t[e[a]]=n,s[n]=o,s.pop(),r[n]=r[a],r.pop(),i[n]=i[a],i.pop()}}}Kd.prototype.isAnimationObjectGroup=!0;class Qd{constructor(e,t,n=null,i=t.blendMode){this._mixer=e,this._clip=t,this._localRoot=n,this.blendMode=i;const r=t.tracks,s=r.length,a=new Array(s),o={endingStart:Gt,endingEnd:Gt};for(let e=0;e!==s;++e){const t=r[e].createInterpolant(null);a[e]=t,t.settings=o}this._interpolantSettings=o,this._interpolants=a,this._propertyBindings=new Array(s),this._cacheIndex=null,this._byClipCacheIndex=null,this._timeScaleInterpolant=null,this._weightInterpolant=null,this.loop=Bt,this._loopCount=-1,this._startTime=null,this.time=0,this.timeScale=1,this._effectiveTimeScale=1,this.weight=1,this._effectiveWeight=1,this.repetitions=1/0,this.paused=!1,this.enabled=!0,this.clampWhenFinished=!1,this.zeroSlopeAtStart=!0,this.zeroSlopeAtEnd=!0}play(){return this._mixer._activateAction(this),this}stop(){return this._mixer._deactivateAction(this),this.reset()}reset(){return this.paused=!1,this.enabled=!0,this.time=0,this._loopCount=-1,this._startTime=null,this.stopFading().stopWarping()}isRunning(){return this.enabled&&!this.paused&&0!==this.timeScale&&null===this._startTime&&this._mixer._isActiveAction(this)}isScheduled(){return this._mixer._isActiveAction(this)}startAt(e){return this._startTime=e,this}setLoop(e,t){return this.loop=e,this.repetitions=t,this}setEffectiveWeight(e){return this.weight=e,this._effectiveWeight=this.enabled?e:0,this.stopFading()}getEffectiveWeight(){return this._effectiveWeight}fadeIn(e){return this._scheduleFading(e,0,1)}fadeOut(e){return this._scheduleFading(e,1,0)}crossFadeFrom(e,t,n){if(e.fadeOut(t),this.fadeIn(t),n){const n=this._clip.duration,i=e._clip.duration,r=i/n,s=n/i;e.warp(1,r,t),this.warp(s,1,t)}return this}crossFadeTo(e,t,n){return e.crossFadeFrom(this,t,n)}stopFading(){const e=this._weightInterpolant;return null!==e&&(this._weightInterpolant=null,this._mixer._takeBackControlInterpolant(e)),this}setEffectiveTimeScale(e){return this.timeScale=e,this._effectiveTimeScale=this.paused?0:e,this.stopWarping()}getEffectiveTimeScale(){return this._effectiveTimeScale}setDuration(e){return this.timeScale=this._clip.duration/e,this.stopWarping()}syncWith(e){return this.time=e.time,this.timeScale=e.timeScale,this.stopWarping()}halt(e){return this.warp(this._effectiveTimeScale,0,e)}warp(e,t,n){const i=this._mixer,r=i.time,s=this.timeScale;let a=this._timeScaleInterpolant;null===a&&(a=i._lendControlInterpolant(),this._timeScaleInterpolant=a);const o=a.parameterPositions,l=a.sampleValues;return o[0]=r,o[1]=r+n,l[0]=e/s,l[1]=t/s,this}stopWarping(){const e=this._timeScaleInterpolant;return null!==e&&(this._timeScaleInterpolant=null,this._mixer._takeBackControlInterpolant(e)),this}getMixer(){return this._mixer}getClip(){return this._clip}getRoot(){return this._localRoot||this._mixer._root}_update(e,t,n,i){if(!this.enabled)return void this._updateWeight(e);const r=this._startTime;if(null!==r){const i=(e-r)*n;if(i<0||0===n)return;this._startTime=null,t=n*i}t*=this._updateTimeScale(e);const s=this._updateTime(t),a=this._updateWeight(e);if(a>0){const e=this._interpolants,t=this._propertyBindings;switch(this.blendMode){case qt:for(let n=0,i=e.length;n!==i;++n)e[n].evaluate(s),t[n].accumulateAdditive(a);break;case jt:default:for(let n=0,r=e.length;n!==r;++n)e[n].evaluate(s),t[n].accumulate(i,a)}}}_updateWeight(e){let t=0;if(this.enabled){t=this.weight;const n=this._weightInterpolant;if(null!==n){const i=n.evaluate(e)[0];t*=i,e>n.parameterPositions[1]&&(this.stopFading(),0===i&&(this.enabled=!1))}}return this._effectiveWeight=t,t}_updateTimeScale(e){let t=0;if(!this.paused){t=this.timeScale;const n=this._timeScaleInterpolant;null!==n&&(t*=n.evaluate(e)[0],e>n.parameterPositions[1]&&(this.stopWarping(),0===t?this.paused=!0:this.timeScale=t))}return this._effectiveTimeScale=t,t}_updateTime(e){const t=this._clip.duration,n=this.loop;let i=this.time+e,r=this._loopCount;const s=n===Ft;if(0===e)return-1===r?i:s&&1==(1&r)?t-i:i;if(n===Ot){-1===r&&(this._loopCount=0,this._setEndings(!0,!0,!1));e:{if(i>=t)i=t;else{if(!(i<0)){this.time=i;break e}i=0}this.clampWhenFinished?this.paused=!0:this.enabled=!1,this.time=i,this._mixer.dispatchEvent({type:"finished",action:this,direction:e<0?-1:1})}}else{if(-1===r&&(e>=0?(r=0,this._setEndings(!0,0===this.repetitions,s)):this._setEndings(0===this.repetitions,!0,s)),i>=t||i<0){const n=Math.floor(i/t);i-=t*n,r+=Math.abs(n);const a=this.repetitions-r;if(a<=0)this.clampWhenFinished?this.paused=!0:this.enabled=!1,i=e>0?t:0,this.time=i,this._mixer.dispatchEvent({type:"finished",action:this,direction:e>0?1:-1});else{if(1===a){const t=e<0;this._setEndings(t,!t,s)}else this._setEndings(!1,!1,s);this._loopCount=r,this.time=i,this._mixer.dispatchEvent({type:"loop",action:this,loopDelta:n})}}else this.time=i;if(s&&1==(1&r))return t-i}return i}_setEndings(e,t,n){const i=this._interpolantSettings;n?(i.endingStart=Vt,i.endingEnd=Vt):(i.endingStart=e?this.zeroSlopeAtStart?Vt:Gt:Wt,i.endingEnd=t?this.zeroSlopeAtEnd?Vt:Gt:Wt)}_scheduleFading(e,t,n){const i=this._mixer,r=i.time;let s=this._weightInterpolant;null===s&&(s=i._lendControlInterpolant(),this._weightInterpolant=s);const a=s.parameterPositions,o=s.sampleValues;return a[0]=r,o[0]=t,a[1]=r+e,o[1]=n,this}}class $d extends On{constructor(e){super(),this._root=e,this._initMemoryManager(),this._accuIndex=0,this.time=0,this.timeScale=1}_bindAction(e,t){const n=e._localRoot||this._root,i=e._clip.tracks,r=i.length,s=e._propertyBindings,a=e._interpolants,o=n.uuid,l=this._bindingsByRootAndName;let c=l[o];void 0===c&&(c={},l[o]=c);for(let e=0;e!==r;++e){const r=i[e],l=r.name;let h=c[l];if(void 0!==h)s[e]=h;else{if(h=s[e],void 0!==h){null===h._cacheIndex&&(++h.referenceCount,this._addInactiveBinding(h,o,l));continue}const i=t&&t._propertyBindings[e].binding.parsedPath;h=new zd(Zd.create(n,l,i),r.ValueTypeName,r.getValueSize()),++h.referenceCount,this._addInactiveBinding(h,o,l),s[e]=h}a[e].resultBuffer=h.buffer}}_activateAction(e){if(!this._isActiveAction(e)){if(null===e._cacheIndex){const t=(e._localRoot||this._root).uuid,n=e._clip.uuid,i=this._actionsByClip[n];this._bindAction(e,i&&i.knownActions[0]),this._addInactiveAction(e,n,t)}const t=e._propertyBindings;for(let e=0,n=t.length;e!==n;++e){const n=t[e];0==n.useCount++&&(this._lendBinding(n),n.saveOriginalState())}this._lendAction(e)}}_deactivateAction(e){if(this._isActiveAction(e)){const t=e._propertyBindings;for(let e=0,n=t.length;e!==n;++e){const n=t[e];0==--n.useCount&&(n.restoreOriginalState(),this._takeBackBinding(n))}this._takeBackAction(e)}}_initMemoryManager(){this._actions=[],this._nActiveActions=0,this._actionsByClip={},this._bindings=[],this._nActiveBindings=0,this._bindingsByRootAndName={},this._controlInterpolants=[],this._nActiveControlInterpolants=0;const e=this;this.stats={actions:{get total(){return e._actions.length},get inUse(){return e._nActiveActions}},bindings:{get total(){return e._bindings.length},get inUse(){return e._nActiveBindings}},controlInterpolants:{get total(){return e._controlInterpolants.length},get inUse(){return e._nActiveControlInterpolants}}}}_isActiveAction(e){const t=e._cacheIndex;return null!==t&&t=0;--t)e[t].stop();return this}update(e){e*=this.timeScale;const t=this._actions,n=this._nActiveActions,i=this.time+=e,r=Math.sign(e),s=this._accuIndex^=1;for(let a=0;a!==n;++a)t[a]._update(i,e,r,s);const a=this._bindings,o=this._nActiveBindings;for(let e=0;e!==o;++e)a[e].apply(s);return this}setTime(e){this.time=0;for(let e=0;ethis.max.x||e.ythis.max.y)}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}getParameter(e,t){return t.set((e.x-this.min.x)/(this.max.x-this.min.x),(e.y-this.min.y)/(this.max.y-this.min.y))}intersectsBox(e){return!(e.max.xthis.max.x||e.max.ythis.max.y)}clampPoint(e,t){return t.copy(e).clamp(this.min,this.max)}distanceToPoint(e){return lp.copy(e).clamp(this.min,this.max).sub(e).length()}intersect(e){return this.min.max(e.min),this.max.min(e.max),this}union(e){return this.min.min(e.min),this.max.max(e.max),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)}}cp.prototype.isBox2=!0;const hp=new oi,up=new oi;class dp{constructor(e=new oi,t=new oi){this.start=e,this.end=t}set(e,t){return this.start.copy(e),this.end.copy(t),this}copy(e){return this.start.copy(e.start),this.end.copy(e.end),this}getCenter(e){return e.addVectors(this.start,this.end).multiplyScalar(.5)}delta(e){return e.subVectors(this.end,this.start)}distanceSq(){return this.start.distanceToSquared(this.end)}distance(){return this.start.distanceTo(this.end)}at(e,t){return this.delta(t).multiplyScalar(e).add(this.start)}closestPointToPointParameter(e,t){hp.subVectors(e,this.start),up.subVectors(this.end,this.start);const n=up.dot(up);let i=up.dot(hp)/n;return t&&(i=Gn(i,0,1)),i}closestPointToPoint(e,t,n){const i=this.closestPointToPointParameter(e,t);return this.delta(n).multiplyScalar(i).add(this.start)}applyMatrix4(e){return this.start.applyMatrix4(e),this.end.applyMatrix4(e),this}equals(e){return e.start.equals(this.start)&&e.end.equals(this.end)}clone(){return(new this.constructor).copy(this)}}class pp extends cr{constructor(e){super(),this.material=e,this.render=function(){},this.hasPositions=!1,this.hasNormals=!1,this.hasColors=!1,this.hasUvs=!1,this.positionArray=null,this.normalArray=null,this.colorArray=null,this.uvArray=null,this.count=0}}pp.prototype.isImmediateRenderObject=!0;const fp=new oi;class mp extends cr{constructor(e,t){super(),this.light=e,this.light.updateMatrixWorld(),this.matrix=e.matrixWorld,this.matrixAutoUpdate=!1,this.color=t;const n=new es,i=[0,0,0,0,0,1,0,0,0,1,0,1,0,0,0,-1,0,1,0,0,0,0,1,1,0,0,0,0,-1,1];for(let e=0,t=1,n=32;e.99999)this.quaternion.set(0,0,0,1);else if(e.y<-.99999)this.quaternion.set(1,0,0,0);else{zp.set(e.z,0,-e.x).normalize();const t=Math.acos(e.y);this.quaternion.setFromAxisAngle(zp,t)}}setLength(e,t=.2*e,n=.2*t){this.line.scale.set(1,Math.max(1e-4,e-t),1),this.line.updateMatrix(),this.cone.scale.set(n,t,n),this.cone.position.y=e,this.cone.updateMatrix()}setColor(e){this.line.material.color.set(e),this.cone.material.color.set(e)}copy(e){return super.copy(e,!1),this.line.copy(e.line),this.cone.copy(e.cone),this}}class Wp extends bc{constructor(e=1){const t=[0,0,0,e,0,0,0,0,0,0,e,0,0,0,0,0,0,e],n=new es;n.setAttribute("position",new Gr(t,3)),n.setAttribute("color",new Gr([1,0,0,1,.6,0,0,1,0,.6,1,0,0,0,1,0,.6,1],3)),super(n,new dc({vertexColors:!0,toneMapped:!1})),this.type="AxesHelper"}setColors(e,t,n){const i=new Cr,r=this.geometry.attributes.color.array;return i.set(e),i.toArray(r,0),i.toArray(r,3),i.set(t),i.toArray(r,6),i.toArray(r,9),i.set(n),i.toArray(r,12),i.toArray(r,15),this.geometry.attributes.color.needsUpdate=!0,this}dispose(){this.geometry.dispose(),this.material.dispose()}}const jp=new Float32Array(1),qp=new Int32Array(jp.buffer);class Xp{static toHalfFloat(e){jp[0]=e;const t=qp[0];let n=t>>16&32768,i=t>>12&2047;const r=t>>23&255;return r<103?n:r>142?(n|=31744,n|=(255==r?0:1)&&8388607&t,n):r<113?(i|=2048,n|=(i>>114-r)+(i>>113-r&1),n):(n|=r-112<<10|i>>1,n+=1&i,n)}}const Yp=0,Jp=1,Zp=0,Kp=1,Qp=2;function $p(e){return console.warn("THREE.MeshFaceMaterial has been removed. Use an Array instead."),e}function ef(e=[]){return console.warn("THREE.MultiMaterial has been removed. Use an Array instead."),e.isMultiMaterial=!0,e.materials=e,e.clone=function(){return e.slice()},e}function tf(e,t){return console.warn("THREE.PointCloud has been renamed to THREE.Points."),new Lc(e,t)}function nf(e){return console.warn("THREE.Particle has been renamed to THREE.Sprite."),new Wl(e)}function rf(e,t){return console.warn("THREE.ParticleSystem has been renamed to THREE.Points."),new Lc(e,t)}function sf(e){return console.warn("THREE.PointCloudMaterial has been renamed to THREE.PointsMaterial."),new Mc(e)}function af(e){return console.warn("THREE.ParticleBasicMaterial has been renamed to THREE.PointsMaterial."),new Mc(e)}function of(e){return console.warn("THREE.ParticleSystemMaterial has been renamed to THREE.PointsMaterial."),new Mc(e)}function lf(e,t,n){return console.warn("THREE.Vertex has been removed. Use THREE.Vector3 instead."),new oi(e,t,n)}function cf(e,t){return console.warn("THREE.DynamicBufferAttribute has been removed. Use new THREE.BufferAttribute().setUsage( THREE.DynamicDrawUsage ) instead."),new Nr(e,t).setUsage(Sn)}function hf(e,t){return console.warn("THREE.Int8Attribute has been removed. Use new THREE.Int8BufferAttribute() instead."),new Ir(e,t)}function uf(e,t){return console.warn("THREE.Uint8Attribute has been removed. Use new THREE.Uint8BufferAttribute() instead."),new Dr(e,t)}function df(e,t){return console.warn("THREE.Uint8ClampedAttribute has been removed. Use new THREE.Uint8ClampedBufferAttribute() instead."),new Or(e,t)}function pf(e,t){return console.warn("THREE.Int16Attribute has been removed. Use new THREE.Int16BufferAttribute() instead."),new Br(e,t)}function ff(e,t){return console.warn("THREE.Uint16Attribute has been removed. Use new THREE.Uint16BufferAttribute() instead."),new Fr(e,t)}function mf(e,t){return console.warn("THREE.Int32Attribute has been removed. Use new THREE.Int32BufferAttribute() instead."),new Ur(e,t)}function gf(e,t){return console.warn("THREE.Uint32Attribute has been removed. Use new THREE.Uint32BufferAttribute() instead."),new zr(e,t)}function vf(e,t){return console.warn("THREE.Float32Attribute has been removed. Use new THREE.Float32BufferAttribute() instead."),new Gr(e,t)}function yf(e,t){return console.warn("THREE.Float64Attribute has been removed. Use new THREE.Float64BufferAttribute() instead."),new Vr(e,t)}function _f(e){return console.warn("THREE.AxisHelper has been renamed to THREE.AxesHelper."),new Wp(e)}function xf(e,t){return console.warn("THREE.BoundingBoxHelper has been deprecated. Creating a THREE.BoxHelper instead."),new Bp(e,t)}function bf(e,t){return console.warn("THREE.EdgesHelper has been removed. Use THREE.EdgesGeometry instead."),new bc(new Vc(e.geometry),new dc({color:void 0!==t?t:16777215}))}function wf(e,t){return console.warn("THREE.WireframeHelper has been removed. Use THREE.WireframeGeometry instead."),new bc(new Kh(e.geometry),new dc({color:void 0!==t?t:16777215}))}function Mf(e){return console.warn("THREE.XHRLoader has been renamed to THREE.FileLoader."),new Ru(e)}function Tf(e){return console.warn("THREE.BinaryTextureLoader has been renamed to THREE.DataTextureLoader."),new Du(e)}function Ef(e,t,n){return console.warn("THREE.WebGLRenderTargetCube( width, height, options ) is now WebGLCubeRenderTarget( size, options )."),new Rs(e,n)}function Sf(){console.error("THREE.CanvasRenderer has been removed")}function Af(){console.error("THREE.JSONLoader has been removed.")}Wc.create=function(e,t){return console.log("THREE.Curve.create() has been deprecated"),e.prototype=Object.create(Wc.prototype),e.prototype.constructor=e,e.prototype.getPoint=t,e},Fu.prototype.fromPoints=function(e){return console.warn("THREE.Path: .fromPoints() has been renamed to .setFromPoints()."),this.setFromPoints(e)},Sp.prototype.setColors=function(){console.error("THREE.GridHelper: setColors() has been deprecated, pass them in the constructor instead.")},_p.prototype.update=function(){console.error("THREE.SkeletonHelper: update() no longer needs to be called.")},Lu.prototype.extractUrlBase=function(e){return console.warn("THREE.Loader: .extractUrlBase() has been deprecated. Use THREE.LoaderUtils.extractUrlBase() instead."),ad.extractUrlBase(e)},Lu.Handlers={add:function(){console.error("THREE.Loader: Handlers.add() has been removed. Use LoadingManager.addHandler() instead.")},get:function(){console.error("THREE.Loader: Handlers.get() has been removed. Use LoadingManager.getHandler() instead.")}},cp.prototype.center=function(e){return console.warn("THREE.Box2: .center() has been renamed to .getCenter()."),this.getCenter(e)},cp.prototype.empty=function(){return console.warn("THREE.Box2: .empty() has been renamed to .isEmpty()."),this.isEmpty()},cp.prototype.isIntersectionBox=function(e){return console.warn("THREE.Box2: .isIntersectionBox() has been renamed to .intersectsBox()."),this.intersectsBox(e)},cp.prototype.size=function(e){return console.warn("THREE.Box2: .size() has been renamed to .getSize()."),this.getSize(e)},hi.prototype.center=function(e){return console.warn("THREE.Box3: .center() has been renamed to .getCenter()."),this.getCenter(e)},hi.prototype.empty=function(){return console.warn("THREE.Box3: .empty() has been renamed to .isEmpty()."),this.isEmpty()},hi.prototype.isIntersectionBox=function(e){return console.warn("THREE.Box3: .isIntersectionBox() has been renamed to .intersectsBox()."),this.intersectsBox(e)},hi.prototype.isIntersectionSphere=function(e){return console.warn("THREE.Box3: .isIntersectionSphere() has been renamed to .intersectsSphere()."),this.intersectsSphere(e)},hi.prototype.size=function(e){return console.warn("THREE.Box3: .size() has been renamed to .getSize()."),this.getSize(e)},Ci.prototype.empty=function(){return console.warn("THREE.Sphere: .empty() has been renamed to .isEmpty()."),this.isEmpty()},Bs.prototype.setFromMatrix=function(e){return console.warn("THREE.Frustum: .setFromMatrix() has been renamed to .setFromProjectionMatrix()."),this.setFromProjectionMatrix(e)},dp.prototype.center=function(e){return console.warn("THREE.Line3: .center() has been renamed to .getCenter()."),this.getCenter(e)},Zn.prototype.flattenToArrayOffset=function(e,t){return console.warn("THREE.Matrix3: .flattenToArrayOffset() has been deprecated. Use .toArray() instead."),this.toArray(e,t)},Zn.prototype.multiplyVector3=function(e){return console.warn("THREE.Matrix3: .multiplyVector3() has been removed. Use vector.applyMatrix3( matrix ) instead."),e.applyMatrix3(this)},Zn.prototype.multiplyVector3Array=function(){console.error("THREE.Matrix3: .multiplyVector3Array() has been removed.")},Zn.prototype.applyToBufferAttribute=function(e){return console.warn("THREE.Matrix3: .applyToBufferAttribute() has been removed. Use attribute.applyMatrix3( matrix ) instead."),e.applyMatrix3(this)},Zn.prototype.applyToVector3Array=function(){console.error("THREE.Matrix3: .applyToVector3Array() has been removed.")},Zn.prototype.getInverse=function(e){return console.warn("THREE.Matrix3: .getInverse() has been removed. Use matrixInv.copy( matrix ).invert(); instead."),this.copy(e).invert()},Fi.prototype.extractPosition=function(e){return console.warn("THREE.Matrix4: .extractPosition() has been renamed to .copyPosition()."),this.copyPosition(e)},Fi.prototype.flattenToArrayOffset=function(e,t){return console.warn("THREE.Matrix4: .flattenToArrayOffset() has been deprecated. Use .toArray() instead."),this.toArray(e,t)},Fi.prototype.getPosition=function(){return console.warn("THREE.Matrix4: .getPosition() has been removed. Use Vector3.setFromMatrixPosition( matrix ) instead."),(new oi).setFromMatrixColumn(this,3)},Fi.prototype.setRotationFromQuaternion=function(e){return console.warn("THREE.Matrix4: .setRotationFromQuaternion() has been renamed to .makeRotationFromQuaternion()."),this.makeRotationFromQuaternion(e)},Fi.prototype.multiplyToArray=function(){console.warn("THREE.Matrix4: .multiplyToArray() has been removed.")},Fi.prototype.multiplyVector3=function(e){return console.warn("THREE.Matrix4: .multiplyVector3() has been removed. Use vector.applyMatrix4( matrix ) instead."),e.applyMatrix4(this)},Fi.prototype.multiplyVector4=function(e){return console.warn("THREE.Matrix4: .multiplyVector4() has been removed. Use vector.applyMatrix4( matrix ) instead."),e.applyMatrix4(this)},Fi.prototype.multiplyVector3Array=function(){console.error("THREE.Matrix4: .multiplyVector3Array() has been removed.")},Fi.prototype.rotateAxis=function(e){console.warn("THREE.Matrix4: .rotateAxis() has been removed. Use Vector3.transformDirection( matrix ) instead."),e.transformDirection(this)},Fi.prototype.crossVector=function(e){return console.warn("THREE.Matrix4: .crossVector() has been removed. Use vector.applyMatrix4( matrix ) instead."),e.applyMatrix4(this)},Fi.prototype.translate=function(){console.error("THREE.Matrix4: .translate() has been removed.")},Fi.prototype.rotateX=function(){console.error("THREE.Matrix4: .rotateX() has been removed.")},Fi.prototype.rotateY=function(){console.error("THREE.Matrix4: .rotateY() has been removed.")},Fi.prototype.rotateZ=function(){console.error("THREE.Matrix4: .rotateZ() has been removed.")},Fi.prototype.rotateByAxis=function(){console.error("THREE.Matrix4: .rotateByAxis() has been removed.")},Fi.prototype.applyToBufferAttribute=function(e){return console.warn("THREE.Matrix4: .applyToBufferAttribute() has been removed. Use attribute.applyMatrix4( matrix ) instead."),e.applyMatrix4(this)},Fi.prototype.applyToVector3Array=function(){console.error("THREE.Matrix4: .applyToVector3Array() has been removed.")},Fi.prototype.makeFrustum=function(e,t,n,i,r,s){return console.warn("THREE.Matrix4: .makeFrustum() has been removed. Use .makePerspective( left, right, top, bottom, near, far ) instead."),this.makePerspective(e,t,i,n,r,s)},Fi.prototype.getInverse=function(e){return console.warn("THREE.Matrix4: .getInverse() has been removed. Use matrixInv.copy( matrix ).invert(); instead."),this.copy(e).invert()},Is.prototype.isIntersectionLine=function(e){return console.warn("THREE.Plane: .isIntersectionLine() has been renamed to .intersectsLine()."),this.intersectsLine(e)},ai.prototype.multiplyVector3=function(e){return console.warn("THREE.Quaternion: .multiplyVector3() has been removed. Use is now vector.applyQuaternion( quaternion ) instead."),e.applyQuaternion(this)},ai.prototype.inverse=function(){return console.warn("THREE.Quaternion: .inverse() has been renamed to invert()."),this.invert()},Bi.prototype.isIntersectionBox=function(e){return console.warn("THREE.Ray: .isIntersectionBox() has been renamed to .intersectsBox()."),this.intersectsBox(e)},Bi.prototype.isIntersectionPlane=function(e){return console.warn("THREE.Ray: .isIntersectionPlane() has been renamed to .intersectsPlane()."),this.intersectsPlane(e)},Bi.prototype.isIntersectionSphere=function(e){return console.warn("THREE.Ray: .isIntersectionSphere() has been renamed to .intersectsSphere()."),this.intersectsSphere(e)},xr.prototype.area=function(){return console.warn("THREE.Triangle: .area() has been renamed to .getArea()."),this.getArea()},xr.prototype.barycoordFromPoint=function(e,t){return console.warn("THREE.Triangle: .barycoordFromPoint() has been renamed to .getBarycoord()."),this.getBarycoord(e,t)},xr.prototype.midpoint=function(e){return console.warn("THREE.Triangle: .midpoint() has been renamed to .getMidpoint()."),this.getMidpoint(e)},xr.prototypenormal=function(e){return console.warn("THREE.Triangle: .normal() has been renamed to .getNormal()."),this.getNormal(e)},xr.prototype.plane=function(e){return console.warn("THREE.Triangle: .plane() has been renamed to .getPlane()."),this.getPlane(e)},xr.barycoordFromPoint=function(e,t,n,i,r){return console.warn("THREE.Triangle: .barycoordFromPoint() has been renamed to .getBarycoord()."),xr.getBarycoord(e,t,n,i,r)},xr.normal=function(e,t,n,i){return console.warn("THREE.Triangle: .normal() has been renamed to .getNormal()."),xr.getNormal(e,t,n,i)},Uu.prototype.extractAllPoints=function(e){return console.warn("THREE.Shape: .extractAllPoints() has been removed. Use .extractPoints() instead."),this.extractPoints(e)},Uu.prototype.extrude=function(e){return console.warn("THREE.Shape: .extrude() has been removed. Use ExtrudeGeometry() instead."),new Bh(this,e)},Uu.prototype.makeGeometry=function(e){return console.warn("THREE.Shape: .makeGeometry() has been removed. Use ShapeGeometry() instead."),new Wh(this,e)},Jn.prototype.fromAttribute=function(e,t,n){return console.warn("THREE.Vector2: .fromAttribute() has been renamed to .fromBufferAttribute()."),this.fromBufferAttribute(e,t,n)},Jn.prototype.distanceToManhattan=function(e){return console.warn("THREE.Vector2: .distanceToManhattan() has been renamed to .manhattanDistanceTo()."),this.manhattanDistanceTo(e)},Jn.prototype.lengthManhattan=function(){return console.warn("THREE.Vector2: .lengthManhattan() has been renamed to .manhattanLength()."),this.manhattanLength()},oi.prototype.setEulerFromRotationMatrix=function(){console.error("THREE.Vector3: .setEulerFromRotationMatrix() has been removed. Use Euler.setFromRotationMatrix() instead.")},oi.prototype.setEulerFromQuaternion=function(){console.error("THREE.Vector3: .setEulerFromQuaternion() has been removed. Use Euler.setFromQuaternion() instead.")},oi.prototype.getPositionFromMatrix=function(e){return console.warn("THREE.Vector3: .getPositionFromMatrix() has been renamed to .setFromMatrixPosition()."),this.setFromMatrixPosition(e)},oi.prototype.getScaleFromMatrix=function(e){return console.warn("THREE.Vector3: .getScaleFromMatrix() has been renamed to .setFromMatrixScale()."),this.setFromMatrixScale(e)},oi.prototype.getColumnFromMatrix=function(e,t){return console.warn("THREE.Vector3: .getColumnFromMatrix() has been renamed to .setFromMatrixColumn()."),this.setFromMatrixColumn(t,e)},oi.prototype.applyProjection=function(e){return console.warn("THREE.Vector3: .applyProjection() has been removed. Use .applyMatrix4( m ) instead."),this.applyMatrix4(e)},oi.prototype.fromAttribute=function(e,t,n){return console.warn("THREE.Vector3: .fromAttribute() has been renamed to .fromBufferAttribute()."),this.fromBufferAttribute(e,t,n)},oi.prototype.distanceToManhattan=function(e){return console.warn("THREE.Vector3: .distanceToManhattan() has been renamed to .manhattanDistanceTo()."),this.manhattanDistanceTo(e)},oi.prototype.lengthManhattan=function(){return console.warn("THREE.Vector3: .lengthManhattan() has been renamed to .manhattanLength()."),this.manhattanLength()},ni.prototype.fromAttribute=function(e,t,n){return console.warn("THREE.Vector4: .fromAttribute() has been renamed to .fromBufferAttribute()."),this.fromBufferAttribute(e,t,n)},ni.prototype.lengthManhattan=function(){return console.warn("THREE.Vector4: .lengthManhattan() has been renamed to .manhattanLength()."),this.manhattanLength()},cr.prototype.getChildByName=function(e){return console.warn("THREE.Object3D: .getChildByName() has been renamed to .getObjectByName()."),this.getObjectByName(e)},cr.prototype.renderDepth=function(){console.warn("THREE.Object3D: .renderDepth has been removed. Use .renderOrder, instead.")},cr.prototype.translate=function(e,t){return console.warn("THREE.Object3D: .translate() has been removed. Use .translateOnAxis( axis, distance ) instead."),this.translateOnAxis(t,e)},cr.prototype.getWorldRotation=function(){console.error("THREE.Object3D: .getWorldRotation() has been removed. Use THREE.Object3D.getWorldQuaternion( target ) instead.")},cr.prototype.applyMatrix=function(e){return console.warn("THREE.Object3D: .applyMatrix() has been renamed to .applyMatrix4()."),this.applyMatrix4(e)},Object.defineProperties(cr.prototype,{eulerOrder:{get:function(){return console.warn("THREE.Object3D: .eulerOrder is now .rotation.order."),this.rotation.order},set:function(e){console.warn("THREE.Object3D: .eulerOrder is now .rotation.order."),this.rotation.order=e}},useQuaternion:{get:function(){console.warn("THREE.Object3D: .useQuaternion has been removed. The library now uses quaternions by default.")},set:function(){console.warn("THREE.Object3D: .useQuaternion has been removed. The library now uses quaternions by default.")}}}),ys.prototype.setDrawMode=function(){console.error("THREE.Mesh: .setDrawMode() has been removed. The renderer now always assumes THREE.TrianglesDrawMode. Transform your geometry via BufferGeometryUtils.toTrianglesDrawMode() if necessary.")},Object.defineProperties(ys.prototype,{drawMode:{get:function(){return console.error("THREE.Mesh: .drawMode has been removed. The renderer now always assumes THREE.TrianglesDrawMode."),Xt},set:function(){console.error("THREE.Mesh: .drawMode has been removed. The renderer now always assumes THREE.TrianglesDrawMode. Transform your geometry via BufferGeometryUtils.toTrianglesDrawMode() if necessary.")}}}),ec.prototype.initBones=function(){console.error("THREE.SkinnedMesh: initBones() has been removed.")},Ss.prototype.setLens=function(e,t){console.warn("THREE.PerspectiveCamera.setLens is deprecated. Use .setFocalLength and .filmGauge for a photographic setup."),void 0!==t&&(this.filmGauge=t),this.setFocalLength(e)},Object.defineProperties(zu.prototype,{onlyShadow:{set:function(){console.warn("THREE.Light: .onlyShadow has been removed.")}},shadowCameraFov:{set:function(e){console.warn("THREE.Light: .shadowCameraFov is now .shadow.camera.fov."),this.shadow.camera.fov=e}},shadowCameraLeft:{set:function(e){console.warn("THREE.Light: .shadowCameraLeft is now .shadow.camera.left."),this.shadow.camera.left=e}},shadowCameraRight:{set:function(e){console.warn("THREE.Light: .shadowCameraRight is now .shadow.camera.right."),this.shadow.camera.right=e}},shadowCameraTop:{set:function(e){console.warn("THREE.Light: .shadowCameraTop is now .shadow.camera.top."),this.shadow.camera.top=e}},shadowCameraBottom:{set:function(e){console.warn("THREE.Light: .shadowCameraBottom is now .shadow.camera.bottom."),this.shadow.camera.bottom=e}},shadowCameraNear:{set:function(e){console.warn("THREE.Light: .shadowCameraNear is now .shadow.camera.near."),this.shadow.camera.near=e}},shadowCameraFar:{set:function(e){console.warn("THREE.Light: .shadowCameraFar is now .shadow.camera.far."),this.shadow.camera.far=e}},shadowCameraVisible:{set:function(){console.warn("THREE.Light: .shadowCameraVisible has been removed. Use new THREE.CameraHelper( light.shadow.camera ) instead.")}},shadowBias:{set:function(e){console.warn("THREE.Light: .shadowBias is now .shadow.bias."),this.shadow.bias=e}},shadowDarkness:{set:function(){console.warn("THREE.Light: .shadowDarkness has been removed.")}},shadowMapWidth:{set:function(e){console.warn("THREE.Light: .shadowMapWidth is now .shadow.mapSize.width."),this.shadow.mapSize.width=e}},shadowMapHeight:{set:function(e){console.warn("THREE.Light: .shadowMapHeight is now .shadow.mapSize.height."),this.shadow.mapSize.height=e}}}),Object.defineProperties(Nr.prototype,{length:{get:function(){return console.warn("THREE.BufferAttribute: .length has been deprecated. Use .count instead."),this.array.length}},dynamic:{get:function(){return console.warn("THREE.BufferAttribute: .dynamic has been deprecated. Use .usage instead."),this.usage===Sn},set:function(){console.warn("THREE.BufferAttribute: .dynamic has been deprecated. Use .usage instead."),this.setUsage(Sn)}}}),Nr.prototype.setDynamic=function(e){return console.warn("THREE.BufferAttribute: .setDynamic() has been deprecated. Use .setUsage() instead."),this.setUsage(!0===e?Sn:En),this},Nr.prototype.copyIndicesArray=function(){console.error("THREE.BufferAttribute: .copyIndicesArray() has been removed.")},Nr.prototype.setArray=function(){console.error("THREE.BufferAttribute: .setArray has been removed. Use BufferGeometry .setAttribute to replace/resize attribute buffers")},es.prototype.addIndex=function(e){console.warn("THREE.BufferGeometry: .addIndex() has been renamed to .setIndex()."),this.setIndex(e)},es.prototype.addAttribute=function(e,t){return console.warn("THREE.BufferGeometry: .addAttribute() has been renamed to .setAttribute()."),t&&t.isBufferAttribute||t&&t.isInterleavedBufferAttribute?"index"===e?(console.warn("THREE.BufferGeometry.addAttribute: Use .setIndex() for index attribute."),this.setIndex(t),this):this.setAttribute(e,t):(console.warn("THREE.BufferGeometry: .addAttribute() now expects ( name, attribute )."),this.setAttribute(e,new Nr(arguments[1],arguments[2])))},es.prototype.addDrawCall=function(e,t,n){void 0!==n&&console.warn("THREE.BufferGeometry: .addDrawCall() no longer supports indexOffset."),console.warn("THREE.BufferGeometry: .addDrawCall() is now .addGroup()."),this.addGroup(e,t)},es.prototype.clearDrawCalls=function(){console.warn("THREE.BufferGeometry: .clearDrawCalls() is now .clearGroups()."),this.clearGroups()},es.prototype.computeOffsets=function(){console.warn("THREE.BufferGeometry: .computeOffsets() has been removed.")},es.prototype.removeAttribute=function(e){return console.warn("THREE.BufferGeometry: .removeAttribute() has been renamed to .deleteAttribute()."),this.deleteAttribute(e)},es.prototype.applyMatrix=function(e){return console.warn("THREE.BufferGeometry: .applyMatrix() has been renamed to .applyMatrix4()."),this.applyMatrix4(e)},Object.defineProperties(es.prototype,{drawcalls:{get:function(){return console.error("THREE.BufferGeometry: .drawcalls has been renamed to .groups."),this.groups}},offsets:{get:function(){return console.warn("THREE.BufferGeometry: .offsets has been renamed to .groups."),this.groups}}}),Al.prototype.setDynamic=function(e){return console.warn("THREE.InterleavedBuffer: .setDynamic() has been deprecated. Use .setUsage() instead."),this.setUsage(!0===e?Sn:En),this},Al.prototype.setArray=function(){console.error("THREE.InterleavedBuffer: .setArray has been removed. Use BufferGeometry .setAttribute to replace/resize attribute buffers")},Bh.prototype.getArrays=function(){console.error("THREE.ExtrudeGeometry: .getArrays() has been removed.")},Bh.prototype.addShapeList=function(){console.error("THREE.ExtrudeGeometry: .addShapeList() has been removed.")},Bh.prototype.addShape=function(){console.error("THREE.ExtrudeGeometry: .addShape() has been removed.")},Sl.prototype.dispose=function(){console.error("THREE.Scene: .dispose() has been removed.")},ep.prototype.onUpdate=function(){return console.warn("THREE.Uniform: .onUpdate() has been removed. Use object.onBeforeRender() instead."),this},Object.defineProperties(wr.prototype,{wrapAround:{get:function(){console.warn("THREE.Material: .wrapAround has been removed.")},set:function(){console.warn("THREE.Material: .wrapAround has been removed.")}},overdraw:{get:function(){console.warn("THREE.Material: .overdraw has been removed.")},set:function(){console.warn("THREE.Material: .overdraw has been removed.")}},wrapRGB:{get:function(){return console.warn("THREE.Material: .wrapRGB has been removed."),new Cr}},shading:{get:function(){console.error("THREE."+this.type+": .shading has been removed. Use the boolean .flatShading instead.")},set:function(e){console.warn("THREE."+this.type+": .shading has been removed. Use the boolean .flatShading instead."),this.flatShading=e===v}},stencilMask:{get:function(){return console.warn("THREE."+this.type+": .stencilMask has been removed. Use .stencilFuncMask instead."),this.stencilFuncMask},set:function(e){console.warn("THREE."+this.type+": .stencilMask has been removed. Use .stencilFuncMask instead."),this.stencilFuncMask=e}},vertexTangents:{get:function(){console.warn("THREE."+this.type+": .vertexTangents has been removed.")},set:function(){console.warn("THREE."+this.type+": .vertexTangents has been removed.")}}}),Object.defineProperties(Ts.prototype,{derivatives:{get:function(){return console.warn("THREE.ShaderMaterial: .derivatives has been moved to .extensions.derivatives."),this.extensions.derivatives},set:function(e){console.warn("THREE. ShaderMaterial: .derivatives has been moved to .extensions.derivatives."),this.extensions.derivatives=e}}}),wl.prototype.clearTarget=function(e,t,n,i){console.warn("THREE.WebGLRenderer: .clearTarget() has been deprecated. Use .setRenderTarget() and .clear() instead."),this.setRenderTarget(e),this.clear(t,n,i)},wl.prototype.animate=function(e){console.warn("THREE.WebGLRenderer: .animate() is now .setAnimationLoop()."),this.setAnimationLoop(e)},wl.prototype.getCurrentRenderTarget=function(){return console.warn("THREE.WebGLRenderer: .getCurrentRenderTarget() is now .getRenderTarget()."),this.getRenderTarget()},wl.prototype.getMaxAnisotropy=function(){return console.warn("THREE.WebGLRenderer: .getMaxAnisotropy() is now .capabilities.getMaxAnisotropy()."),this.capabilities.getMaxAnisotropy()},wl.prototype.getPrecision=function(){return console.warn("THREE.WebGLRenderer: .getPrecision() is now .capabilities.precision."),this.capabilities.precision},wl.prototype.resetGLState=function(){return console.warn("THREE.WebGLRenderer: .resetGLState() is now .state.reset()."),this.state.reset()},wl.prototype.supportsFloatTextures=function(){return console.warn("THREE.WebGLRenderer: .supportsFloatTextures() is now .extensions.get( 'OES_texture_float' )."),this.extensions.get("OES_texture_float")},wl.prototype.supportsHalfFloatTextures=function(){return console.warn("THREE.WebGLRenderer: .supportsHalfFloatTextures() is now .extensions.get( 'OES_texture_half_float' )."),this.extensions.get("OES_texture_half_float")},wl.prototype.supportsStandardDerivatives=function(){return console.warn("THREE.WebGLRenderer: .supportsStandardDerivatives() is now .extensions.get( 'OES_standard_derivatives' )."),this.extensions.get("OES_standard_derivatives")},wl.prototype.supportsCompressedTextureS3TC=function(){return console.warn("THREE.WebGLRenderer: .supportsCompressedTextureS3TC() is now .extensions.get( 'WEBGL_compressed_texture_s3tc' )."),this.extensions.get("WEBGL_compressed_texture_s3tc")},wl.prototype.supportsCompressedTexturePVRTC=function(){return console.warn("THREE.WebGLRenderer: .supportsCompressedTexturePVRTC() is now .extensions.get( 'WEBGL_compressed_texture_pvrtc' )."),this.extensions.get("WEBGL_compressed_texture_pvrtc")},wl.prototype.supportsBlendMinMax=function(){return console.warn("THREE.WebGLRenderer: .supportsBlendMinMax() is now .extensions.get( 'EXT_blend_minmax' )."),this.extensions.get("EXT_blend_minmax")},wl.prototype.supportsVertexTextures=function(){return console.warn("THREE.WebGLRenderer: .supportsVertexTextures() is now .capabilities.vertexTextures."),this.capabilities.vertexTextures},wl.prototype.supportsInstancedArrays=function(){return console.warn("THREE.WebGLRenderer: .supportsInstancedArrays() is now .extensions.get( 'ANGLE_instanced_arrays' )."),this.extensions.get("ANGLE_instanced_arrays")},wl.prototype.enableScissorTest=function(e){console.warn("THREE.WebGLRenderer: .enableScissorTest() is now .setScissorTest()."),this.setScissorTest(e)},wl.prototype.initMaterial=function(){console.warn("THREE.WebGLRenderer: .initMaterial() has been removed.")},wl.prototype.addPrePlugin=function(){console.warn("THREE.WebGLRenderer: .addPrePlugin() has been removed.")},wl.prototype.addPostPlugin=function(){console.warn("THREE.WebGLRenderer: .addPostPlugin() has been removed.")},wl.prototype.updateShadowMap=function(){console.warn("THREE.WebGLRenderer: .updateShadowMap() has been removed.")},wl.prototype.setFaceCulling=function(){console.warn("THREE.WebGLRenderer: .setFaceCulling() has been removed.")},wl.prototype.allocTextureUnit=function(){console.warn("THREE.WebGLRenderer: .allocTextureUnit() has been removed.")},wl.prototype.setTexture=function(){console.warn("THREE.WebGLRenderer: .setTexture() has been removed.")},wl.prototype.setTexture2D=function(){console.warn("THREE.WebGLRenderer: .setTexture2D() has been removed.")},wl.prototype.setTextureCube=function(){console.warn("THREE.WebGLRenderer: .setTextureCube() has been removed.")},wl.prototype.getActiveMipMapLevel=function(){return console.warn("THREE.WebGLRenderer: .getActiveMipMapLevel() is now .getActiveMipmapLevel()."),this.getActiveMipmapLevel()},Object.defineProperties(wl.prototype,{shadowMapEnabled:{get:function(){return this.shadowMap.enabled},set:function(e){console.warn("THREE.WebGLRenderer: .shadowMapEnabled is now .shadowMap.enabled."),this.shadowMap.enabled=e}},shadowMapType:{get:function(){return this.shadowMap.type},set:function(e){console.warn("THREE.WebGLRenderer: .shadowMapType is now .shadowMap.type."),this.shadowMap.type=e}},shadowMapCullFace:{get:function(){console.warn("THREE.WebGLRenderer: .shadowMapCullFace has been removed. Set Material.shadowSide instead.")},set:function(){console.warn("THREE.WebGLRenderer: .shadowMapCullFace has been removed. Set Material.shadowSide instead.")}},context:{get:function(){return console.warn("THREE.WebGLRenderer: .context has been removed. Use .getContext() instead."),this.getContext()}},vr:{get:function(){return console.warn("THREE.WebGLRenderer: .vr has been renamed to .xr"),this.xr}},gammaInput:{get:function(){return console.warn("THREE.WebGLRenderer: .gammaInput has been removed. Set the encoding for textures via Texture.encoding instead."),!1},set:function(){console.warn("THREE.WebGLRenderer: .gammaInput has been removed. Set the encoding for textures via Texture.encoding instead.")}},gammaOutput:{get:function(){return console.warn("THREE.WebGLRenderer: .gammaOutput has been removed. Set WebGLRenderer.outputEncoding instead."),!1},set:function(e){console.warn("THREE.WebGLRenderer: .gammaOutput has been removed. Set WebGLRenderer.outputEncoding instead."),this.outputEncoding=!0===e?Kt:Zt}},toneMappingWhitePoint:{get:function(){return console.warn("THREE.WebGLRenderer: .toneMappingWhitePoint has been removed."),1},set:function(){console.warn("THREE.WebGLRenderer: .toneMappingWhitePoint has been removed.")}}}),Object.defineProperties(dl.prototype,{cullFace:{get:function(){console.warn("THREE.WebGLRenderer: .shadowMap.cullFace has been removed. Set Material.shadowSide instead.")},set:function(){console.warn("THREE.WebGLRenderer: .shadowMap.cullFace has been removed. Set Material.shadowSide instead.")}},renderReverseSided:{get:function(){console.warn("THREE.WebGLRenderer: .shadowMap.renderReverseSided has been removed. Set Material.shadowSide instead.")},set:function(){console.warn("THREE.WebGLRenderer: .shadowMap.renderReverseSided has been removed. Set Material.shadowSide instead.")}},renderSingleSided:{get:function(){console.warn("THREE.WebGLRenderer: .shadowMap.renderSingleSided has been removed. Set Material.shadowSide instead.")},set:function(){console.warn("THREE.WebGLRenderer: .shadowMap.renderSingleSided has been removed. Set Material.shadowSide instead.")}}}),Object.defineProperties(ii.prototype,{wrapS:{get:function(){return console.warn("THREE.WebGLRenderTarget: .wrapS is now .texture.wrapS."),this.texture.wrapS},set:function(e){console.warn("THREE.WebGLRenderTarget: .wrapS is now .texture.wrapS."),this.texture.wrapS=e}},wrapT:{get:function(){return console.warn("THREE.WebGLRenderTarget: .wrapT is now .texture.wrapT."),this.texture.wrapT},set:function(e){console.warn("THREE.WebGLRenderTarget: .wrapT is now .texture.wrapT."),this.texture.wrapT=e}},magFilter:{get:function(){return console.warn("THREE.WebGLRenderTarget: .magFilter is now .texture.magFilter."),this.texture.magFilter},set:function(e){console.warn("THREE.WebGLRenderTarget: .magFilter is now .texture.magFilter."),this.texture.magFilter=e}},minFilter:{get:function(){return console.warn("THREE.WebGLRenderTarget: .minFilter is now .texture.minFilter."),this.texture.minFilter},set:function(e){console.warn("THREE.WebGLRenderTarget: .minFilter is now .texture.minFilter."),this.texture.minFilter=e}},anisotropy:{get:function(){return console.warn("THREE.WebGLRenderTarget: .anisotropy is now .texture.anisotropy."),this.texture.anisotropy},set:function(e){console.warn("THREE.WebGLRenderTarget: .anisotropy is now .texture.anisotropy."),this.texture.anisotropy=e}},offset:{get:function(){return console.warn("THREE.WebGLRenderTarget: .offset is now .texture.offset."),this.texture.offset},set:function(e){console.warn("THREE.WebGLRenderTarget: .offset is now .texture.offset."),this.texture.offset=e}},repeat:{get:function(){return console.warn("THREE.WebGLRenderTarget: .repeat is now .texture.repeat."),this.texture.repeat},set:function(e){console.warn("THREE.WebGLRenderTarget: .repeat is now .texture.repeat."),this.texture.repeat=e}},format:{get:function(){return console.warn("THREE.WebGLRenderTarget: .format is now .texture.format."),this.texture.format},set:function(e){console.warn("THREE.WebGLRenderTarget: .format is now .texture.format."),this.texture.format=e}},type:{get:function(){return console.warn("THREE.WebGLRenderTarget: .type is now .texture.type."),this.texture.type},set:function(e){console.warn("THREE.WebGLRenderTarget: .type is now .texture.type."),this.texture.type=e}},generateMipmaps:{get:function(){return console.warn("THREE.WebGLRenderTarget: .generateMipmaps is now .texture.generateMipmaps."),this.texture.generateMipmaps},set:function(e){console.warn("THREE.WebGLRenderTarget: .generateMipmaps is now .texture.generateMipmaps."),this.texture.generateMipmaps=e}}}),Nd.prototype.load=function(e){console.warn("THREE.Audio: .load has been deprecated. Use THREE.AudioLoader instead.");const t=this;return(new xd).load(e,(function(e){t.setBuffer(e)})),this},Ud.prototype.getData=function(){return console.warn("THREE.AudioAnalyser: .getData() is now .getFrequencyData()."),this.getFrequencyData()},Ls.prototype.updateCubeMap=function(e,t){return console.warn("THREE.CubeCamera: .updateCubeMap() is now .update()."),this.update(e,t)},Ls.prototype.clear=function(e,t,n,i){return console.warn("THREE.CubeCamera: .clear() is now .renderTarget.clear()."),this.renderTarget.clear(e,t,n,i)},Qn.crossOrigin=void 0,Qn.loadTexture=function(e,t,n,i){console.warn("THREE.ImageUtils.loadTexture has been deprecated. Use THREE.TextureLoader() instead.");const r=new Ou;r.setCrossOrigin(this.crossOrigin);const s=r.load(e,n,void 0,i);return t&&(s.mapping=t),s},Qn.loadTextureCube=function(e,t,n,i){console.warn("THREE.ImageUtils.loadTextureCube has been deprecated. Use THREE.CubeTextureLoader() instead.");const r=new Iu;r.setCrossOrigin(this.crossOrigin);const s=r.load(e,n,void 0,i);return t&&(s.mapping=t),s},Qn.loadCompressedTexture=function(){console.error("THREE.ImageUtils.loadCompressedTexture has been removed. Use THREE.DDSLoader instead.")},Qn.loadCompressedTextureCube=function(){console.error("THREE.ImageUtils.loadCompressedTextureCube has been removed. Use THREE.DDSLoader instead.")};const Lf={createMultiMaterialObject:function(){console.error("THREE.SceneUtils has been moved to /examples/jsm/utils/SceneUtils.js")},detach:function(){console.error("THREE.SceneUtils has been moved to /examples/jsm/utils/SceneUtils.js")},attach:function(){console.error("THREE.SceneUtils has been moved to /examples/jsm/utils/SceneUtils.js")}};function Cf(){console.error("THREE.LensFlare has been moved to /examples/jsm/objects/Lensflare.js")}"undefined"!=typeof __THREE_DEVTOOLS__&&__THREE_DEVTOOLS__.dispatchEvent(new CustomEvent("register",{detail:{revision:i}})),"undefined"!=typeof window&&(window.__THREE__?console.warn("WARNING: Multiple instances of Three.js being imported."):window.__THREE__=i)},973:(e,t,n)=>{"use strict";n.d(t,{eW:()=>T,oe:()=>x});var i=n(212);class r{static addMaterial(e,t,n,i,r){let s;t.name=n,i?(e[n]=t,r&&console.info('Material with name "'+n+'" was forcefully overridden.')):(s=e[n],s?s.uuid!=s.uuid&&r&&console.log('Same material name "'+s.name+'" different uuid ['+s.uuid+"|"+t.uuid+"]"):(e[n]=t,r&&console.info('Material with name "'+n+'" was added.')))}static getMaterialsJSON(e){const t={};let n;for(const i in e)n=e[i],"function"==typeof n.toJSON&&(t[i]=n.toJSON());return t}static cloneMaterial(e,t,n){let i;if(t){let s=t.materialNameOrg;s=null!=s?s:"";const a=e[s];a?(i=a.clone(),Object.assign(i,t.materialProperties),r.addMaterial(e,i,t.materialProperties.name,!0)):n&&console.info('Requested material "'+s+'" is not available!')}return i}}class s{static buildThreeConst(){return"const EventDispatcher = THREE.EventDispatcher;\\nconst BufferGeometry = THREE.BufferGeometry;\\nconst BufferAttribute = THREE.BufferAttribute;\\nconst Box3 = THREE.Box3;\\nconst Sphere = THREE.Sphere;\\nconst Texture = THREE.Texture;\\nconst MaterialLoader = THREE.MaterialLoader;\\n"}static buildUglifiedThreeMapping(){return s.buildUglifiedNameAssignment((function(){return i.BufferGeometry}),"BufferGeometry",/_BufferGeometry/,!1)+s.buildUglifiedNameAssignment((function(){return i.BufferAttribute}),"BufferAttribute",/_BufferAttribute/,!1)+s.buildUglifiedNameAssignment((function(){return i.Box3}),"Box3",/_Box3/,!1)+s.buildUglifiedNameAssignment((function(){return i.Sphere}),"Sphere",/_Sphere/,!1)+s.buildUglifiedNameAssignment((function(){return i.Texture}),"Texture",/_Texture/,!1)+s.buildUglifiedNameAssignment((function(){return i.MaterialLoader}),"MaterialLoader",/_MaterialLoader/,!1)}static buildUglifiedThreeWtmMapping(){return s.buildUglifiedNameAssignment((function(){return a}),"DataTransport",/_DataTransport/,!0)+s.buildUglifiedNameAssignment((function(){return l}),"GeometryTransport",/_GeometryTransport/,!0)+s.buildUglifiedNameAssignment((function(){return c}),"MeshTransport",/_MeshTransport/,!0)+s.buildUglifiedNameAssignment((function(){return o}),"MaterialsTransport",/_MaterialsTransport/,!0)+s.buildUglifiedNameAssignment((function(){return r}),"MaterialUtils",/_MaterialUtils/,!0)}static buildUglifiedNameAssignment(e,t,n,i){let r=e.toString();r=r.replace(n,"").replace(/[\\r\\n]+/gm,""),r=r.replace(/.*return/,"").replace(/\\}/,"").replace(/;/gm,"");const s=r.trim();let a="";return s!==t&&(a="const "+(i?t:s)+" = "+(i?s:t)+";\\n"),a}}class a{constructor(e,t){this.main={cmd:void 0!==e?e:"unknown",id:void 0!==t?t:0,type:"DataTransport",progress:0,buffers:{},params:{}},this.transferables=[]}loadData(e){return this.main.cmd=e.cmd,this.main.id=e.id,this.main.type="DataTransport",this.setProgress(e.progress),this.setParams(e.params),e.buffers&&Object.entries(e.buffers).forEach((([e,t])=>{this.main.buffers[e]=t})),this}getCmd(){return this.main.cmd}getId(){return this.main.id}setParams(e){return null!=e&&(this.main.params=e),this}getParams(){return this.main.params}setProgress(e){return this.main.progress=e,this}addBuffer(e,t){return this.main.buffers[e]=t,this}getBuffer(e){return this.main.buffers[e]}package(e){for(let t of Object.values(this.main.buffers))if(null!=t){const n=e?t.slice(0):t;this.transferables.push(n)}return this}getMain(){return this.main}getTransferables(){return this.transferables}postMessage(e){return e.postMessage(this.main,this.transferables),this}}class o extends a{constructor(e,t){super(e,t),this.main.type="MaterialsTransport",this.main.materials={},this.main.multiMaterialNames={},this.main.cloneInstructions=[]}loadData(e){super.loadData(e),this.main.type="MaterialsTransport",Object.assign(this.main,e);const t=new i.MaterialLoader;return Object.entries(this.main.materials).forEach((([e,n])=>{this.main.materials[e]=t.parse(n)})),this}_cleanMaterial(e){return Object.entries(e).forEach((([t,n])=>{(n instanceof i.Texture||null===n)&&(e[t]=void 0)})),e}addBuffer(e,t){return super.addBuffer(e,t),this}setParams(e){return super.setParams(e),this}setMaterials(e){return null!=e&&Object.keys(e).length>0&&(this.main.materials=e),this}getMaterials(){return this.main.materials}cleanMaterials(){let e,t={};for(let n of Object.values(this.main.materials))"function"==typeof n.clone&&(e=n.clone(),t[e.name]=this._cleanMaterial(e));return this.setMaterials(t),this}package(e){return super.package(e),this.main.materials=r.getMaterialsJSON(this.main.materials),this}hasMultiMaterial(){return Object.keys(this.main.multiMaterialNames).length>0}getSingleMaterial(){return Object.keys(this.main.materials).length>0?Object.entries(this.main.materials)[0][1]:null}processMaterialTransport(e,t){for(let n=0;n{n[t]=e[i]}));else{const t=this.getSingleMaterial();null!==t&&(n=e[t.name],n||(n=t))}return n}}class l extends a{constructor(e,t){super(e,t),this.main.type="GeometryTransport",this.main.geometryType=0,this.main.geometry={},this.main.bufferGeometry=null}loadData(e){return super.loadData(e),this.main.type="GeometryTransport",this.setGeometry(e.geometry,e.geometryType)}getGeometryType(){return this.main.geometryType}setParams(e){return super.setParams(e),this}setGeometry(e,t){return this.main.geometry=e,this.main.geometryType=t,e instanceof i.BufferGeometry&&(this.main.bufferGeometry=e),this}package(e){super.package(e);const t=this.main.geometry.getAttribute("position"),n=this.main.geometry.getAttribute("normal"),i=this.main.geometry.getAttribute("uv"),r=this.main.geometry.getAttribute("color"),s=this.main.geometry.getAttribute("skinIndex"),a=this.main.geometry.getAttribute("skinWeight"),o=this.main.geometry.getIndex();return this._addBufferAttributeToTransferable(t,e),this._addBufferAttributeToTransferable(n,e),this._addBufferAttributeToTransferable(i,e),this._addBufferAttributeToTransferable(r,e),this._addBufferAttributeToTransferable(s,e),this._addBufferAttributeToTransferable(a,e),this._addBufferAttributeToTransferable(o,e),this}reconstruct(e){if(this.main.bufferGeometry instanceof i.BufferGeometry)return this;this.main.bufferGeometry=new i.BufferGeometry;const t=this.main.geometry;this._assignAttribute(t.attributes.position,"position",e),this._assignAttribute(t.attributes.normal,"normal",e),this._assignAttribute(t.attributes.uv,"uv",e),this._assignAttribute(t.attributes.color,"color",e),this._assignAttribute(t.attributes.skinIndex,"skinIndex",e),this._assignAttribute(t.attributes.skinWeight,"skinWeight",e);const n=t.index;if(null!=n){const t=e?n.array.slice(0):n.array;this.main.bufferGeometry.setIndex(new i.BufferAttribute(t,n.itemSize,n.normalized))}const r=t.boundingBox;null!==r&&(this.main.bufferGeometry.boundingBox=Object.assign(new i.Box3,r));const s=t.boundingSphere;return null!==s&&(this.main.bufferGeometry.boundingSphere=Object.assign(new i.Sphere,s)),this.main.bufferGeometry.uuid=t.uuid,this.main.bufferGeometry.name=t.name,this.main.bufferGeometry.type=t.type,this.main.bufferGeometry.groups=t.groups,this.main.bufferGeometry.drawRange=t.drawRange,this.main.bufferGeometry.userData=t.userData,this}getBufferGeometry(){return this.main.bufferGeometry}_addBufferAttributeToTransferable(e,t){if(null!=e){const n=t?e.array.slice(0):e.array;this.transferables.push(n.buffer)}return this}_assignAttribute(e,t,n){if(e){const r=n?e.array.slice(0):e.array;this.main.bufferGeometry.setAttribute(t,new i.BufferAttribute(r,e.itemSize,e.normalized))}return this}}class c extends l{constructor(e,t){super(e,t),this.main.type="MeshTransport",this.main.materialsTransport=new o}loadData(e){return super.loadData(e),this.main.type="MeshTransport",this.main.meshName=e.meshName,this.main.materialsTransport=(new o).loadData(e.materialsTransport.main),this}setParams(e){return super.setParams(e),this}setMaterialsTransport(e){return e instanceof o&&(this.main.materialsTransport=e),this}getMaterialsTransport(){return this.main.materialsTransport}setMesh(e,t){return this.main.meshName=e.name,super.setGeometry(e.geometry,t),this}package(e){return super.package(e),null!==this.main.materialsTransport&&this.main.materialsTransport.package(e),this}reconstruct(e){return super.reconstruct(e),this}}class h{static serializePrototype(e,t,n,i){let r,s=[],a="";i?(a=e.toString()+"\\n\\n",r=t):r=e;for(let e in r){let t=r[e],n=t.toString();"function"==typeof t&&s.push("\\t"+e+": "+n+",\\n\\n")}a+=n+(i?".prototype":"")+" = {\\n\\n";for(let e=0;e0){let n;for(const i in e)n=e[i],r.addMaterial(this.materials,n,i,!0===t)}}getMaterials(){return this.materials}getMaterial(e){return this.materials[e]}clearMaterials(){this.materials={}}}class p{static comRouting(e,t,n,i,r){let s=t.data;"init"===s.cmd?null!=n?n[i](e,s.workerId,s.config):i(e,s.workerId,s.config):"execute"===s.cmd&&(null!=n?n[r](e,s.workerId,s.config):r(e,s.workerId,s.config))}}class f{constructor(e){this.taskTypes=new Map,this.verbose=!1,this.maxParallelExecutions=e||4,this.actualExecutionCount=0,this.storedExecutions=[],this.teardown=!1}setVerbose(e){return this.verbose=e,this}setMaxParallelExecutions(e){return this.maxParallelExecutions=e,this}getMaxParallelExecutions(){return this.maxParallelExecutions}supportsTaskType(e){return this.taskTypes.has(e)}registerTaskType(e,t,n,i,r,s){let a=!this.supportsTaskType(e);if(a){let a=new m(e,this.maxParallelExecutions,r,this.verbose);a.setFunctions(t,n,i),a.setDependencyDescriptions(s),this.taskTypes.set(e,a)}return a}registerTaskTypeModule(e,t){let n=!this.supportsTaskType(e);if(n){let n=new m(e,this.maxParallelExecutions,!1,this.verbose);n.setWorkerModule(t),this.taskTypes.set(e,n)}return n}async initTaskType(e,t,n){let i=this.taskTypes.get(e);if(i)if(i.status.initStarted)for(;!i.status.initComplete;)await this._wait(10);else i.status.initStarted=!0,i.isWorkerModule()?await i.createWorkerModules().then((()=>i.initWorkers(t,n))).then((()=>i.status.initComplete=!0)).catch((e=>console.error(e))):await i.loadDependencies().then((()=>i.createWorkers())).then((()=>i.initWorkers(t,n))).then((()=>i.status.initComplete=!0)).catch((e=>console.error(e)))}async _wait(e){return new Promise((t=>{setTimeout(t,e)}))}async enqueueForExecution(e,t,n,i){return new Promise(((r,s)=>{this.storedExecutions.push(new g(e,t,n,r,s,i)),this._depleteExecutions()}))}_depleteExecutions(){let e=0;for(;this.actualExecutionCount{i.onmessage=n=>{"assetAvailable"===n.data.cmd?t.assetAvailableFunction instanceof Function&&t.assetAvailableFunction(n.data):e(n)},i.onerror=n,i.postMessage({cmd:"execute",workerId:i.getId(),config:t.config},t.transferables)})).then((e=>{n.returnAvailableTask(i),t.resolve(e.data),this.actualExecutionCount--,this._depleteExecutions()})).catch((e=>{t.reject("Execution error: "+e)}))):e++}}dispose(){this.teardown=!0;for(let e of this.taskTypes.values())e.dispose();return this}}class m{constructor(e,t,n,i){this.taskType=e,this.fallback=n,this.verbose=!0===i,this.initialised=!1,this.functions={init:null,execute:null,comRouting:null,dependencies:{descriptions:[],code:[]},workerModuleUrl:null},this.workers={code:[],instances:new Array(t),available:[]},this.status={initStarted:!1,initComplete:!1}}getTaskType(){return this.taskType}setFunctions(e,t,n){this.functions.init=e,this.functions.execute=t,this.functions.comRouting=n,void 0!==this.functions.comRouting&&null!==this.functions.comRouting||(this.functions.comRouting=p.comRouting),this._addWorkerCode("init",this.functions.init.toString()),this._addWorkerCode("execute",this.functions.execute.toString()),this._addWorkerCode("comRouting",this.functions.comRouting.toString()),this.workers.code.push('self.addEventListener( "message", message => comRouting( self, message, null, init, execute ), false );')}_addWorkerCode(e,t){t.startsWith("function")?this.workers.code.push("const "+e+" = "+t+";\\n\\n"):this.workers.code.push("function "+t+";\\n\\n")}setDependencyDescriptions(e){e&&e.forEach((e=>{this.functions.dependencies.descriptions.push(e)}))}setWorkerModule(e){this.functions.workerModuleUrl=new URL(e,window.location.href)}isWorkerModule(){return null!==this.functions.workerModuleUrl}async loadDependencies(){let e=[],t=new i.FileLoader;t.setResponseType("arraybuffer");for(let n of this.functions.dependencies.descriptions){if(n.url){let i=new URL(n.url,window.location.href);e.push(t.loadAsync(i.href,(e=>{this.verbose&&console.log(e)})))}n.code&&e.push(new Promise((e=>e(n.code))))}this.verbose&&console.log("Task: "+this.getTaskType()+": Waiting for completion of loading of all dependencies."),this.functions.dependencies.code=await Promise.all(e)}async createWorkers(){let e;if(this.fallback)for(let t=0;t{let s;if(i.onmessage=e=>{this.verbose&&console.log("Init Complete: "+e.data.id),n(e)},i.onerror=r,t){s=[];for(let e=0;e0}returnAvailableTask(e){this.workers.available.push(e)}dispose(){for(let e of this.workers.instances)e.terminate()}}class g{constructor(e,t,n,i,r,s){this.taskType=e,this.config=t,this.assetAvailableFunction=n,this.resolve=i,this.reject=r,this.transferables=s}}class v extends Worker{constructor(e,t,n){super(t,n),this.id=e}getId(){return this.id}}class y{constructor(e,t,n){this.id=e,this.functions={init:t,execute:n}}getId(){return this.id}postMessage(e,t){let n=this,i={postMessage:function(e){n.onmessage({data:e})}};p.comRouting(i,{data:e},null,n.functions.init,n.functions.execute)}terminate(){}}function _(e,t,n){return t in e?Object.defineProperty(e,t,{value:n,enumerable:!0,configurable:!0,writable:!0}):e[t]=n,e}class x extends i.Loader{constructor(e){super(e),this.parser=new b,this.materialStore=new d(!0),this.parser.materials=this.materialStore.getMaterials()}setLogging(e,t){return this.parser.logging.enabled=!0===e,this.parser.logging.debug=!0===t,this}setMaterialPerSmoothingGroup(e){return this.parser.aterialPerSmoothingGroup=!0===e,this}setUseOAsMesh(e){return this.parser.useOAsMesh=!0===e,this}setUseIndices(e){return this.parser.useIndices=!0===e,this}setDisregardNormals(e){return this.parser.disregardNormals=!0===e,this}setModelName(e){return e&&(this.parser.modelName=e),this}getModelName(){return this.parser.modelName}setBaseObject3d(e){return this.parser.baseObject3d=null==e?this.parser.baseObject3d:e,this}setMaterials(e){return this.materialStore.addMaterials(e,!1),this.parser.materials=this.materialStore.getMaterials(),this}setCallbackOnProgress(e){return null!=e&&e instanceof Function&&(this.parser.callbacks.onProgress=e),this}setCallbackOnError(e){return null!=e&&e instanceof Function&&(this.parser.callbacks.onError=e),this}setCallbackOnLoad(e){return null!=e&&e instanceof Function&&(this.parser.callbacks.onLoad=e),this}setCallbackOnMeshAlter(e){return null!=e&&e instanceof Function&&(this.parser.callbacks.onMeshAlter=e),this}load(e,t,n,r,s){if(!(null!=t&&t instanceof Function)){const e="onLoad is not a function! Aborting...";throw this.parser._onError(e),e}this.setCallbackOnLoad(t);const a=this;null!=r&&r instanceof Function||(r=function(e){let t=e;e.currentTarget&&null!==e.currentTarget.statusText&&(t="Error occurred while downloading!\\nurl: "+e.currentTarget.responseURL+"\\nstatus: "+e.currentTarget.statusText),a.parser._onError(t)}),e||r("An invalid url was provided. Unable to continue!");const o=new URL(e,window.location.href).href;let l=o;const c=o.split("/");if(c.length>2){l=c[c.length-1];let e=c.slice(0,c.length-1).join("/")+"/";void 0!==e&&(this.path=e)}if(null==n||!(n instanceof Function)){let t=0,i=0;n=function(n){if(n.lengthComputable&&(i=n.loaded/n.total,i>t)){t=i;const n='Download of "'+e+'": '+(100*i).toFixed(2)+"%";a.parser._onProgress("progressLoad",n,i)}}}this.setCallbackOnMeshAlter(s);const h=new i.FileLoader(this.manager);h.setPath(this.path||this.resourcePath),h.setResponseType("arraybuffer"),h.load(l,(function(e){a.parse(e)}),n,r)}parse(e){if(this.parser.logging.enabled&&console.info("Using OBJLoader2 version: "+x.OBJLOADER2_VERSION),null==e)throw"Provided content is not a valid ArrayBuffer or String. Unable to continue parsing";return this.parser.logging.enabled&&console.time("OBJLoader parse: "+this.modelName),e instanceof ArrayBuffer||e instanceof Uint8Array?(this.parser.logging.enabled&&console.info("Parsing arrayBuffer..."),this.parser._execute(e)):"string"==typeof e||e instanceof String?(this.parser.logging.enabled&&console.info("Parsing text..."),this.parser._executeLegacy(e)):this.parser._onError("Provided content was neither of type String nor Uint8Array! Aborting..."),this.parser.logging.enabled&&console.timeEnd("OBJLoader parse: "+this.modelName),this.parser.baseObject3d}}_(x,"OBJLOADER2_VERSION","4.0.0-dev");class b{constructor(){this.logging={enabled:!1,debug:!1},this.usedBefore=!1,this._init(),this.callbacks={onLoad:null,onError:null,onProgress:null,onMeshAlter:null}}_init(){this.contentRef=null,this.legacyMode=!1,this.materials={},this.baseObject3d=new i.Object3D,this.modelName="noname",this.materialPerSmoothingGroup=!1,this.useOAsMesh=!1,this.useIndices=!1,this.disregardNormals=!1,this.vertices=[],this.colors=[],this.normals=[],this.uvs=[],this.objectId=0,this.rawMesh={objectName:"",groupName:"",activeMtlName:"",mtllibName:"",faceType:-1,subGroups:[],subGroupInUse:null,smoothingGroup:{splitMaterials:!1,normalized:-1,real:-1},counts:{doubleIndicesCount:0,faceCount:0,mtlCount:0,smoothingGroupCount:0}},this.inputObjectCount=1,this.outputObjectCount=1,this.globalCounts={vertices:0,faces:0,doubleIndicesCount:0,lineByte:0,currentByte:0,totalBytes:0}}_resetRawMesh(){this.rawMesh.subGroups=[],this.rawMesh.subGroupInUse=null,this.rawMesh.smoothingGroup.normalized=-1,this.rawMesh.smoothingGroup.real=-1,this._pushSmoothingGroup(1),this.rawMesh.counts.doubleIndicesCount=0,this.rawMesh.counts.faceCount=0,this.rawMesh.counts.mtlCount=0,this.rawMesh.counts.smoothingGroupCount=0}_configure(){if(this.usedBefore=!0,this._pushSmoothingGroup(1),this.logging.enabled){const e=Object.keys(this.materials);let t="OBJLoader2 Parser configuration:"+(e.length>0?"\\n\\tmaterialNames:\\n\\t\\t- "+e.join("\\n\\t\\t- "):"\\n\\tmaterialNames: None")+"\\n\\tmaterialPerSmoothingGroup: "+this.materialPerSmoothingGroup+"\\n\\tuseOAsMesh: "+this.useOAsMesh+"\\n\\tuseIndices: "+this.useIndices+"\\n\\tdisregardNormals: "+this.disregardNormals;null!==this.callbacks.onProgress&&(t+="\\n\\tcallbacks.onProgress: "+this.callbacks.onProgress.name),null!==this.callbacks.onError&&(t+="\\n\\tcallbacks.onError: "+this.callbacks.onError.name),null!==this.callbacks.onMeshAlter&&(t+="\\n\\tcallbacks.onMeshAlter: "+this.callbacks.onMeshAlter.name),null!==this.callbacks.onLoad&&(t+="\\n\\tcallbacks.onLoad: "+this.callbacks.onLoad.name),console.info(t)}}_execute(e){this.logging.enabled&&console.time("OBJLoader2Parser.execute"),this._configure();const t=new Uint8Array(e);this.contentRef=t;const n=t.byteLength;this.globalCounts.totalBytes=n;const i=new Array(128);let r,s=0,a=0,o="",l=0;for(;l0&&(i[s++]=o),o="";break;case 47:o.length>0&&(i[s++]=o),a++,o="";break;case 10:this._processLine(i,s,a,o,l),o="",s=0,a=0;break;case 13:break;default:o+=String.fromCharCode(r)}this._processLine(i,s,a,o,l),this._finalizeParsing(),this.logging.enabled&&console.timeEnd("OBJLoader2Parser.execute")}_executeLegacy(e){this.logging.enabled&&console.time("OBJLoader2Parser.executeLegacy"),this._configure(),this.legacyMode=!0,this.contentRef=e;const t=e.length;this.globalCounts.totalBytes=t;const n=new Array(128);let i,r=0,s=0,a="",o=0;for(;o0&&(n[r++]=a),a="";break;case"/":a.length>0&&(n[r++]=a),s++,a="";break;case"\\n":this._processLine(n,r,s,a,o),a="",r=0,s=0;break;case"\\r":break;default:a+=i}this._processLine(n,r,a,s),this._finalizeParsing(),this.logging.enabled&&console.timeEnd("OBJLoader2Parser.executeLegacy")}_processLine(e,t,n,i,r){if(this.globalCounts.lineByte=this.globalCounts.currentByte,this.globalCounts.currentByte=r,t<1)return;i.length>0&&(e[t++]=i);const s=function(e,t,n,i){let r="";if(i>n){let s;if(t)for(s=n;s4&&(this.colors.push(parseFloat(e[4])),this.colors.push(parseFloat(e[5])),this.colors.push(parseFloat(e[6])));break;case"vt":this.uvs.push(parseFloat(e[1])),this.uvs.push(parseFloat(e[2]));break;case"vn":this.normals.push(parseFloat(e[1])),this.normals.push(parseFloat(e[2])),this.normals.push(parseFloat(e[3]));break;case"f":if(a=t-1,0===n)for(this._checkFaceType(0),l=2,o=a;l0?s-1:s+r.vertices.length/3),o=r.colors.length>0?a:null;const l=i.vertices;if(l.push(r.vertices[a++]),l.push(r.vertices[a++]),l.push(r.vertices[a]),null!==o){const e=i.colors;e.push(r.colors[o++]),e.push(r.colors[o++]),e.push(r.colors[o])}if(t){const e=parseInt(t);let n=2*(e>0?e-1:e+r.uvs.length/2);const s=i.uvs;s.push(r.uvs[n++]),s.push(r.uvs[n])}if(n&&!r.disregardNormals){const e=parseInt(n);let t=3*(e>0?e-1:e+r.normals.length/3);const s=i.normals;s.push(r.normals[t++]),s.push(r.normals[t++]),s.push(r.normals[t])}};if(this.useIndices){this.disregardNormals&&(n=void 0);const r=e+(t?"_"+t:"_n")+(n?"_"+n:"_n");let a=i.indexMappings[r];null==a?(a=this.rawMesh.subGroupInUse.vertices.length/3,s(),i.indexMappings[r]=a,i.indexMappingsCount++):this.rawMesh.counts.doubleIndicesCount++,i.indices.push(a)}else s();this.rawMesh.counts.faceCount++}_createRawMeshReport(e){return"Input Object number: "+e+"\\n\\tObject name: "+this.rawMesh.objectName+"\\n\\tGroup name: "+this.rawMesh.groupName+"\\n\\tMtllib name: "+this.rawMesh.mtllibName+"\\n\\tVertex count: "+this.vertices.length/3+"\\n\\tNormal count: "+this.normals.length/3+"\\n\\tUV count: "+this.uvs.length/2+"\\n\\tSmoothingGroup count: "+this.rawMesh.counts.smoothingGroupCount+"\\n\\tMaterial count: "+this.rawMesh.counts.mtlCount+"\\n\\tReal MeshOutputGroup count: "+this.rawMesh.subGroups.length}_finalizeRawMesh(){const e=[];let t,n,i=0,r=0,s=0,a=0,o=0,l=0;for(const c in this.rawMesh.subGroups)if(t=this.rawMesh.subGroups[c],t.vertices.length>0){if(n=t.indices,n.length>0&&r>0)for(let e=0;e0&&(c={name:""!==this.rawMesh.groupName?this.rawMesh.groupName:this.rawMesh.objectName,subGroups:e,absoluteVertexCount:i,absoluteIndexCount:s,absoluteColorCount:a,absoluteNormalCount:o,absoluteUvCount:l,faceCount:this.rawMesh.counts.faceCount,doubleIndicesCount:this.rawMesh.counts.doubleIndicesCount}),c}_processCompletedMesh(){const e=this._finalizeRawMesh(),t=null!==e;if(t){this.colors.length>0&&this.colors.length!==this.vertices.length&&this._onError("Vertex Colors were detected, but vertex count and color count do not match!"),this.logging.enabled&&this.logging.debug&&console.debug(this._createRawMeshReport(this.inputObjectCount)),this.inputObjectCount++,this._buildMesh(e);const t=this.globalCounts.currentByte/this.globalCounts.totalBytes;this._onProgress("Completed [o: "+this.rawMesh.objectName+" g:"+this.rawMesh.groupName+"] Total progress: "+(100*t).toFixed(2)+"%"),this._resetRawMesh()}return t}_buildMesh(e){const t=e.subGroups;this.globalCounts.vertices+=e.absoluteVertexCount/3,this.globalCounts.faces+=e.faceCount,this.globalCounts.doubleIndicesCount+=e.doubleIndicesCount;const n=new i.BufferGeometry,s=new Float32Array(e.absoluteVertexCount),a=e.absoluteIndexCount>0?new Uint32Array(e.absoluteIndexCount):null,o=e.absoluteColorCount>0?new Float32Array(e.absoluteColorCount):null,l=e.absoluteNormalCount>0?new Float32Array(e.absoluteNormalCount):null,c=e.absoluteUvCount>0?new Float32Array(e.absoluteUvCount):null;let h;n.setAttribute("position",new i.BufferAttribute(s,3,!1)),null!=l&&n.setAttribute("normal",new i.BufferAttribute(l,3,!1)),null!=c&&n.setAttribute("uv",new i.BufferAttribute(c,2,!1)),null!=o&&n.setAttribute("color",new i.BufferAttribute(o,3,!1)),null!==a&&n.setIndex(new i.BufferAttribute(a,1,!1));let u=0,d=0,p=0,f=0,m=0,g=0,v=0;const y=t.length>1,_=[],x=null!==o;let b,w,M,T,E,S=0;const A={cloneInstructions:[],multiMaterialNames:{},modelName:this.modelName,progress:this.globalCounts.currentByte/this.globalCounts.totalBytes,geometryType:this.rawMesh.faceType<4?0:6===this.rawMesh.faceType?2:1,objectId:this.objectId};for(const e in t)if(t.hasOwnProperty(e)){if(h=t[e],E=h.materialName,b=0===h.smoothingGroup,this.rawMesh.faceType<4?(T=E,x&&(T+="_vertexColor"),b&&(T+="_flat")):T=6===this.rawMesh.faceType?"defaultPointMaterial":"defaultLineMaterial",w=this.materials[E],M=this.materials[T],null==w&&null==M&&(T=x?"defaultVertexColorMaterial":"defaultMaterial",M=this.materials[T],this.logging.enabled&&console.info('object_group "'+h.objectName+"_"+h.groupName+'" was defined with unresolvable material "'+E+'"! Assigning "'+T+'".')),null==M){const e={materialNameOrg:E,materialProperties:{name:T,vertexColors:x?2:0,flatShading:b}};M=r.cloneMaterial(this.materials,e,this.logging.enabled&&this.logging.debug),A.cloneInstructions.push(e)}if(y&&(v=this.useIndices?h.indices.length:h.vertices.length/3,n.addGroup(g,v,S),M=this.materials[T],_[S]=M,A.multiMaterialNames[S]=M.name,g+=v,S++),s.set(h.vertices,u),u+=h.vertices.length,null!==a&&(a.set(h.indices,d),d+=h.indices.length),null!==o&&(o.set(h.colors,p),p+=h.colors.length),null!==l&&(l.set(h.normals,f),f+=h.normals.length),null!==c&&(c.set(h.uvs,m),m+=h.uvs.length),this.logging.enabled&&this.logging.debug){let e="";S>0&&(e="\\n\\t\\tmaterialIndex: "+S);const t="\\tOutput Object no.: "+this.outputObjectCount+"\\n\\t\\tgroupName: "+h.groupName+"\\n\\t\\tIndex: "+h.index+"\\n\\t\\tfaceType: "+this.rawMesh.faceType+"\\n\\t\\tmaterialName: "+h.materialName+"\\n\\t\\tsmoothingGroup: "+h.smoothingGroup+e+"\\n\\t\\tobjectName: "+h.objectName+"\\n\\t\\t#vertices: "+h.vertices.length/3+"\\n\\t\\t#indices: "+h.indices.length+"\\n\\t\\t#colors: "+h.colors.length/3+"\\n\\t\\t#uvs: "+h.uvs.length/2+"\\n\\t\\t#normals: "+h.normals.length/3;console.debug(t)}}let L;this.outputObjectCount++,null==n.getAttribute("normal")&&n.computeVertexNormals();const C=y?_:M;L=0===A.geometryType?new i.Mesh(n,C):1===A.geometryType?new i.LineSegments(n,C):new i.Points(n,C),L.name=e.name,this._onAssetAvailable(L,A)}_finalizeParsing(){if(this.logging.enabled&&console.info("Global output object count: "+this.outputObjectCount),this._processCompletedMesh()&&this.logging.enabled){const e="Overall counts: \\n\\tVertices: "+this.globalCounts.vertices+"\\n\\tFaces: "+this.globalCounts.faces+"\\n\\tMultiple definitions: "+this.globalCounts.doubleIndicesCount;console.info(e)}this._onLoad()}_onProgress(e){if(null!==this.callbacks.onProgress)this.callbacks.onProgress(e);else{const t=e||"";this.logging.enabled&&this.logging.debug&&console.log(t)}}_onError(e){null!==this.callbacks.onError?this.callbacks.onError(e):this.logging.enabled&&this.logging.debug&&console.error(e)}_onAssetAvailable(e,t){this._onMeshAlter(e,t),this.baseObject3d.add(e)}_onMeshAlter(e){null!==this.callbacks.onMeshAlter&&this.callbacks.onMeshAlter(e,this.baseObject3d)}_onLoad(){null!==this.callbacks.onLoad&&this.callbacks.onLoad(this.baseObject3d,this.objectId)}static buildUglifiedMapping(){return s.buildUglifiedNameAssignment((function(){return b}),"OBJLoader2Parser",/_OBJLoader2Parser/,!0)}}class w{static buildStandardWorkerDependencies(e){return[{url:e},{code:s.buildThreeConst()},{code:w.buildThreeExtraConst()},{code:"\\n\\n"},{code:s.buildUglifiedThreeMapping()},{code:w.buildUglifiedThreeExtraMapping()},{code:"\\n\\n"},{code:h.serializeClass(a)},{code:h.serializeClass(l)},{code:h.serializeClass(c)},{code:h.serializeClass(o)},{code:h.serializeClass(r)},{code:h.serializeClass(b)},{code:h.serializeClass(u)},{code:s.buildUglifiedThreeWtmMapping()},{code:"\\n\\n"},{code:b.buildUglifiedMapping()},{code:"\\n\\n"}]}static buildThreeExtraConst(){return"const MathUtils = THREE.MathUtils;\\nconst Material = THREE.Material;\\nconst Object3D = THREE.Object3D;\\nconst Mesh = THREE.Mesh;\\n"}static buildUglifiedThreeExtraMapping(){return s.buildUglifiedNameAssignment((function(){return i.MathUtils}),"MathUtils",/_MathUtils/,!1)+s.buildUglifiedNameAssignment((function(){return i.Material}),"Material",/_Material/,!1)+s.buildUglifiedNameAssignment((function(){return i.Object3D}),"Object3D",/_Object3D/,!1)+s.buildUglifiedNameAssignment((function(){return i.Mesh}),"Mesh",/_Mesh/,!1)}static init(e,t,n){const i=(new o).loadData(n);e.obj2={parser:new b,buffer:null,materials:i.getMaterials()},e.obj2.parser._onMeshAlter=(t,n)=>{const i=new o;if(i.main.multiMaterialNames=n.multiMaterialNames,0===Object.keys(i.main.multiMaterialNames).length){const e=t.material;r.addMaterial(i.main.materials,e,e.name,!1,!1)}i.main.cloneInstructions=n.cloneInstructions,i.cleanMaterials(),new c("assetAvailable",n.objectId).setProgress(n.progress).setParams({modelName:n.modelName}).setMesh(t,n.geometryType).setMaterialsTransport(i).postMessage(e)},e.obj2.parser.callbacks.onLoad=()=>{new a("execComplete",e.obj2.parser.objectId).postMessage(e)},e.obj2.parser.callbacks.onProgress=t=>{e.obj2.parser.logging.debug&&console.debug("WorkerRunner: progress: "+t)},u.applyProperties(e.obj2.parser,i.getParams(),!1);const s=i.getBuffer("modelData");null!=s&&(e.obj2.buffer=s),new a("init",t).postMessage(e)}static execute(e,t,n){e.obj2.parser.usedBefore&&e.obj2.parser._init(),e.obj2.parser.materials=e.obj2.materials;const i=(new a).loadData(n);u.applyProperties(e.obj2.parser,i.getParams(),!1);const r=i.getBuffer("modelData");null!=r&&(e.obj2.buffer=r),e.obj2.buffer&&(e.obj2.parser.objectId=i.getId(),e.obj2.parser._execute(e.obj2.buffer))}}class M extends x{constructor(e){super(e),this.preferJsmWorker=!1,this.urls={jsmWorker:new URL(M.DEFAULT_JSM_WORKER_PATH,window.location.href),threejs:new URL(M.DEFAULT_JSM_THREEJS_PATH,window.location.href)},this.workerTaskManager=null,this.taskName="tmOBJLoader2"}setWorkerTaskManager(e,t){return this.workerTaskManager=e,t&&(this.taskName=t),this}setJsmWorker(e,t){if(this.preferJsmWorker=!0===e,!(null!=t&&t instanceof URL))throw"The url to the jsm worker is not valid. Aborting...";return this.urls.jsmWorker=t,this}setThreejsLocation(e){if(!(null!=e&&e instanceof URL))throw"The url to the jsm worker is not valid. Aborting...";return this.urls.threejs=e,this}setTerminateWorkerOnLoad(e){return this.terminateWorkerOnLoad=!0===e,this}async _buildWorkerCode(e){null!==this.workerTaskManager&&this.workerTaskManager instanceof f||(this.parser.logging.debug&&console.log("Needed to create new WorkerTaskManager"),this.workerTaskManager=new f(1),this.workerTaskManager.setVerbose(this.parser.logging.enabled&&this.parser.logging.debug)),this.workerTaskManager.supportsTaskType(this.taskName)||(this.preferJsmWorker?this.workerTaskManager.registerTaskTypeModule(this.taskName,this.urls.jsmWorker):this.workerTaskManager.registerTaskType(this.taskName,w.init,w.execute,null,!1,w.buildStandardWorkerDependencies(this.urls.threejs)),await this.workerTaskManager.initTaskType(this.taskName,e.getMain()))}load(e,t,n,i,r){const s=this;x.prototype.load.call(this,e,(function(e,n){"OBJLoader2ParallelDummy"===e.name?s.parser.logging.enabled&&s.parser.logging.debug&&console.debug("Received dummy answer from OBJLoader2Parallel#parse"):t(e,n)}),n,i,r)}parse(e){this.parser.logging.enabled&&console.info("Using OBJLoader2Parallel version: "+M.OBJLOADER2_PARALLEL_VERSION);const t=(new a).setParams({logging:{enabled:this.parser.logging.enabled,debug:this.parser.logging.debug}});this._buildWorkerCode(t).then((()=>{this.parser.logging.debug&&console.log("OBJLoader2Parallel init was performed"),this._executeWorkerParse(e)})).catch((e=>console.error(e)));let n=new i.Object3D;return n.name="OBJLoader2ParallelDummy",n}_executeWorkerParse(e){const t=new a("execute",Math.floor(Math.random()*Math.floor(65536)));t.setParams({modelName:this.parser.modelName,useIndices:this.parser.useIndices,disregardNormals:this.parser.disregardNormals,materialPerSmoothingGroup:this.parser.materialPerSmoothingGroup,useOAsMesh:this.parser.useOAsMesh,materials:r.getMaterialsJSON(this.materialStore.getMaterials())}).addBuffer("modelData",e).package(!1),this.workerTaskManager.enqueueForExecution(this.taskName,t.getMain(),(e=>this._onLoad(e)),t.getTransferables()).then((e=>{this._onLoad(e),this.terminateWorkerOnLoad&&this.workerTaskManager.dispose()})).catch((e=>console.error(e)))}_onLoad(e){let t=e.cmd;if("assetAvailable"===t){let t;if("MeshTransport"===e.type?t=(new c).loadData(e).reconstruct(!1):console.error("Received unknown asset.type: "+e.type),t){let e,n=t.getMaterialsTransport().processMaterialTransport(this.materialStore.getMaterials(),this.parser.logging.enabled);null===n&&(n=new i.MeshStandardMaterial({color:16711680})),e=0===t.getGeometryType()?new i.Mesh(t.getBufferGeometry(),n):1===t.getGeometryType()?new i.LineSegments(t.getBufferGeometry(),n):new i.Points(t.getBufferGeometry(),n),this.parser._onMeshAlter(e),this.parser.baseObject3d.add(e)}}else if("execComplete"===t){let t;"DataTransport"===e.type?(t=(new a).loadData(e),t instanceof a&&null!==this.parser.callbacks.onLoad&&this.parser.callbacks.onLoad(this.parser.baseObject3d,t.getId())):console.error("Received unknown asset.type: "+e.type)}else console.error("Received unknown command: "+t)}}_(M,"OBJLOADER2_PARALLEL_VERSION",x.OBJLOADER2_VERSION),_(M,"DEFAULT_JSM_WORKER_PATH","/src/loaders/tmOBJLoader2.js"),_(M,"DEFAULT_JSM_THREEJS_PATH","/node_modules/three/build/three.min.js");class T{static link(e,t){"function"==typeof t.setMaterials&&t.setMaterials(T.addMaterialsFromMtlLoader(e),!0)}static addMaterialsFromMtlLoader(e){let t={};return void 0!==e.preload&&e.preload instanceof Function&&(e.preload(),t=e.materials),t}}},365:(e,t,n)=>{"use strict";n.d(t,{z:()=>o});var i=n(212);const r={type:"change"},s={type:"start"},a={type:"end"};class o extends i.EventDispatcher{constructor(e,t){super(),void 0===t&&console.warn('THREE.OrbitControls: The second parameter "domElement" is now mandatory.'),t===document&&console.error('THREE.OrbitControls: "document" should not be used as the target "domElement". Please use "renderer.domElement" instead.'),this.object=e,this.domElement=t,this.domElement.style.touchAction="none",this.enabled=!0,this.target=new i.Vector3,this.minDistance=0,this.maxDistance=1/0,this.minZoom=0,this.maxZoom=1/0,this.minPolarAngle=0,this.maxPolarAngle=Math.PI,this.minAzimuthAngle=-1/0,this.maxAzimuthAngle=1/0,this.enableDamping=!1,this.dampingFactor=.05,this.enableZoom=!0,this.zoomSpeed=1,this.enableRotate=!0,this.rotateSpeed=1,this.enablePan=!0,this.panSpeed=1,this.screenSpacePanning=!0,this.keyPanSpeed=7,this.autoRotate=!1,this.autoRotateSpeed=2,this.keys={LEFT:"ArrowLeft",UP:"ArrowUp",RIGHT:"ArrowRight",BOTTOM:"ArrowDown"},this.mouseButtons={LEFT:i.MOUSE.ROTATE,MIDDLE:i.MOUSE.DOLLY,RIGHT:i.MOUSE.PAN},this.touches={ONE:i.TOUCH.ROTATE,TWO:i.TOUCH.DOLLY_PAN},this.target0=this.target.clone(),this.position0=this.object.position.clone(),this.zoom0=this.object.zoom,this._domElementKeyEvents=null,this.getPolarAngle=function(){return h.phi},this.getAzimuthalAngle=function(){return h.theta},this.getDistance=function(){return this.object.position.distanceTo(this.target)},this.listenToKeyEvents=function(e){e.addEventListener("keydown",X),this._domElementKeyEvents=e},this.saveState=function(){n.target0.copy(n.target),n.position0.copy(n.object.position),n.zoom0=n.object.zoom},this.reset=function(){n.target.copy(n.target0),n.object.position.copy(n.position0),n.object.zoom=n.zoom0,n.object.updateProjectionMatrix(),n.dispatchEvent(r),n.update(),l=o.NONE},this.update=function(){const t=new i.Vector3,s=(new i.Quaternion).setFromUnitVectors(e.up,new i.Vector3(0,1,0)),a=s.clone().invert(),m=new i.Vector3,g=new i.Quaternion,v=2*Math.PI;return function(){const e=n.object.position;t.copy(e).sub(n.target),t.applyQuaternion(s),h.setFromVector3(t),n.autoRotate&&l===o.NONE&&A(2*Math.PI/60/60*n.autoRotateSpeed),n.enableDamping?(h.theta+=u.theta*n.dampingFactor,h.phi+=u.phi*n.dampingFactor):(h.theta+=u.theta,h.phi+=u.phi);let i=n.minAzimuthAngle,y=n.maxAzimuthAngle;return isFinite(i)&&isFinite(y)&&(i<-Math.PI?i+=v:i>Math.PI&&(i-=v),y<-Math.PI?y+=v:y>Math.PI&&(y-=v),h.theta=i<=y?Math.max(i,Math.min(y,h.theta)):h.theta>(i+y)/2?Math.max(i,h.theta):Math.min(y,h.theta)),h.phi=Math.max(n.minPolarAngle,Math.min(n.maxPolarAngle,h.phi)),h.makeSafe(),h.radius*=d,h.radius=Math.max(n.minDistance,Math.min(n.maxDistance,h.radius)),!0===n.enableDamping?n.target.addScaledVector(p,n.dampingFactor):n.target.add(p),t.setFromSpherical(h),t.applyQuaternion(a),e.copy(n.target).add(t),n.object.lookAt(n.target),!0===n.enableDamping?(u.theta*=1-n.dampingFactor,u.phi*=1-n.dampingFactor,p.multiplyScalar(1-n.dampingFactor)):(u.set(0,0,0),p.set(0,0,0)),d=1,!!(f||m.distanceToSquared(n.object.position)>c||8*(1-g.dot(n.object.quaternion))>c)&&(n.dispatchEvent(r),m.copy(n.object.position),g.copy(n.object.quaternion),f=!1,!0)}}(),this.dispose=function(){n.domElement.removeEventListener("contextmenu",Y),n.domElement.removeEventListener("pointerdown",G),n.domElement.removeEventListener("pointercancel",j),n.domElement.removeEventListener("wheel",q),n.domElement.removeEventListener("pointermove",V),n.domElement.removeEventListener("pointerup",W),null!==n._domElementKeyEvents&&n._domElementKeyEvents.removeEventListener("keydown",X)};const n=this,o={NONE:-1,ROTATE:0,DOLLY:1,PAN:2,TOUCH_ROTATE:3,TOUCH_PAN:4,TOUCH_DOLLY_PAN:5,TOUCH_DOLLY_ROTATE:6};let l=o.NONE;const c=1e-6,h=new i.Spherical,u=new i.Spherical;let d=1;const p=new i.Vector3;let f=!1;const m=new i.Vector2,g=new i.Vector2,v=new i.Vector2,y=new i.Vector2,_=new i.Vector2,x=new i.Vector2,b=new i.Vector2,w=new i.Vector2,M=new i.Vector2,T=[],E={};function S(){return Math.pow(.95,n.zoomSpeed)}function A(e){u.theta-=e}function L(e){u.phi-=e}const C=function(){const e=new i.Vector3;return function(t,n){e.setFromMatrixColumn(n,0),e.multiplyScalar(-t),p.add(e)}}(),R=function(){const e=new i.Vector3;return function(t,i){!0===n.screenSpacePanning?e.setFromMatrixColumn(i,1):(e.setFromMatrixColumn(i,0),e.crossVectors(n.object.up,e)),e.multiplyScalar(t),p.add(e)}}(),P=function(){const e=new i.Vector3;return function(t,i){const r=n.domElement;if(n.object.isPerspectiveCamera){const s=n.object.position;e.copy(s).sub(n.target);let a=e.length();a*=Math.tan(n.object.fov/2*Math.PI/180),C(2*t*a/r.clientHeight,n.object.matrix),R(2*i*a/r.clientHeight,n.object.matrix)}else n.object.isOrthographicCamera?(C(t*(n.object.right-n.object.left)/n.object.zoom/r.clientWidth,n.object.matrix),R(i*(n.object.top-n.object.bottom)/n.object.zoom/r.clientHeight,n.object.matrix)):(console.warn("WARNING: OrbitControls.js encountered an unknown camera type - pan disabled."),n.enablePan=!1)}}();function k(e){n.object.isPerspectiveCamera?d/=e:n.object.isOrthographicCamera?(n.object.zoom=Math.max(n.minZoom,Math.min(n.maxZoom,n.object.zoom*e)),n.object.updateProjectionMatrix(),f=!0):(console.warn("WARNING: OrbitControls.js encountered an unknown camera type - dolly/zoom disabled."),n.enableZoom=!1)}function N(e){n.object.isPerspectiveCamera?d*=e:n.object.isOrthographicCamera?(n.object.zoom=Math.max(n.minZoom,Math.min(n.maxZoom,n.object.zoom/e)),n.object.updateProjectionMatrix(),f=!0):(console.warn("WARNING: OrbitControls.js encountered an unknown camera type - dolly/zoom disabled."),n.enableZoom=!1)}function I(e){m.set(e.clientX,e.clientY)}function D(e){y.set(e.clientX,e.clientY)}function O(){if(1===T.length)m.set(T[0].pageX,T[0].pageY);else{const e=.5*(T[0].pageX+T[1].pageX),t=.5*(T[0].pageY+T[1].pageY);m.set(e,t)}}function B(){if(1===T.length)y.set(T[0].pageX,T[0].pageY);else{const e=.5*(T[0].pageX+T[1].pageX),t=.5*(T[0].pageY+T[1].pageY);y.set(e,t)}}function F(){const e=T[0].pageX-T[1].pageX,t=T[0].pageY-T[1].pageY,n=Math.sqrt(e*e+t*t);b.set(0,n)}function U(e){if(1==T.length)g.set(e.pageX,e.pageY);else{const t=K(e),n=.5*(e.pageX+t.x),i=.5*(e.pageY+t.y);g.set(n,i)}v.subVectors(g,m).multiplyScalar(n.rotateSpeed);const t=n.domElement;A(2*Math.PI*v.x/t.clientHeight),L(2*Math.PI*v.y/t.clientHeight),m.copy(g)}function z(e){if(1===T.length)_.set(e.pageX,e.pageY);else{const t=K(e),n=.5*(e.pageX+t.x),i=.5*(e.pageY+t.y);_.set(n,i)}x.subVectors(_,y).multiplyScalar(n.panSpeed),P(x.x,x.y),y.copy(_)}function H(e){const t=K(e),i=e.pageX-t.x,r=e.pageY-t.y,s=Math.sqrt(i*i+r*r);w.set(0,s),M.set(0,Math.pow(w.y/b.y,n.zoomSpeed)),k(M.y),b.copy(w)}function G(e){!1!==n.enabled&&(0===T.length&&(n.domElement.setPointerCapture(e.pointerId),n.domElement.addEventListener("pointermove",V),n.domElement.addEventListener("pointerup",W)),function(e){T.push(e)}(e),"touch"===e.pointerType?function(e){switch(Z(e),T.length){case 1:switch(n.touches.ONE){case i.TOUCH.ROTATE:if(!1===n.enableRotate)return;O(),l=o.TOUCH_ROTATE;break;case i.TOUCH.PAN:if(!1===n.enablePan)return;B(),l=o.TOUCH_PAN;break;default:l=o.NONE}break;case 2:switch(n.touches.TWO){case i.TOUCH.DOLLY_PAN:if(!1===n.enableZoom&&!1===n.enablePan)return;n.enableZoom&&F(),n.enablePan&&B(),l=o.TOUCH_DOLLY_PAN;break;case i.TOUCH.DOLLY_ROTATE:if(!1===n.enableZoom&&!1===n.enableRotate)return;n.enableZoom&&F(),n.enableRotate&&O(),l=o.TOUCH_DOLLY_ROTATE;break;default:l=o.NONE}break;default:l=o.NONE}l!==o.NONE&&n.dispatchEvent(s)}(e):function(e){let t;switch(e.button){case 0:t=n.mouseButtons.LEFT;break;case 1:t=n.mouseButtons.MIDDLE;break;case 2:t=n.mouseButtons.RIGHT;break;default:t=-1}switch(t){case i.MOUSE.DOLLY:if(!1===n.enableZoom)return;!function(e){b.set(e.clientX,e.clientY)}(e),l=o.DOLLY;break;case i.MOUSE.ROTATE:if(e.ctrlKey||e.metaKey||e.shiftKey){if(!1===n.enablePan)return;D(e),l=o.PAN}else{if(!1===n.enableRotate)return;I(e),l=o.ROTATE}break;case i.MOUSE.PAN:if(e.ctrlKey||e.metaKey||e.shiftKey){if(!1===n.enableRotate)return;I(e),l=o.ROTATE}else{if(!1===n.enablePan)return;D(e),l=o.PAN}break;default:l=o.NONE}l!==o.NONE&&n.dispatchEvent(s)}(e))}function V(e){!1!==n.enabled&&("touch"===e.pointerType?function(e){switch(Z(e),l){case o.TOUCH_ROTATE:if(!1===n.enableRotate)return;U(e),n.update();break;case o.TOUCH_PAN:if(!1===n.enablePan)return;z(e),n.update();break;case o.TOUCH_DOLLY_PAN:if(!1===n.enableZoom&&!1===n.enablePan)return;!function(e){n.enableZoom&&H(e),n.enablePan&&z(e)}(e),n.update();break;case o.TOUCH_DOLLY_ROTATE:if(!1===n.enableZoom&&!1===n.enableRotate)return;!function(e){n.enableZoom&&H(e),n.enableRotate&&U(e)}(e),n.update();break;default:l=o.NONE}}(e):function(e){if(!1!==n.enabled)switch(l){case o.ROTATE:if(!1===n.enableRotate)return;!function(e){g.set(e.clientX,e.clientY),v.subVectors(g,m).multiplyScalar(n.rotateSpeed);const t=n.domElement;A(2*Math.PI*v.x/t.clientHeight),L(2*Math.PI*v.y/t.clientHeight),m.copy(g),n.update()}(e);break;case o.DOLLY:if(!1===n.enableZoom)return;!function(e){w.set(e.clientX,e.clientY),M.subVectors(w,b),M.y>0?k(S()):M.y<0&&N(S()),b.copy(w),n.update()}(e);break;case o.PAN:if(!1===n.enablePan)return;!function(e){_.set(e.clientX,e.clientY),x.subVectors(_,y).multiplyScalar(n.panSpeed),P(x.x,x.y),y.copy(_),n.update()}(e)}}(e))}function W(e){!1!==n.enabled&&(e.pointerType,n.dispatchEvent(a),l=o.NONE,J(e),0===T.length&&(n.domElement.releasePointerCapture(e.pointerId),n.domElement.removeEventListener("pointermove",V),n.domElement.removeEventListener("pointerup",W)))}function j(e){J(e)}function q(e){!1===n.enabled||!1===n.enableZoom||l!==o.NONE&&l!==o.ROTATE||(e.preventDefault(),n.dispatchEvent(s),function(e){e.deltaY<0?N(S()):e.deltaY>0&&k(S()),n.update()}(e),n.dispatchEvent(a))}function X(e){!1!==n.enabled&&!1!==n.enablePan&&function(e){let t=!1;switch(e.code){case n.keys.UP:P(0,n.keyPanSpeed),t=!0;break;case n.keys.BOTTOM:P(0,-n.keyPanSpeed),t=!0;break;case n.keys.LEFT:P(n.keyPanSpeed,0),t=!0;break;case n.keys.RIGHT:P(-n.keyPanSpeed,0),t=!0}t&&(e.preventDefault(),n.update())}(e)}function Y(e){!1!==n.enabled&&e.preventDefault()}function J(e){delete E[e.pointerId];for(let t=0;t{"use strict";n.d(t,{G:()=>s});var i=n(212);class r extends i.DataTextureLoader{constructor(e){super(e)}parse(e){e.length<19&&console.error("THREE.TGALoader: Not enough data to contain header.");let t=0;const n=new Uint8Array(e),r={id_length:n[t++],colormap_type:n[t++],image_type:n[t++],colormap_index:n[t++]|n[t++]<<8,colormap_length:n[t++]|n[t++]<<8,colormap_size:n[t++],origin:[n[t++]|n[t++]<<8,n[t++]|n[t++]<<8],width:n[t++]|n[t++]<<8,height:n[t++]|n[t++]<<8,pixel_size:n[t++],flags:n[t++]};!function(e){switch(e.image_type){case 1:case 9:(e.colormap_length>256||24!==e.colormap_size||1!==e.colormap_type)&&console.error("THREE.TGALoader: Invalid type colormap data for indexed type.");break;case 2:case 3:case 10:case 11:e.colormap_type&&console.error("THREE.TGALoader: Invalid type colormap data for colormap type.");break;case 0:console.error("THREE.TGALoader: No data.");default:console.error('THREE.TGALoader: Invalid type "%s".',e.image_type)}(e.width<=0||e.height<=0)&&console.error("THREE.TGALoader: Invalid image size."),8!==e.pixel_size&&16!==e.pixel_size&&24!==e.pixel_size&&32!==e.pixel_size&&console.error('THREE.TGALoader: Invalid pixel size "%s".',e.pixel_size)}(r),r.id_length+t>e.length&&console.error("THREE.TGALoader: No data."),t+=r.id_length;let s=!1,a=!1,o=!1;switch(r.image_type){case 9:s=!0,a=!0;break;case 1:a=!0;break;case 10:s=!0;break;case 2:break;case 11:s=!0,o=!0;break;case 3:o=!0}const l=new Uint8Array(r.width*r.height*4),c=function(e,t,n,i,r){let s,a;const o=n.pixel_size>>3,l=n.width*n.height*o;if(t&&(a=r.subarray(i,i+=n.colormap_length*(n.colormap_size>>3))),e){let e,t,n;s=new Uint8Array(l);let a=0;const c=new Uint8Array(o);for(;a>4){default:case 2:a=0,c=1,u=t,l=0,h=1,d=n;break;case 0:a=0,c=1,u=t,l=n-1,h=-1,d=-1;break;case 3:a=t-1,c=-1,u=-1,l=0,h=1,d=n;break;case 1:a=t-1,c=-1,u=-1,l=n-1,h=-1,d=-1}if(o)switch(r.pixel_size){case 8:!function(e,t,n,i,s,a,o,l){let c,h,u,d=0;const p=r.width;for(u=t;u!==i;u+=n)for(h=s;h!==o;h+=a,d++)c=l[d],e[4*(h+p*u)+0]=c,e[4*(h+p*u)+1]=c,e[4*(h+p*u)+2]=c,e[4*(h+p*u)+3]=255}(e,l,h,d,a,c,u,i);break;case 16:!function(e,t,n,i,s,a,o,l){let c,h,u=0;const d=r.width;for(h=t;h!==i;h+=n)for(c=s;c!==o;c+=a,u+=2)e[4*(c+d*h)+0]=l[u+0],e[4*(c+d*h)+1]=l[u+0],e[4*(c+d*h)+2]=l[u+0],e[4*(c+d*h)+3]=l[u+1]}(e,l,h,d,a,c,u,i);break;default:console.error("THREE.TGALoader: Format not supported.")}else switch(r.pixel_size){case 8:!function(e,t,n,i,s,a,o,l,c){const h=c;let u,d,p,f=0;const m=r.width;for(p=t;p!==i;p+=n)for(d=s;d!==o;d+=a,f++)u=l[f],e[4*(d+m*p)+3]=255,e[4*(d+m*p)+2]=h[3*u+0],e[4*(d+m*p)+1]=h[3*u+1],e[4*(d+m*p)+0]=h[3*u+2]}(e,l,h,d,a,c,u,i,s);break;case 16:!function(e,t,n,i,s,a,o,l){let c,h,u,d=0;const p=r.width;for(u=t;u!==i;u+=n)for(h=s;h!==o;h+=a,d+=2)c=l[d+0]+(l[d+1]<<8),e[4*(h+p*u)+0]=(31744&c)>>7,e[4*(h+p*u)+1]=(992&c)>>2,e[4*(h+p*u)+2]=(31&c)<<3,e[4*(h+p*u)+3]=32768&c?0:255}(e,l,h,d,a,c,u,i);break;case 24:!function(e,t,n,i,s,a,o,l){let c,h,u=0;const d=r.width;for(h=t;h!==i;h+=n)for(c=s;c!==o;c+=a,u+=3)e[4*(c+d*h)+3]=255,e[4*(c+d*h)+2]=l[u+0],e[4*(c+d*h)+1]=l[u+1],e[4*(c+d*h)+0]=l[u+2]}(e,l,h,d,a,c,u,i);break;case 32:!function(e,t,n,i,s,a,o,l){let c,h,u=0;const d=r.width;for(h=t;h!==i;h+=n)for(c=s;c!==o;c+=a,u+=4)e[4*(c+d*h)+2]=l[u+0],e[4*(c+d*h)+1]=l[u+1],e[4*(c+d*h)+0]=l[u+2],e[4*(c+d*h)+3]=l[u+3]}(e,l,h,d,a,c,u,i);break;default:console.error("THREE.TGALoader: Format not supported.")}}(l,r.width,r.height,c.pixel_data,c.palettes),{data:l,width:r.width,height:r.height,flipY:!0,generateMipmaps:!0,minFilter:i.LinearMipmapLinearFilter}}}class s extends i.Loader{constructor(e){super(e)}load(e,t,n,r){const s=this,a=""===s.path?i.LoaderUtils.extractUrlBase(e):s.path,o=new i.FileLoader(s.manager);o.setPath(s.path),o.setRequestHeader(s.requestHeader),o.setWithCredentials(s.withCredentials),o.load(e,(function(n){try{t(s.parse(n,a))}catch(t){r?r(t):console.error(t),s.manager.itemError(e)}}),n,r)}parse(e,t){function n(e,t){const n=[],i=e.childNodes;for(let e=0,r=i.length;e0&&t.push(new i.VectorKeyframeTrack(r+".position",s,a)),o.length>0&&t.push(new i.QuaternionKeyframeTrack(r+".quaternion",s,o)),l.length>0&&t.push(new i.VectorKeyframeTrack(r+".scale",s,l)),t}function T(e,t,n){let i,r,s,a=!0;for(r=0,s=e.length;r=0;){const i=e[t];if(null!==i.value[n])return i;t--}return null}function S(e,t,n){for(;t>>0));switch(n=n.toLowerCase(),n){case"tga":t=qe;break;default:t=je}return t}(r);if(void 0!==t){const n=t.load(r),s=e.extra;if(void 0!==s&&void 0!==s.technique&&!1===c(s.technique)){const e=s.technique;n.wrapS=e.wrapU?i.RepeatWrapping:i.ClampToEdgeWrapping,n.wrapT=e.wrapV?i.RepeatWrapping:i.ClampToEdgeWrapping,n.offset.set(e.offsetU||0,e.offsetV||0),n.repeat.set(e.repeatU||1,e.repeatV||1)}else n.wrapS=i.RepeatWrapping,n.wrapT=i.RepeatWrapping;return n}return console.warn("THREE.ColladaLoader: Loader for texture %s not found.",r),null}return console.warn("THREE.ColladaLoader: Couldn't create texture with ID:",e.id),null}a.name=e.name||"";const l=r.parameters;for(const e in l){const t=l[e];switch(e){case"diffuse":t.color&&a.color.fromArray(t.color),t.texture&&(a.map=o(t.texture));break;case"specular":t.color&&a.specular&&a.specular.fromArray(t.color),t.texture&&(a.specularMap=o(t.texture));break;case"bump":t.texture&&(a.normalMap=o(t.texture));break;case"ambient":t.texture&&(a.lightMap=o(t.texture));break;case"shininess":t.float&&a.shininess&&(a.shininess=t.float);break;case"emission":t.color&&a.emissive&&a.emissive.fromArray(t.color),t.texture&&(a.emissiveMap=o(t.texture))}}let h=l.transparent,u=l.transparency;if(void 0===u&&h&&(u={float:1}),void 0===h&&u&&(h={opaque:"A_ONE",data:{color:[1,1,1,1]}}),h&&u)if(h.data.texture)a.transparent=!0;else{const e=h.data.color;switch(h.opaque){case"A_ONE":a.opacity=e[3]*u.float;break;case"RGB_ZERO":a.opacity=1-e[0]*u.float;break;case"A_ZERO":a.opacity=1-e[3]*u.float;break;case"RGB_ONE":a.opacity=e[0]*u.float;break;default:console.warn('THREE.ColladaLoader: Invalid opaque type "%s" of transparent tag.',h.opaque)}a.opacity<1&&(a.transparent=!0)}return void 0!==s&&void 0!==s.technique&&1===s.technique.double_sided&&(a.side=i.DoubleSide),a}function Z(e){return f(Ze.materials[e],J)}function K(e){for(let t=0;t0?n+s:n;t.inputs[a]={id:e,offset:r},t.stride=Math.max(t.stride,r+1),"TEXCOORD"===n&&(t.hasUV=!0);break;case"vcount":t.vcount=o(i.textContent);break;case"p":t.p=o(i.textContent)}}return t}function ce(e){let t=0;for(let n=0,i=e.length;n0&&t0&&d.setAttribute("position",new i.Float32BufferAttribute(s.array,s.stride)),a.array.length>0&&d.setAttribute("normal",new i.Float32BufferAttribute(a.array,a.stride)),c.array.length>0&&d.setAttribute("color",new i.Float32BufferAttribute(c.array,c.stride)),o.array.length>0&&d.setAttribute("uv",new i.Float32BufferAttribute(o.array,o.stride)),l.array.length>0&&d.setAttribute("uv2",new i.Float32BufferAttribute(l.array,l.stride)),h.length>0&&d.setAttribute("skinIndex",new i.Float32BufferAttribute(h,4)),u.length>0&&d.setAttribute("skinWeight",new i.Float32BufferAttribute(u,4)),r.data=d,r.type=e[0].type,r.materialKeys=p,r}function de(e,t,n,i){const r=e.p,s=e.stride,a=e.vcount;function o(e){let t=r[e+n]*c;const s=t+c;for(;t4)for(let t=1,i=n-2;t<=i;t++){const n=e+s*t,i=e+s*(t+1);o(e+0*s),o(n),o(i)}e+=s*n}}else for(let e=0,t=r.length;e=t.limits.max&&(t.static=!0),t.middlePosition=(t.limits.min+t.limits.max)/2,t}function ye(e){const t={sid:e.getAttribute("sid"),name:e.getAttribute("name")||"",attachments:[],transforms:[]};for(let n=0;nr.limits.max||t{"use strict";n.d(t,{v:()=>r});var i=n(212);class r extends i.Loader{constructor(e){super(e)}load(e,t,n,r){const s=this,a=""===this.path?i.LoaderUtils.extractUrlBase(e):this.path,o=new i.FileLoader(this.manager);o.setPath(this.path),o.setRequestHeader(this.requestHeader),o.setWithCredentials(this.withCredentials),o.load(e,(function(n){try{t(s.parse(n,a))}catch(t){r?r(t):console.error(t),s.manager.itemError(e)}}),n,r)}setMaterialOptions(e){return this.materialOptions=e,this}parse(e,t){const n=e.split("\\n");let i={};const r=/\\s+/,a={};for(let e=0;e=0?t.substring(0,s):t;o=o.toLowerCase();let l=s>=0?t.substring(s+1):"";if(l=l.trim(),"newmtl"===o)i={name:l},a[l]=i;else if("ka"===o||"kd"===o||"ks"===o||"ke"===o){const e=l.split(r,3);i[o]=[parseFloat(e[0]),parseFloat(e[1]),parseFloat(e[2])]}else i[o]=l}const o=new s(this.resourcePath||t,this.materialOptions);return o.setCrossOrigin(this.crossOrigin),o.setManager(this.manager),o.setMaterials(a),o}}class s{constructor(e="",t={}){this.baseUrl=e,this.options=t,this.materialsInfo={},this.materials={},this.materialsArray=[],this.nameLookup={},this.crossOrigin="anonymous",this.side=void 0!==this.options.side?this.options.side:i.FrontSide,this.wrap=void 0!==this.options.wrap?this.options.wrap:i.RepeatWrapping}setCrossOrigin(e){return this.crossOrigin=e,this}setManager(e){this.manager=e}setMaterials(e){this.materialsInfo=this.convert(e),this.materials={},this.materialsArray=[],this.nameLookup={}}convert(e){if(!this.options)return e;const t={};for(const n in e){const i=e[n],r={};t[n]=r;for(const e in i){let t=!0,n=i[e];const s=e.toLowerCase();switch(s){case"kd":case"ka":case"ks":this.options&&this.options.normalizeRGB&&(n=[n[0]/255,n[1]/255,n[2]/255]),this.options&&this.options.ignoreZeroRGBs&&0===n[0]&&0===n[1]&&0===n[2]&&(t=!1)}t&&(r[s]=n)}}return t}preload(){for(const e in this.materialsInfo)this.create(e)}getIndex(e){return this.nameLookup[e]}getAsArray(){let e=0;for(const t in this.materialsInfo)this.materialsArray[e]=this.create(t),this.nameLookup[t]=e,e++;return this.materialsArray}create(e){return void 0===this.materials[e]&&this.createMaterial_(e),this.materials[e]}createMaterial_(e){const t=this,n=this.materialsInfo[e],r={name:e,side:this.side};function s(e,n){if(r[e])return;const i=t.getTextureParams(n,r),s=t.loadTexture((a=t.baseUrl,"string"!=typeof(o=i.url)||""===o?"":/^https?:\\/\\//i.test(o)?o:a+o));var a,o;s.repeat.copy(i.scale),s.offset.copy(i.offset),s.wrapS=t.wrap,s.wrapT=t.wrap,r[e]=s}for(const e in n){const t=n[e];let a;if(""!==t)switch(e.toLowerCase()){case"kd":r.color=(new i.Color).fromArray(t);break;case"ks":r.specular=(new i.Color).fromArray(t);break;case"ke":r.emissive=(new i.Color).fromArray(t);break;case"map_kd":s("map",t);break;case"map_ks":s("specularMap",t);break;case"map_ke":s("emissiveMap",t);break;case"norm":s("normalMap",t);break;case"map_bump":case"bump":s("bumpMap",t);break;case"map_d":s("alphaMap",t),r.transparent=!0;break;case"ns":r.shininess=parseFloat(t);break;case"d":a=parseFloat(t),a<1&&(r.opacity=a,r.transparent=!0);break;case"tr":a=parseFloat(t),this.options&&this.options.invertTrProperty&&(a=1-a),a>0&&(r.opacity=1-a,r.transparent=!0)}}return this.materials[e]=new i.MeshPhongMaterial(r),this.materials[e]}getTextureParams(e,t){const n={scale:new i.Vector2(1,1),offset:new i.Vector2(0,0)},r=e.split(/\\s+/);let s;return s=r.indexOf("-bm"),s>=0&&(t.bumpScale=parseFloat(r[s+1]),r.splice(s,2)),s=r.indexOf("-s"),s>=0&&(n.scale.set(parseFloat(r[s+1]),parseFloat(r[s+2])),r.splice(s,4)),s=r.indexOf("-o"),s>=0&&(n.offset.set(parseFloat(r[s+1]),parseFloat(r[s+2])),r.splice(s,4)),n.url=r.join(" ").trim(),n}loadTexture(e,t,n,r,s){const a=void 0!==this.manager?this.manager:i.DefaultLoadingManager;let o=a.getHandler(e);null===o&&(o=new i.TextureLoader(a)),o.setCrossOrigin&&o.setCrossOrigin(this.crossOrigin);const l=o.load(e,n,r,s);return void 0!==t&&(l.mapping=t),l}}},476:(e,t,n)=>{"use strict";n.d(t,{j:()=>r});var i=n(212);class r extends i.Loader{constructor(e){super(e)}load(e,t,n,r){const s=this,a=new i.FileLoader(this.manager);a.setPath(this.path),a.setResponseType("arraybuffer"),a.setRequestHeader(this.requestHeader),a.setWithCredentials(this.withCredentials),a.load(e,(function(n){try{t(s.parse(n))}catch(t){r?r(t):console.error(t),s.manager.itemError(e)}}),n,r)}parse(e){function t(e,t,n){for(let i=0,r=e.length;i>5&31)/31,a=(e>>10&31)/31):(r=l,s=c,a=h)}for(let l=1;l<=3;l++){const c=n+12*l,h=3*e*3+3*(l-1);f[h]=t.getFloat32(c,!0),f[h+1]=t.getFloat32(c+4,!0),f[h+2]=t.getFloat32(c+8,!0),m[h]=i,m[h+1]=u,m[h+2]=p,d&&(o[h]=r,o[h+1]=s,o[h+2]=a)}}return p.setAttribute("position",new i.BufferAttribute(f,3)),p.setAttribute("normal",new i.BufferAttribute(m,3)),d&&(p.setAttribute("color",new i.BufferAttribute(o,3)),p.hasColors=!0,p.alpha=u),p}(n):function(e){const t=new i.BufferGeometry,n=/solid([\\s\\S]*?)endsolid/g,r=/facet([\\s\\S]*?)endfacet/g;let s=0;const a=/[\\s]+([+-]?(?:\\d*)(?:\\.\\d*)?(?:[eE][+-]?\\d+)?)/.source,o=new RegExp("vertex"+a+a+a,"g"),l=new RegExp("normal"+a+a+a,"g"),c=[],h=[],u=new i.Vector3;let d,p=0,f=0,m=0;for(;null!==(d=n.exec(e));){f=m;const e=d[0];for(;null!==(d=r.exec(e));){let e=0,t=0;const n=d[0];for(;null!==(d=l.exec(n));)u.x=parseFloat(d[1]),u.y=parseFloat(d[2]),u.z=parseFloat(d[3]),t++;for(;null!==(d=o.exec(n));)c.push(parseFloat(d[1]),parseFloat(d[2]),parseFloat(d[3])),h.push(u.x,u.y,u.z),e++,m++;1!==t&&console.error("THREE.STLLoader: Something isn't right with the normal of face number "+s),3!==e&&console.error("THREE.STLLoader: Something isn't right with the vertices of face number "+s),s++}const n=f,i=m-f;t.addGroup(n,i,p),p++}return t.setAttribute("position",new i.Float32BufferAttribute(c,3)),t.setAttribute("normal",new i.Float32BufferAttribute(h,3)),t}("string"!=typeof(r=e)?i.LoaderUtils.decodeText(new Uint8Array(r)):r);var r}}},140:(e,t,n)=>{}},__webpack_module_cache__={};function __webpack_require__(e){var t=__webpack_module_cache__[e];if(void 0!==t)return t.exports;var n=__webpack_module_cache__[e]={id:e,loaded:!1,exports:{}};return __webpack_modules__[e].call(n.exports,n,n.exports,__webpack_require__),n.loaded=!0,n.exports}__webpack_require__.d=(e,t)=>{for(var n in t)__webpack_require__.o(t,n)&&!__webpack_require__.o(e,n)&&Object.defineProperty(e,n,{enumerable:!0,get:t[n]})},__webpack_require__.g=function(){if("object"==typeof globalThis)return globalThis;try{return this||new Function("return this")()}catch(e){if("object"==typeof window)return window}}(),__webpack_require__.o=(e,t)=>Object.prototype.hasOwnProperty.call(e,t),__webpack_require__.r=e=>{"undefined"!=typeof Symbol&&Symbol.toStringTag&&Object.defineProperty(e,Symbol.toStringTag,{value:"Module"}),Object.defineProperty(e,"__esModule",{value:!0})},__webpack_require__.nmd=e=>(e.paths=[],e.children||(e.children=[]),e);var __webpack_exports__={};return(()=>{"use strict";__webpack_require__.r(__webpack_exports__),__webpack_require__.d(__webpack_exports__,{Viewer:()=>Viewer,THREE:()=>THREE});var three_examples_jsm_utils_BufferGeometryUtils_js__WEBPACK_IMPORTED_MODULE_2__=__webpack_require__(140),wwobjloader2__WEBPACK_IMPORTED_MODULE_0__=__webpack_require__(973),three_examples_jsm_loaders_ColladaLoader_js__WEBPACK_IMPORTED_MODULE_3__=__webpack_require__(976),three_examples_jsm_loaders_MTLLoader_js__WEBPACK_IMPORTED_MODULE_5__=__webpack_require__(23),three_examples_jsm_loaders_STLLoader_js__WEBPACK_IMPORTED_MODULE_4__=__webpack_require__(476),three_examples_jsm_controls_OrbitControls_js__WEBPACK_IMPORTED_MODULE_1__=__webpack_require__(365),THREE=__webpack_require__(212),msgpack=__webpack_require__(374),dat=__webpack_require__(376).ZP;function merge_geometries(e,t=!1){let n=[],i=[],r=e.matrix.clone();!function e(t,r){let s=r.clone().multiply(t.matrix);"Mesh"===t.type&&(t.geometry.applyMatrix4(s),i.push(t.geometry),n.push(t.material));for(let n of t.children)e(n,s)}(e,r);let s=null;return 1==i.length?(s=i[0],t&&(s.material=n[0])):i.length>1?(s=three_examples_jsm_utils_BufferGeometryUtils_js__WEBPACK_IMPORTED_MODULE_2__.BufferGeometryUtils.mergeBufferGeometries(i,!0),t&&(s.material=n)):s=new THREE.BufferGeometry,s}function handle_special_texture(e){if("_text"==e.type){let t=document.createElement("canvas");t.width=256,t.height=256;let n=t.getContext("2d");n.textAlign="center";let i=e.font_size;for(n.font=i+"px "+e.font_face;n.measureText(e.text).width>t.width;)i--,n.font=i+"px "+e.font_face;n.fillText(e.text,t.width/2,t.height/2);let r=new THREE.CanvasTexture(t);return r.uuid=e.uuid,r}return null}function handle_special_geometry(e){if("_meshfile"==e.type&&(console.warn("_meshfile is deprecated. Please use _meshfile_geometry for geometries and _meshfile_object for objects with geometry and material"),e.type="_meshfile_geometry"),"_meshfile_geometry"==e.type){if("obj"==e.format){let t=merge_geometries((new wwobjloader2__WEBPACK_IMPORTED_MODULE_0__.oe).parse(e.data+"\\n"));return t.uuid=e.uuid,t}if("dae"==e.format){let t=merge_geometries((new three_examples_jsm_loaders_ColladaLoader_js__WEBPACK_IMPORTED_MODULE_3__.G).parse(e.data).scene);return t.uuid=e.uuid,t}if("stl"==e.format){let t=(new three_examples_jsm_loaders_STLLoader_js__WEBPACK_IMPORTED_MODULE_4__.j).parse(e.data.buffer);return t.uuid=e.uuid,t}return console.error("Unsupported mesh type:",e),null}return null}__webpack_require__(583);class ExtensibleObjectLoader extends THREE.ObjectLoader{delegate(e,t,n,i){let r={};if(void 0===n)return r;let s=[];for(let t of n){let n=e(t);null!==n?r[n.uuid]=n:s.push(t)}return Object.assign(r,t(s,i))}parseTextures(e,t){return this.delegate(handle_special_texture,super.parseTextures,e,t)}parseGeometries(e,t){return this.delegate(handle_special_geometry,super.parseGeometries,e,t)}parseObject(e,t,n){if("_meshfile_object"==e.type){let t,n,i=new THREE.LoadingManager,r=void 0===e.url?void 0:THREE.LoaderUtils.extractUrlBase(e.url);if(i.setURLModifier((t=>void 0!==e.resources[t]?e.resources[t]:t)),"obj"==e.format){let s=new wwobjloader2__WEBPACK_IMPORTED_MODULE_0__.oe(i);if(e.mtl_library){let t=new three_examples_jsm_loaders_MTLLoader_js__WEBPACK_IMPORTED_MODULE_5__.v(i).parse(e.mtl_library+"\\n",""),n=wwobjloader2__WEBPACK_IMPORTED_MODULE_0__.eW.addMaterialsFromMtlLoader(t);s.setMaterials(n),this.onTextureLoad()}t=merge_geometries(s.parse(e.data+"\\n",r),!0),t.uuid=e.uuid,n=t.material}else if("dae"==e.format){let s=new three_examples_jsm_loaders_ColladaLoader_js__WEBPACK_IMPORTED_MODULE_3__.G(i);s.onTextureLoad=this.onTextureLoad,t=merge_geometries(s.parse(e.data,r).scene,!0),t.uuid=e.uuid,n=t.material}else{if("stl"!=e.format)return console.error("Unsupported mesh type:",e),null;t=(new three_examples_jsm_loaders_STLLoader_js__WEBPACK_IMPORTED_MODULE_4__.j).parse(e.data.buffer,r),t.uuid=e.uuid,n=t.material}let s=new THREE.Mesh(t,n);return s.uuid=e.uuid,void 0!==e.name&&(s.name=e.name),void 0!==e.matrix?(s.matrix.fromArray(e.matrix),void 0!==e.matrixAutoUpdate&&(s.matrixAutoUpdate=e.matrixAutoUpdate),s.matrixAutoUpdate&&s.matrix.decompose(s.position,s.quaternion,s.scale)):(void 0!==e.position&&s.position.fromArray(e.position),void 0!==e.rotation&&s.rotation.fromArray(e.rotation),void 0!==e.quaternion&&s.quaternion.fromArray(e.quaternion),void 0!==e.scale&&s.scale.fromArray(e.scale)),void 0!==e.castShadow&&(s.castShadow=e.castShadow),void 0!==e.receiveShadow&&(s.receiveShadow=e.receiveShadow),e.shadow&&(void 0!==e.shadow.bias&&(s.shadow.bias=e.shadow.bias),void 0!==e.shadow.radius&&(s.shadow.radius=e.shadow.radius),void 0!==e.shadow.mapSize&&s.shadow.mapSize.fromArray(e.shadow.mapSize),void 0!==e.shadow.camera&&(s.shadow.camera=this.parseObject(e.shadow.camera))),void 0!==e.visible&&(s.visible=e.visible),void 0!==e.frustumCulled&&(s.frustumCulled=e.frustumCulled),void 0!==e.renderOrder&&(s.renderOrder=e.renderOrder),void 0!==e.userjson&&(s.userjson=e.userData),void 0!==e.layers&&(s.layers.mask=e.layers),s}return super.parseObject(e,t,n)}}class SceneNode{constructor(e,t,n){this.object=e,this.folder=t,this.children={},this.controllers=[],this.on_update=n,this.create_controls();for(let e of this.object.children)this.add_child(e)}add_child(e){let t=this.folder.addFolder(e.name),n=new SceneNode(e,t,this.on_update);return this.children[e.name]=n,n}create_child(e){let t=new THREE.Group;return t.name=e,this.object.add(t),this.add_child(t)}find(e){if(0==e.length)return this;{let t=e[0],n=this.children[t];return void 0===n&&(n=this.create_child(t)),n.find(e.slice(1))}}create_controls(){for(let e of this.controllers)this.folder.remove(e);if(void 0!==this.vis_controller&&this.folder.domElement.removeChild(this.vis_controller.domElement),this.vis_controller=new dat.controllers.BooleanController(this.object,"visible"),this.vis_controller.onChange((()=>this.on_update())),this.folder.domElement.prepend(this.vis_controller.domElement),this.vis_controller.domElement.style.height="0",this.vis_controller.domElement.style.float="right",this.vis_controller.domElement.classList.add("meshcat-visibility-checkbox"),this.vis_controller.domElement.children[0].addEventListener("change",(e=>{e.target.checked?this.folder.domElement.classList.remove("meshcat-hidden-scene-element"):this.folder.domElement.classList.add("meshcat-hidden-scene-element")})),this.object.isLight){let e=this.folder.add(this.object,"intensity").min(0).step(.01);if(e.onChange((()=>this.on_update())),this.controllers.push(e),void 0!==this.object.castShadow){let e=this.folder.add(this.object,"castShadow");if(e.onChange((()=>this.on_update())),this.controllers.push(e),void 0!==this.object.shadow){let e=this.folder.add(this.object.shadow,"radius").min(0).step(.05).max(3);e.onChange((()=>this.on_update())),this.controllers.push(e)}}if(void 0!==this.object.distance){let e=this.folder.add(this.object,"distance").min(0).step(.1).max(100);e.onChange((()=>this.on_update())),this.controllers.push(e)}}if(this.object.isCamera){let e=this.folder.add(this.object,"zoom").min(0).step(.1);e.onChange((()=>{this.on_update()})),this.controllers.push(e)}}set_property(e,t){if("position"===e)this.object.position.set(t[0],t[1],t[2]);else if("quaternion"===e)this.object.quaternion.set(t[0],t[1],t[2],t[3]);else if("scale"===e)this.object.scale.set(t[0],t[1],t[2]);else if("color"===e){function e(t,n){if(t.material){t.material.color.setRGB(n[0],n[1],n[2]);let e=n[3];t.material.opacity=e,t.material.transparent=1!=e}for(let i of t.children)e(i,n)}e(this.object,t)}else this.object[e]="top_color"==e||"bottom_color"==e?t.map((e=>255*e)):t;this.vis_controller.updateDisplay(),this.controllers.forEach((e=>e.updateDisplay()))}set_transform(e){let t=new THREE.Matrix4;t.fromArray(e),t.decompose(this.object.position,this.object.quaternion,this.object.scale)}set_object(e){let t=this.object.parent;this.dispose_recursive(),this.object.parent.remove(this.object),this.object=e,t.add(e),this.create_controls()}dispose_recursive(){for(let e of Object.keys(this.children))this.children[e].dispose_recursive();dispose(this.object)}delete(e){if(0==e.length)console.error("Can't delete an empty path");else{let t=this.find(e.slice(0,e.length-1)),n=e[e.length-1],i=t.children[n];void 0!==i&&(i.dispose_recursive(),t.object.remove(i.object),remove_folders(i.folder),t.folder.removeFolder(i.folder),delete t.children[n])}}}function remove_folders(e){for(let t of Object.keys(e.__folders)){let n=e.__folders[t];remove_folders(n),dat.dom.dom.unbind(window,"resize",n.__resizeHandler),e.removeFolder(n)}}function dispose(e){if(e&&(e.geometry&&e.geometry.dispose(),e.material))if(Array.isArray(e.material))for(let t of e.material)t.map&&t.map.dispose(),t.dispose();else e.material.map&&e.material.map.dispose(),e.material.dispose()}function create_default_scene(){var e=new THREE.Scene;return e.name="Scene",e.rotateX(-Math.PI/2),e}function download_data_uri(e,t){let n=document.createElement("a");n.download=e,n.href=t,document.body.appendChild(n),n.click(),document.body.removeChild(n)}function download_file(e,t,n){n=n||"text/plain";let i=new Blob([t],{type:n}),r=document.createElement("a");document.body.appendChild(r),r.download=e,r.href=window.URL.createObjectURL(i),r.onclick=function(e){let t=this;setTimeout((function(){window.URL.revokeObjectURL(t.href)}),1500)},r.click(),r.remove()}class Animator{constructor(e){this.viewer=e,this.folder=this.viewer.gui.addFolder("Animations"),this.mixer=new THREE.AnimationMixer,this.loader=new THREE.ObjectLoader,this.clock=new THREE.Clock,this.actions=[],this.playing=!1,this.time=0,this.time_scrubber=null,this.setup_capturer("png"),this.duration=0}setup_capturer(e){this.capturer=new window.CCapture({format:e,name:"meshcat_"+String(Date.now())}),this.capturer.format=e}play(){this.clock.start();for(let e of this.actions)e.play();this.playing=!0}record(){this.reset(),this.play(),this.recording=!0,this.capturer.start()}pause(){this.clock.stop(),this.playing=!1,this.recording&&(this.stop_capture(),this.save_capture())}stop_capture(){this.recording=!1,this.capturer.stop(),this.viewer.animate()}save_capture(){this.capturer.save(),"png"===this.capturer.format?alert("To convert the still frames into a video, extract the `.tar` file and run: \\nffmpeg -r 60 -i %07d.png \\\\\\n\\t -vcodec libx264 \\\\\\n\\t -preset slow \\\\\\n\\t -crf 18 \\\\\\n\\t output.mp4"):"jpg"===this.capturer.format&&alert("To convert the still frames into a video, extract the `.tar` file and run: \\nffmpeg -r 60 -i %07d.jpg \\\\\\n\\t -vcodec libx264 \\\\\\n\\t -preset slow \\\\\\n\\t -crf 18 \\\\\\n\\t output.mp4")}display_progress(e){this.time=e,null!==this.time_scrubber&&this.time_scrubber.updateDisplay()}seek(e){this.actions.forEach((t=>{t.time=Math.max(0,Math.min(t._clip.duration,e))})),this.mixer.update(0),this.viewer.set_dirty()}reset(){for(let e of this.actions)e.reset();this.display_progress(0),this.mixer.update(0),this.setup_capturer(this.capturer.format),this.viewer.set_dirty()}clear(){remove_folders(this.folder),this.mixer.stopAllAction(),this.actions=[],this.duration=0,this.display_progress(0),this.mixer=new THREE.AnimationMixer}load(e,t){this.clear(),this.folder.open();let n=this.folder.addFolder("default");n.open(),n.add(this,"play"),n.add(this,"pause"),n.add(this,"reset"),this.time_scrubber=n.add(this,"time",0,1e9,.001),this.time_scrubber.onChange((e=>this.seek(e))),n.add(this.mixer,"timeScale").step(.01).min(0);let i=n.addFolder("Recording");i.add(this,"record"),i.add({format:"png"},"format",["png","jpg"]).onChange((e=>{this.setup_capturer(e)})),void 0===t.play&&(t.play=!0),void 0===t.loopMode&&(t.loopMode=THREE.LoopRepeat),void 0===t.repetitions&&(t.repetitions=1),void 0===t.clampWhenFinished&&(t.clampWhenFinished=!0),this.duration=0,this.progress=0;for(let n of e){let e=this.viewer.scene_tree.find(n.path).object,i=Object.values(this.loader.parseAnimations([n.clip]))[0],r=this.mixer.clipAction(i,e);r.clampWhenFinished=t.clampWhenFinished,r.setLoop(t.loopMode,t.repetitions),this.actions.push(r),this.duration=Math.max(this.duration,i.duration)}this.time_scrubber.min(0),this.time_scrubber.max(this.duration),this.reset(),t.play&&this.play()}update(){if(this.playing){if(this.mixer.update(this.clock.getDelta()),this.viewer.set_dirty(),0!=this.duration){let e=this.actions.reduce(((e,t)=>Math.max(e,t.time)),0);this.display_progress(e)}else this.display_progress(0);if(this.actions.every((e=>e.paused))){this.pause();for(let e of this.actions)e.reset()}}}after_render(){this.recording&&this.capturer.capture(this.viewer.renderer.domElement)}}function gradient_texture(e,t){let n=[t,e];var i=new Uint8Array(6);for(let e=0;e<2;e++){let t=n[e];for(let n=0;n<1;n++){let r=3*(1*e+n);for(let e=0;e<3;e++)i[r+e]=t[e]}}var r=new THREE.DataTexture(i,1,2,THREE.RGBFormat);return r.magFilter=THREE.LinearFilter,r.encoding=THREE.LinearEncoding,r.matrixAutoUpdate=!1,r.matrix.set(.5,0,.25,0,.5,.25,0,0,1),r.needsUpdate=!0,r}class Viewer{constructor(e,t,n){this.dom_element=e,void 0===n?(this.renderer=new THREE.WebGLRenderer({antialias:!0,alpha:!0}),this.renderer.shadowMap.enabled=!0,this.renderer.shadowMap.type=THREE.PCFSoftShadowMap,this.dom_element.appendChild(this.renderer.domElement)):this.renderer=n,this.scene=create_default_scene(),this.gui_controllers={},this.create_scene_tree(),this.add_default_scene_elements(),this.set_dirty(),this.create_camera(),this.num_messages_received=0,window.onload=e=>this.set_3d_pane_size(),window.addEventListener("resize",(e=>this.set_3d_pane_size()),!1),requestAnimationFrame((()=>this.set_3d_pane_size())),(t||void 0===t)&&this.animate()}hide_background(){this.scene.background=null,this.set_dirty()}show_background(){var e=this.scene_tree.find(["Background"]).object.top_color,t=this.scene_tree.find(["Background"]).object.bottom_color;this.scene.background=gradient_texture(e,t),this.set_dirty()}set_dirty(){this.needs_render=!0}create_camera(){let e=new THREE.Matrix4;e.makeRotationX(Math.PI/2),this.set_transform(["Cameras","default","rotated"],e.toArray());let t=new THREE.PerspectiveCamera(75,1,.01,100);this.set_camera(t),this.set_object(["Cameras","default","rotated"],t),t.position.set(3,1,0)}create_default_spot_light(){var e=new THREE.SpotLight(16777215,.8);return e.position.set(1.5,1.5,2),e.castShadow=!1,e.shadow.mapSize.width=1024,e.shadow.mapSize.height=1024,e.shadow.camera.near=.5,e.shadow.camera.far=50,e.shadow.bias=-.001,e}add_default_scene_elements(){var e=this.create_default_spot_light();this.set_object(["Lights","SpotLight"],e),this.set_property(["Lights","SpotLight"],"visible",!1);var t=new THREE.PointLight(16777215,.4);t.position.set(1.5,1.5,2),t.castShadow=!1,t.distance=10,t.shadow.mapSize.width=1024,t.shadow.mapSize.height=1024,t.shadow.camera.near=.5,t.shadow.camera.far=10,t.shadow.bias=-.001,this.set_object(["Lights","PointLightNegativeX"],t);var n=new THREE.PointLight(16777215,.4);n.position.set(-1.5,-1.5,2),n.castShadow=!1,n.distance=10,n.shadow.mapSize.width=1024,n.shadow.mapSize.height=1024,n.shadow.camera.near=.5,n.shadow.camera.far=10,n.shadow.bias=-.001,this.set_object(["Lights","PointLightPositiveX"],n);var i=new THREE.AmbientLight(16777215,.3);i.intensity=.6,this.set_object(["Lights","AmbientLight"],i);var r=new THREE.DirectionalLight(16777215,.4);r.position.set(-10,-10,0),this.set_object(["Lights","FillLight"],r);var s=new THREE.GridHelper(20,40);s.rotateX(Math.PI/2),this.set_object(["Grid"],s);var a=new THREE.AxesHelper(.5);this.set_object(["Axes"],a)}create_scene_tree(){this.gui&&this.gui.destroy(),this.gui=new dat.GUI({autoPlace:!1}),this.dom_element.parentElement.appendChild(this.gui.domElement),this.gui.domElement.style.position="absolute",this.gui.domElement.style.right=0,this.gui.domElement.style.top=0;let e=this.gui.addFolder("Scene");e.open(),this.scene_tree=new SceneNode(this.scene,e,(()=>this.set_dirty()));let t=this.gui.addFolder("Save / Load / Capture");t.add(this,"save_scene"),t.add(this,"load_scene"),t.add(this,"save_image"),this.animator=new Animator(this),this.gui.close(),this.set_property(["Background"],"top_color",[135/255,206/255,250/255]),this.set_property(["Background"],"bottom_color",[25/255,25/255,112/255]),this.scene_tree.find(["Background"]).on_update=()=>{this.scene_tree.find(["Background"]).object.visible?this.show_background():this.hide_background()},this.show_background()}set_3d_pane_size(e,t){void 0===e&&(e=this.dom_element.offsetWidth),void 0===t&&(t=window.innerHeight),"OrthographicCamera"==this.camera.type?this.camera.right=this.camera.left+e*(this.camera.top-this.camera.bottom)/t:this.camera.aspect=e/t,this.camera.updateProjectionMatrix(),this.renderer.setSize(e,t),this.set_dirty()}render(){this.controls.update(),this.camera.updateProjectionMatrix(),this.renderer.render(this.scene,this.camera),this.animator.after_render(),this.needs_render=!1}animate(){requestAnimationFrame((()=>this.animate())),this.animator.update(),this.needs_render&&this.render()}capture_image(){return this.render(),this.renderer.domElement.toDataURL()}save_image(){download_data_uri("meshcat.png",this.capture_image())}set_camera(e){this.camera=e,this.controls=new three_examples_jsm_controls_OrbitControls_js__WEBPACK_IMPORTED_MODULE_1__.z(e,this.dom_element),this.controls.enableKeys=!1,this.controls.screenSpacePanning=!0,this.controls.addEventListener("start",(()=>{this.set_dirty()})),this.controls.addEventListener("change",(()=>{this.set_dirty()}))}set_camera_from_json(e){(new ExtensibleObjectLoader).parse(e,(e=>{this.set_camera(e)}))}set_transform(e,t){this.scene_tree.find(e).set_transform(t)}set_object(e,t){this.scene_tree.find(e.concat([""])).set_object(t)}set_object_from_json(e,t){let n=new ExtensibleObjectLoader;n.onTextureLoad=()=>{this.set_dirty()},n.parse(t,(t=>{void 0!==t.geometry&&"BufferGeometry"==t.geometry.type?void 0!==t.geometry.attributes.normal&&0!==t.geometry.attributes.normal.count||t.geometry.computeVertexNormals():t.type.includes("Camera")&&(this.set_camera(t),this.set_3d_pane_size()),t.castShadow=!0,t.receiveShadow=!0,this.set_object(e,t),this.set_dirty()}))}delete_path(e){0==e.length?console.error("Deleting the entire scene is not implemented"):this.scene_tree.delete(e)}set_property(e,t,n){this.scene_tree.find(e).set_property(t,n),"Background"===e[0]&&this.scene_tree.find(e).on_update()}set_animation(e,t){t=t||{},this.animator.load(e,t)}set_control(name,callback,value,min,max,step){let handler={};name in this.gui_controllers&&this.gui.remove(this.gui_controllers[name]),void 0!==value?(handler[name]=value,this.gui_controllers[name]=this.gui.add(handler,name,min,max,step),this.gui_controllers[name].onChange(eval(callback))):(handler[name]=eval(callback),this.gui_controllers[name]=this.gui.add(handler,name))}set_control_value(e,t){e in this.gui_controllers&&this.gui_controllers[e]instanceof dat.controllers.NumberController&&(this.gui_controllers[e].setValue(t),this.gui_controllers[e].updateDisplay())}delete_control(e){e in this.gui_controllers&&(this.gui.remove(this.gui_controllers[e]),delete this.gui_controllers[e])}handle_command(e){if("set_transform"==e.type){let t=split_path(e.path);this.set_transform(t,e.matrix)}else if("delete"==e.type){let t=split_path(e.path);this.delete_path(t)}else if("set_object"==e.type){let t=split_path(e.path);this.set_object_from_json(t,e.object)}else if("set_property"==e.type){let t=split_path(e.path);this.set_property(t,e.property,e.value)}else if("set_animation"==e.type)e.animations.forEach((e=>{e.path=split_path(e.path)})),this.set_animation(e.animations,e.options);else if("set_control"==e.type)this.set_control(e.name,e.callback,e.value,e.min,e.max,e.step);else if("set_control_value"==e.type)this.set_control_value(e.name,e.value);else if("delete_control"==e.type)this.delete_control(e.name);else if("capture_image"==e.type){let e=this.capture_image();this.connection.send(JSON.stringify({type:"img",data:e}))}else"save_image"==e.type&&this.save_image();this.set_dirty()}handle_command_bytearray(e){let t=msgpack.decode(e);this.handle_command(t)}handle_command_message(e){this.num_messages_received++,this.handle_command_bytearray(new Uint8Array(e.data))}connect(e){void 0===e&&(e=`ws://${location.host}`),"https:"==location.protocol&&(e=e.replace("ws:","wss:")),this.connection=new WebSocket(e),this.connection.binaryType="arraybuffer",this.connection.onmessage=e=>this.handle_command_message(e),this.connection.onclose=function(e){console.log("onclose:",e)}}save_scene(){download_file("scene.json",JSON.stringify(this.scene.toJSON()))}load_scene_from_json(e){let t=new ExtensibleObjectLoader;t.onTextureLoad=()=>{this.set_dirty()},this.scene_tree.dispose_recursive(),this.scene=t.parse(e),this.show_background(),this.create_scene_tree();let n=this.scene_tree.find(["Cameras","default","rotated",""]);n.object.isCamera?this.set_camera(n.object):this.create_camera()}handle_load_file(e){let t=e.files[0];if(!t)return;let n=new FileReader,i=this;n.onload=function(e){let t=this.result,n=JSON.parse(t);i.load_scene_from_json(n)},n.readAsText(t)}load_scene(){let e=document.createElement("input");e.type="file",document.body.appendChild(e);let t=this;e.addEventListener("change",(function(){console.log(this,t),t.handle_load_file(this)}),!1),e.click(),e.remove()}}function split_path(e){return e.split("/").filter((e=>e.length>0))}let style=document.createElement("style");style.appendChild(document.createTextNode("")),document.head.appendChild(style),style.sheet.insertRule("\\n .meshcat-visibility-checkbox > input {\\n float: right;\\n }"),style.sheet.insertRule("\\n .meshcat-hidden-scene-element li .meshcat-visibility-checkbox {\\n opacity: 0.25;\\n pointer-events: none;\\n }"),style.sheet.insertRule("\\n .meshcat-visibility-checkbox > input[type=checkbox] {\\n height: 16px;\\n width: 16px;\\n display:inline-block;\\n padding: 0 0 0 0px;\\n }")})(),__webpack_exports__})()}));\n", " \n", " \n", " ' scripts_js = re.findall(pattern % '(.*)', html_content) for file in scripts_js: file_path = os.path.join(viewer_url, file) - js_content = urllib.request.urlopen( - file_path).read().decode() + js_content = urlopen(file_path).read().decode() html_content = html_content.replace(pattern % file, f""" """) + # Provide websocket URL as fallback if needed. It would be + # the case if the environment is not jupyter-notebook nor + # colab but rather japyterlab or vscode for instance. + web_url = f"ws://{urlparse(viewer_url).netloc}" + html_content = html_content.replace( + "var ws_url = undefined;", f'var ws_url = "{web_url}";') + if interactive_mode() == 1: # Embed HTML in iframe on Jupyter, since it is not # possible to load HTML/Javascript content directly. @@ -883,8 +889,9 @@ def has_gui() -> bool: if Viewer.backend == 'meshcat': comm_manager = Viewer._backend_obj.comm_manager if comm_manager is not None: - Viewer.wait(require_client=False) - Viewer._has_gui = comm_manager.n_comm > 0 + ack = Viewer._backend_obj.wait(require_client=False) + Viewer._has_gui = any([ + msg == "meshcat:ok" for msg in ack.split(",")]) return Viewer._has_gui return False From e010cdda0e0c8e4bb9ca176b8b066c7295fa875c Mon Sep 17 00:00:00 2001 From: Alexis Duburcq Date: Sun, 5 Sep 2021 12:55:52 +0200 Subject: [PATCH 8/8] [misc] Update release Patch tag. --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 97cc4dd51..bb9781a17 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.10) # Set the build version -set(BUILD_VERSION 1.6.29) +set(BUILD_VERSION 1.6.30) # Set compatibility if(CMAKE_VERSION VERSION_GREATER "3.11.0")